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.
MockDriver.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#pragma once
17
18#include <ros/ros.h>
19#include <string>
20#include <vector>
21#include <boost/shared_ptr.hpp>
22#include <cav_msgs/DriverStatus.h>
23
28
29namespace mock_drivers
30{
40{
41protected:
42 // Helper typedefs for child classes
43 template <class T>
44 using ConstPtr = boost::shared_ptr<const T>;
45
46 template <class T>
47 using ConstPtrRef = const ConstPtr<T>&;
48
49 template <class T>
50 using ROSCommsPtr = boost::shared_ptr<ROSComms<T>>;
51
52 template <class T>
54
55 template <class T>
57
58 // Member variables
59 MockDriverNode mock_driver_node_; // Node to use as pub/sub interface
60
61 // Prefix which child classes can apply to their topics to identify bag subscriptions. This is meant to be used when
62 // we are subscribing using the addPassthrough functions
63 const std::string bag_prefix_ = "/bag/hardware_interface/";
64
65 const std::string driver_discovery_topic_ = "driver_discovery";
66
68 boost::make_shared<ROSComms<cav_msgs::DriverStatus>>(CommTypes::pub, false, 10, driver_discovery_topic_);
69
70 ros::Time last_discovery_pub_ = ros::Time(0);
71
78 virtual bool onSpin();
79
87 virtual int onRun() = 0;
88
92 void driverDiscovery();
93
96
114 template <typename T>
115 void addPassthroughPub(const std::string& sub_topic, const std::string& pub_topic, bool latch, size_t queue_size);
116
134 template <typename T>
135 void addPassthroughPubNoHeader(const std::string& sub_topic, const std::string& pub_topic, bool latch,
136 size_t queue_size);
137
138public:
139 virtual ~MockDriver() = 0;
140
148 int run();
149
156 virtual std::vector<DriverType> getDriverTypes() = 0;
157
164 virtual uint8_t getDriverStatus() = 0;
165
171 virtual unsigned int getRate() = 0;
172
178 bool spinCallback();
179};
180
181} // namespace mock_drivers
182
183#include "impl/MockDriver.tpp" // Include for templated function implementations
Node class which connects to the ROS network.
The template node for the mock drivers that will handle all of the default driver logic.
Definition: MockDriver.h:40
MockDriverNode getMockDriverNode() const
Returns the mock driver node for the mock driver (used for testing)
Definition: MockDriver.cpp:25
virtual int onRun()=0
Pure virtual method which must be implemented by child classes. This method will be run once at start...
virtual bool onSpin()
Virtual method which child classes can override to add functionality which will occur during each spi...
Definition: MockDriver.cpp:30
ros::Time last_discovery_pub_
Definition: MockDriver.h:70
const std::string driver_discovery_topic_
Definition: MockDriver.h:65
const std::string bag_prefix_
Definition: MockDriver.h:63
ROSCommsPtr< cav_msgs::DriverStatus > driver_discovery_pub_ptr_
Definition: MockDriver.h:67
MockDriverNode mock_driver_node_
Definition: MockDriver.h:59
boost::shared_ptr< ROSComms< T > > ROSCommsPtr
Definition: MockDriver.h:50
void driverDiscovery()
Helper function to publish the driver discovery message.
Definition: MockDriver.cpp:63
bool spinCallback()
Callback which will be triggered at the rate specified by getRate(). This callback will also trigger ...
Definition: MockDriver.cpp:53
int run()
A function to initialize the publishers and subsricers and start the node. In child classes,...
Definition: MockDriver.cpp:35
void addPassthroughPub(const std::string &sub_topic, const std::string &pub_topic, bool latch, size_t queue_size)
Function adds both a publisher and subscriber of the specified type. This means a passthrough subscri...
void addPassthroughPubNoHeader(const std::string &sub_topic, const std::string &pub_topic, bool latch, size_t queue_size)
Function adds both a publisher and subscriber of the specified type. This means a passthrough subscri...
ROSCommsPtr< ConstPtrRef< T > > ConstPtrRefROSCommsPtr
Definition: MockDriver.h:56
boost::shared_ptr< const T > ConstPtr
Definition: MockDriver.h:44
virtual unsigned int getRate()=0
Pure virtual method that returns the desired operational rate of a child class.
virtual std::vector< DriverType > getDriverTypes()=0
Pure Virtual method which child classes must override that returns the list of all driver types that ...
const ConstPtr< T > & ConstPtrRef
Definition: MockDriver.h:47
virtual uint8_t getDriverStatus()=0
Pure Virtual method. Returns an integer value which corresponds to the cav_msgs/DriverStatus enum fel...
This class is used to transfer all the information required to initialize ros topics/services.
Definition: ROSComms.h:34