Carma-platform v4.2.0
CARMA Platform is built on robot operating system (ROS) and utilizes open source software (OSS) that enables Cooperative Driving Automation (CDA) features to allow Automated Driving Systems to interact and cooperate with infrastructure and other vehicles through communication.
MockCameraDriver.h
Go to the documentation of this file.
1/*
2 * Copyright (C) 2020-2021 LEIDOS.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License"); you may not
5 * use this file except in compliance with the License. You may obtain a copy of
6 * the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
12 * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
13 * License for the specific language governing permissions and limitations under
14 * the License.
15 */
16
17#pragma once
18
20#include <sensor_msgs/CameraInfo.h>
21#include <sensor_msgs/Image.h>
22#include <autoware_msgs/ProjectionMatrix.h>
23
24namespace mock_drivers
25{
28{
29private:
30 const std::string camera_info_topic_ = "camera/camera_info";
31 const std::string image_raw_topic_ = "camera/image_raw";
32 const std::string image_rects_topic_ = "camera/image_rect";
33 const std::string projection_matrix_topic_ = "camera/projection_matrix";
34
35protected:
36 int onRun() override;
37public:
38 MockCameraDriver(bool dummy = false);
40 std::vector<DriverType> getDriverTypes() override;
41 uint8_t getDriverStatus() override;
42 unsigned int getRate() override;
43
44};
45
46} // namespace mock_drivers
Mock camera driver. Operates as a passthrough for bag data which updates the timestamps on received m...
const std::string image_raw_topic_
int onRun() override
Pure virtual method which must be implemented by child classes. This method will be run once at start...
const std::string camera_info_topic_
unsigned int getRate() override
Pure virtual method that returns the desired operational rate of a child class.
const std::string projection_matrix_topic_
std::vector< DriverType > getDriverTypes() override
Pure Virtual method which child classes must override that returns the list of all driver types that ...
uint8_t getDriverStatus() override
Pure Virtual method. Returns an integer value which corresponds to the cav_msgs/DriverStatus enum fel...
const std::string image_rects_topic_
The template node for the mock drivers that will handle all of the default driver logic.
Definition: MockDriver.h:40