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.
mock_drivers::MockDriver Class Referenceabstract

The template node for the mock drivers that will handle all of the default driver logic. More...

#include <MockDriver.h>

Inheritance diagram for mock_drivers::MockDriver:
Inheritance graph
Collaboration diagram for mock_drivers::MockDriver:
Collaboration graph

Public Member Functions

virtual ~MockDriver ()=0
 
int run ()
 A function to initialize the publishers and subsricers and start the node. In child classes, this function will trigger a call to onRun(). More...
 
virtual std::vector< DriverTypegetDriverTypes ()=0
 Pure Virtual method which child classes must override that returns the list of all driver types that class implements. More...
 
virtual uint8_t getDriverStatus ()=0
 Pure Virtual method. Returns an integer value which corresponds to the cav_msgs/DriverStatus enum felids representing the status of the driver. More...
 
virtual unsigned int getRate ()=0
 Pure virtual method that returns the desired operational rate of a child class. More...
 
bool spinCallback ()
 Callback which will be triggered at the rate specified by getRate(). This callback will also trigger the onSpin() method. More...
 

Protected Types

template<class T >
using ConstPtr = boost::shared_ptr< const T >
 
template<class T >
using ConstPtrRef = const ConstPtr< T > &
 
template<class T >
using ROSCommsPtr = boost::shared_ptr< ROSComms< T > >
 
template<class T >
using ConstPtrRefROSComms = ROSComms< ConstPtrRef< T > >
 
template<class T >
using ConstPtrRefROSCommsPtr = ROSCommsPtr< ConstPtrRef< T > >
 

Protected Member Functions

virtual bool onSpin ()
 Virtual method which child classes can override to add functionality which will occur during each spin loop. This means this function will be nominally called at the rate specified by getRate() More...
 
virtual int onRun ()=0
 Pure virtual method which must be implemented by child classes. This method will be run once at startup. Child classes should add pub/sub initialization in this method implementation. More...
 
void driverDiscovery ()
 Helper function to publish the driver discovery message. More...
 
MockDriverNode getMockDriverNode () const
 Returns the mock driver node for the mock driver (used for testing) More...
 
template<typename T >
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 subscription has been created. This version of the method should be used for message types which contain a Header at the field "header". The header field will be automatically updated to the current ros::Time::now(). More...
 
template<typename T >
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 subscription has been created. This version of the method should be used for message types which does NOT contain a Header at the field "header". More...
 

Protected Attributes

MockDriverNode mock_driver_node_
 
const std::string bag_prefix_ = "/bag/hardware_interface/"
 
const std::string driver_discovery_topic_ = "driver_discovery"
 
ROSCommsPtr< cav_msgs::DriverStatus > driver_discovery_pub_ptr_
 
ros::Time last_discovery_pub_ = ros::Time(0)
 

Detailed Description

The template node for the mock drivers that will handle all of the default driver logic.

This class has virtual functions that define what to do when the mock driver is run.

It will also have build in default mock driver publishers and subscribers baked in, such as the driver discovery publisher.

Definition at line 39 of file MockDriver.h.

Member Typedef Documentation

◆ ConstPtr

template<class T >
using mock_drivers::MockDriver::ConstPtr = boost::shared_ptr<const T>
protected

Definition at line 44 of file MockDriver.h.

◆ ConstPtrRef

template<class T >
using mock_drivers::MockDriver::ConstPtrRef = const ConstPtr<T>&
protected

Definition at line 47 of file MockDriver.h.

◆ ConstPtrRefROSComms

template<class T >
using mock_drivers::MockDriver::ConstPtrRefROSComms = ROSComms<ConstPtrRef<T> >
protected

Definition at line 53 of file MockDriver.h.

◆ ConstPtrRefROSCommsPtr

Definition at line 56 of file MockDriver.h.

◆ ROSCommsPtr

template<class T >
using mock_drivers::MockDriver::ROSCommsPtr = boost::shared_ptr<ROSComms<T> >
protected

Definition at line 50 of file MockDriver.h.

Constructor & Destructor Documentation

◆ ~MockDriver()

mock_drivers::MockDriver::~MockDriver ( )
pure virtual

Definition at line 21 of file MockDriver.cpp.

22{
23}

Member Function Documentation

◆ addPassthroughPub()

template<typename T >
void mock_drivers::MockDriver::addPassthroughPub ( const std::string &  sub_topic,
const std::string &  pub_topic,
bool  latch,
size_t  queue_size 
)
protected

Function adds both a publisher and subscriber of the specified type. This means a passthrough subscription has been created. This version of the method should be used for message types which contain a Header at the field "header". The header field will be automatically updated to the current ros::Time::now().

Template Parameters
TROS message type which the provided topic name applies to. Should be the base type only such as sensor_msgs/NavSatFix
Parameters
sub_topicThe topic name to subscribe to.
pub_topicThe topic name to publish to.
latchFlag idicating if the output publisher should be latched.
queue_sizeThe size of the queue to use both for the publisher and subscriber

TODO: This function can be combined with addPassthroughPubNoHeader using C++ 17's constexpr if statements.

◆ addPassthroughPubNoHeader()

template<typename T >
void mock_drivers::MockDriver::addPassthroughPubNoHeader ( const std::string &  sub_topic,
const std::string &  pub_topic,
bool  latch,
size_t  queue_size 
)
protected

Function adds both a publisher and subscriber of the specified type. This means a passthrough subscription has been created. This version of the method should be used for message types which does NOT contain a Header at the field "header".

Template Parameters
TROS message type which the provided topic name applies to. Should be the base type only such as sensor_msgs/NavSatFix
Parameters
sub_topicThe topic name to subscribe to.
pub_topicThe topic name to publish to.
latchFlag idicating if the output publisher should be latched.
queue_sizeThe size of the queue to use both for the publisher and subscriber

TODO: This function can be combined with addPassthroughPub using C++ 17's constexpr if statements.

◆ driverDiscovery()

void mock_drivers::MockDriver::driverDiscovery ( )
protected

Helper function to publish the driver discovery message.

Definition at line 63 of file MockDriver.cpp.

64{
65 cav_msgs::DriverStatus discovery_msg;
66
67 discovery_msg.name = mock_driver_node_.getGraphName();
68 discovery_msg.status = getDriverStatus();
69
70 for (DriverType type : getDriverTypes())
71 {
72 switch (type)
73 {
74 case DriverType::CAN:
75 discovery_msg.can = true;
76 break;
78 discovery_msg.radar = true;
79 break;
81 discovery_msg.gnss = true;
82 break;
84 discovery_msg.lidar = true;
85 break;
87 discovery_msg.roadway_sensor = true;
88 break;
90 discovery_msg.comms = true;
91 break;
93 discovery_msg.controller = true;
94 break;
96 discovery_msg.camera = true;
97 break;
98 case DriverType::IMU:
99 discovery_msg.imu = true;
100 break;
102 discovery_msg.trailer_angle_sensor = true;
103 break;
105 discovery_msg.lightbar = true;
106 break;
107
108 default:
109 std::invalid_argument("Unsupported DriverType provided by getDriverTypes");
110 break;
111 }
112 }
113
114 mock_driver_node_.publishDataNoHeader<cav_msgs::DriverStatus>(driver_discovery_topic_, discovery_msg);
115}
DriverType
Enum defining the different possible types of drivers.
Definition: DriverType.h:22
@ TRAILER_ANGLE_SENSOR
std::string getGraphName() const
Returns the fully qualified name of this node in the ROS network graph.
void publishDataNoHeader(std::string topic, T msg)
Publish data with no header on a desired topic.
const std::string driver_discovery_topic_
Definition: MockDriver.h:65
MockDriverNode mock_driver_node_
Definition: MockDriver.h:59
virtual std::vector< DriverType > getDriverTypes()=0
Pure Virtual method which child classes must override that returns the list of all driver types that ...
virtual uint8_t getDriverStatus()=0
Pure Virtual method. Returns an integer value which corresponds to the cav_msgs/DriverStatus enum fel...

References CAMERA, CAN, COMMS, CONTROLLER, driver_discovery_topic_, getDriverStatus(), getDriverTypes(), mock_drivers::MockDriverNode::getGraphName(), GNSS, IMU, LIDAR, LIGHTBAR, mock_driver_node_, mock_drivers::MockDriverNode::publishDataNoHeader(), RADAR, ROADWAY_SENSOR, and TRAILER_ANGLE_SENSOR.

Referenced by spinCallback().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getDriverStatus()

virtual uint8_t mock_drivers::MockDriver::getDriverStatus ( )
pure virtual

Pure Virtual method. Returns an integer value which corresponds to the cav_msgs/DriverStatus enum felids representing the status of the driver.

Returns
Integer value which must match one of the enum fields in cav_msgs/DriverStatus

Implemented in mock_drivers::MockCameraDriver, mock_drivers::MockCANDriver, mock_drivers::MockCommsDriver, mock_drivers::MockControllerDriver, mock_drivers::MockGNSSDriver, mock_drivers::MockIMUDriver, mock_drivers::MockLidarDriver, mock_drivers::MockRadarDriver, and mock_drivers::MockRoadwaySensorDriver.

Referenced by driverDiscovery().

Here is the caller graph for this function:

◆ getDriverTypes()

virtual std::vector< DriverType > mock_drivers::MockDriver::getDriverTypes ( )
pure virtual

Pure Virtual method which child classes must override that returns the list of all driver types that class implements.

Returns
A list of DriverType that defines the interfaces the implementing class provides

Implemented in mock_drivers::MockCameraDriver, mock_drivers::MockCANDriver, mock_drivers::MockCommsDriver, mock_drivers::MockControllerDriver, mock_drivers::MockGNSSDriver, mock_drivers::MockIMUDriver, mock_drivers::MockLidarDriver, mock_drivers::MockRadarDriver, and mock_drivers::MockRoadwaySensorDriver.

Referenced by driverDiscovery().

Here is the caller graph for this function:

◆ getMockDriverNode()

MockDriverNode mock_drivers::MockDriver::getMockDriverNode ( ) const
protected

Returns the mock driver node for the mock driver (used for testing)

Definition at line 25 of file MockDriver.cpp.

26{
27 return mock_driver_node_;
28}

References mock_driver_node_.

◆ getRate()

virtual unsigned int mock_drivers::MockDriver::getRate ( )
pure virtual

Pure virtual method that returns the desired operational rate of a child class.

Returns
Spin rate in Hz

Implemented in mock_drivers::MockCameraDriver, mock_drivers::MockCANDriver, mock_drivers::MockCommsDriver, mock_drivers::MockControllerDriver, mock_drivers::MockGNSSDriver, mock_drivers::MockIMUDriver, mock_drivers::MockLidarDriver, mock_drivers::MockRadarDriver, and mock_drivers::MockRoadwaySensorDriver.

Referenced by run().

Here is the caller graph for this function:

◆ onRun()

virtual int mock_drivers::MockDriver::onRun ( )
protectedpure virtual

Pure virtual method which must be implemented by child classes. This method will be run once at startup. Child classes should add pub/sub initialization in this method implementation.

Returns
An integer error code. A non-zero value will indicate an initialization failure and result in node shutdown.

Implemented in mock_drivers::MockCameraDriver, mock_drivers::MockCANDriver, mock_drivers::MockCommsDriver, mock_drivers::MockControllerDriver, mock_drivers::MockGNSSDriver, mock_drivers::MockIMUDriver, mock_drivers::MockLidarDriver, mock_drivers::MockRadarDriver, and mock_drivers::MockRoadwaySensorDriver.

Referenced by run().

Here is the caller graph for this function:

◆ onSpin()

bool mock_drivers::MockDriver::onSpin ( )
protectedvirtual

Virtual method which child classes can override to add functionality which will occur during each spin loop. This means this function will be nominally called at the rate specified by getRate()

Returns
Return false if this node should shutdown. True otherwise.

Reimplemented in mock_drivers::MockControllerDriver.

Definition at line 30 of file MockDriver.cpp.

31{
32 return true;
33}

Referenced by spinCallback().

Here is the caller graph for this function:

◆ run()

int mock_drivers::MockDriver::run ( )

A function to initialize the publishers and subsricers and start the node. In child classes, this function will trigger a call to onRun().

Returns
An integer error code. A non-zero value will indicate an initialization failure and result in node shutdown.

Definition at line 35 of file MockDriver.cpp.

35 {
37
38 // driver discovery publisher
41
42 int return_val = onRun();
43
44 if (return_val != 0) {
45 return return_val;
46 }
47
49
50 return 0;
51}
void spin(double rate) const
Begin the ros node.
void setSpinCallback(std::function< bool()> cb) const
Set the spin callback for the ros node.
void init()
Initialize the CARMA Node Handle pointer for the MockDriverNode (must be called before spin)
void addPub(T comm)
Function to add a publisher from a ROSComms object.
virtual int onRun()=0
Pure virtual method which must be implemented by child classes. This method will be run once at start...
ROSCommsPtr< cav_msgs::DriverStatus > driver_discovery_pub_ptr_
Definition: MockDriver.h:67
bool spinCallback()
Callback which will be triggered at the rate specified by getRate(). This callback will also trigger ...
Definition: MockDriver.cpp:53
virtual unsigned int getRate()=0
Pure virtual method that returns the desired operational rate of a child class.

References mock_drivers::MockDriverNode::addPub(), driver_discovery_pub_ptr_, getRate(), mock_drivers::MockDriverNode::init(), mock_driver_node_, onRun(), mock_drivers::MockDriverNode::setSpinCallback(), mock_drivers::MockDriverNode::spin(), and spinCallback().

Referenced by main().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ spinCallback()

bool mock_drivers::MockDriver::spinCallback ( )

Callback which will be triggered at the rate specified by getRate(). This callback will also trigger the onSpin() method.

Returns
False if this node should shutdown. True otherwise.

Definition at line 53 of file MockDriver.cpp.

54{
55 if (last_discovery_pub_ == ros::Time(0) || (ros::Time::now() - last_discovery_pub_).toSec() > 0.95)
56 {
58 last_discovery_pub_ = ros::Time::now();
59 }
60 return onSpin();
61}
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
void driverDiscovery()
Helper function to publish the driver discovery message.
Definition: MockDriver.cpp:63

References driverDiscovery(), last_discovery_pub_, and onSpin().

Referenced by run().

Here is the call graph for this function:
Here is the caller graph for this function:

Member Data Documentation

◆ bag_prefix_

◆ driver_discovery_pub_ptr_

ROSCommsPtr<cav_msgs::DriverStatus> mock_drivers::MockDriver::driver_discovery_pub_ptr_
protected
Initial value:
=
boost::make_shared<ROSComms<cav_msgs::DriverStatus>>(CommTypes::pub, false, 10, driver_discovery_topic_)

Definition at line 67 of file MockDriver.h.

Referenced by run().

◆ driver_discovery_topic_

const std::string mock_drivers::MockDriver::driver_discovery_topic_ = "driver_discovery"
protected

Definition at line 65 of file MockDriver.h.

Referenced by driverDiscovery().

◆ last_discovery_pub_

ros::Time mock_drivers::MockDriver::last_discovery_pub_ = ros::Time(0)
protected

Definition at line 70 of file MockDriver.h.

Referenced by spinCallback().

◆ mock_driver_node_


The documentation for this class was generated from the following files: