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.cpp
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
18
19namespace mock_drivers
20{
21std::vector<DriverType> MockCameraDriver::getDriverTypes()
22{
23 return { DriverType::CAMERA };
24}
25
27{
28 return cav_msgs::DriverStatus::OPERATIONAL;
29}
30
32{
34}
35
37{
38 return 20; // 20 Hz as default spin rate to surpass AVT vimba driver rate of 19Hz
39}
40
42{
43 addPassthroughPub<sensor_msgs::CameraInfo>(bag_prefix_ + camera_info_topic_, camera_info_topic_, false, 10);
44 addPassthroughPub<sensor_msgs::Image>(bag_prefix_ + image_raw_topic_, image_raw_topic_, false, 10);
45 addPassthroughPub<sensor_msgs::Image>(bag_prefix_ + image_rects_topic_, image_rects_topic_, false, 10);
46 addPassthroughPub<autoware_msgs::ProjectionMatrix>(bag_prefix_ + projection_matrix_topic_, projection_matrix_topic_,
47 false, 10);
48
49 return 0;
50}
51
52} // namespace mock_drivers
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_
Node class which connects to the ROS network.
const std::string bag_prefix_
Definition: MockDriver.h:63
MockDriverNode mock_driver_node_
Definition: MockDriver.h:59