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.
|
The template node for the mock drivers that will handle all of the default driver logic. More...
#include <MockDriver.h>
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< DriverType > | getDriverTypes ()=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) |
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.
|
protected |
Definition at line 44 of file MockDriver.h.
|
protected |
Definition at line 47 of file MockDriver.h.
|
protected |
Definition at line 53 of file MockDriver.h.
|
protected |
Definition at line 56 of file MockDriver.h.
|
protected |
Definition at line 50 of file MockDriver.h.
|
pure virtual |
Definition at line 21 of file MockDriver.cpp.
|
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().
T | ROS message type which the provided topic name applies to. Should be the base type only such as sensor_msgs/NavSatFix |
sub_topic | The topic name to subscribe to. |
pub_topic | The topic name to publish to. |
latch | Flag idicating if the output publisher should be latched. |
queue_size | The 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.
|
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".
T | ROS message type which the provided topic name applies to. Should be the base type only such as sensor_msgs/NavSatFix |
sub_topic | The topic name to subscribe to. |
pub_topic | The topic name to publish to. |
latch | Flag idicating if the output publisher should be latched. |
queue_size | The 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.
|
protected |
Helper function to publish the driver discovery message.
Definition at line 63 of file MockDriver.cpp.
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().
|
pure virtual |
Pure Virtual method. Returns an integer value which corresponds to the cav_msgs/DriverStatus enum felids representing the status of the driver.
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().
|
pure virtual |
Pure Virtual method which child classes must override that returns the list of all driver types that class implements.
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().
|
protected |
Returns the mock driver node for the mock driver (used for testing)
Definition at line 25 of file MockDriver.cpp.
References mock_driver_node_.
|
pure virtual |
Pure virtual method that returns the desired operational rate of a child class.
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().
|
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.
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().
|
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()
Reimplemented in mock_drivers::MockControllerDriver.
Definition at line 30 of file MockDriver.cpp.
Referenced by spinCallback().
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().
Definition at line 35 of file MockDriver.cpp.
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().
bool mock_drivers::MockDriver::spinCallback | ( | ) |
Callback which will be triggered at the rate specified by getRate(). This callback will also trigger the onSpin() method.
Definition at line 53 of file MockDriver.cpp.
References driverDiscovery(), last_discovery_pub_, and onSpin().
Referenced by run().
|
protected |
Definition at line 63 of file MockDriver.h.
Referenced by mock_drivers::MockCameraDriver::onRun(), mock_drivers::MockCANDriver::onRun(), mock_drivers::MockCommsDriver::onRun(), mock_drivers::MockGNSSDriver::onRun(), mock_drivers::MockIMUDriver::onRun(), mock_drivers::MockLidarDriver::onRun(), mock_drivers::MockRadarDriver::onRun(), and mock_drivers::MockRoadwaySensorDriver::onRun().
|
protected |
Definition at line 67 of file MockDriver.h.
Referenced by run().
|
protected |
Definition at line 65 of file MockDriver.h.
Referenced by driverDiscovery().
|
protected |
Definition at line 70 of file MockDriver.h.
Referenced by spinCallback().
|
protected |
Definition at line 59 of file MockDriver.h.
Referenced by mock_drivers::MockCameraDriver::MockCameraDriver(), mock_drivers::MockCANDriver::MockCANDriver(), mock_drivers::MockCommsDriver::MockCommsDriver(), mock_drivers::MockControllerDriver::MockControllerDriver(), mock_drivers::MockGNSSDriver::MockGNSSDriver(), mock_drivers::MockIMUDriver::MockIMUDriver(), mock_drivers::MockLidarDriver::MockLidarDriver(), mock_drivers::MockRadarDriver::MockRadarDriver(), mock_drivers::MockRoadwaySensorDriver::MockRoadwaySensorDriver(), driverDiscovery(), getMockDriverNode(), mock_drivers::MockCommsDriver::onRun(), mock_drivers::MockControllerDriver::onRun(), mock_drivers::MockControllerDriver::onSpin(), and run().