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::MockCommsDriver Class Reference

Mock Comms driver. Operates as a passthrough for bag data which updates the timestamps on received messages. More...

#include <MockCommsDriver.h>

Inheritance diagram for mock_drivers::MockCommsDriver:
Inheritance graph
Collaboration diagram for mock_drivers::MockCommsDriver:
Collaboration graph

Public Member Functions

 MockCommsDriver (bool dummy=false)
 
 ~MockCommsDriver ()
 
std::vector< DriverTypegetDriverTypes () override
 Pure Virtual method which child classes must override that returns the list of all driver types that class implements. More...
 
uint8_t getDriverStatus () override
 Pure Virtual method. Returns an integer value which corresponds to the cav_msgs/DriverStatus enum felids representing the status of the driver. More...
 
unsigned int getRate () override
 Pure virtual method that returns the desired operational rate of a child class. More...
 
- Public Member Functions inherited from mock_drivers::MockDriver
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 Member Functions

int onRun () override
 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...
 
- Protected Member Functions inherited from mock_drivers::MockDriver
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...
 

Private Member Functions

void outboundCallback (const cav_msgs::ByteArray::ConstPtr &msg) const
 

Private Attributes

ConstPtrRefROSCommsPtr< cav_msgs::ByteArray > outbound_sub_ptr_
 
const std::string inbound_binary_topic_ = "comms/inbound_binary_msg"
 
const std::string outbound_binary_topic_ = "comms/outbound_binary_msg"
 

Additional Inherited Members

- Protected Types inherited from mock_drivers::MockDriver
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 Attributes inherited from mock_drivers::MockDriver
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

Mock Comms driver. Operates as a passthrough for bag data which updates the timestamps on received messages.

Definition at line 25 of file MockCommsDriver.h.

Constructor & Destructor Documentation

◆ MockCommsDriver()

mock_drivers::MockCommsDriver::MockCommsDriver ( bool  dummy = false)

Definition at line 36 of file MockCommsDriver.cpp.

37{
38 mock_driver_node_ = MockDriverNode(dummy);
39
40 std::function<void(const cav_msgs::ByteArray::ConstPtr&)> outbound_ptr =
41 std::bind(&MockCommsDriver::outboundCallback, this, std::placeholders::_1);
42 outbound_sub_ptr_ = boost::make_shared<ConstPtrRefROSComms<cav_msgs::ByteArray>>(outbound_ptr, CommTypes::sub, false,
44}
const std::string outbound_binary_topic_
ConstPtrRefROSCommsPtr< cav_msgs::ByteArray > outbound_sub_ptr_
void outboundCallback(const cav_msgs::ByteArray::ConstPtr &msg) const
MockDriverNode mock_driver_node_
Definition: MockDriver.h:59

References mock_drivers::MockDriver::mock_driver_node_, outbound_binary_topic_, outbound_sub_ptr_, outboundCallback(), and sub.

Here is the call graph for this function:

◆ ~MockCommsDriver()

mock_drivers::MockCommsDriver::~MockCommsDriver ( )
inline

Definition at line 40 of file MockCommsDriver.h.

40{};

Member Function Documentation

◆ getDriverStatus()

uint8_t mock_drivers::MockCommsDriver::getDriverStatus ( )
overridevirtual

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

Implements mock_drivers::MockDriver.

Definition at line 26 of file MockCommsDriver.cpp.

27{
28 return cav_msgs::DriverStatus::OPERATIONAL;
29}

◆ getDriverTypes()

std::vector< DriverType > mock_drivers::MockCommsDriver::getDriverTypes ( )
overridevirtual

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

Implements mock_drivers::MockDriver.

Definition at line 21 of file MockCommsDriver.cpp.

22{
23 return { DriverType::COMMS };
24}

References COMMS.

◆ getRate()

unsigned int mock_drivers::MockCommsDriver::getRate ( )
overridevirtual

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

Returns
Spin rate in Hz

Implements mock_drivers::MockDriver.

Definition at line 46 of file MockCommsDriver.cpp.

47{
48 return 20; // 20 Hz as default spin rate to match expected comms data rate
49}

◆ onRun()

int mock_drivers::MockCommsDriver::onRun ( )
overrideprotectedvirtual

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.

Implements mock_drivers::MockDriver.

Definition at line 51 of file MockCommsDriver.cpp.

52{
53 // driver publisher and subscriber
54 addPassthroughPub<cav_msgs::ByteArray>(bag_prefix_ + inbound_binary_topic_, inbound_binary_topic_, false, 10);
55
57
58 return 0;
59}
const std::string inbound_binary_topic_
void addSub(T comm)
Function to add a subscriber from a ROSComms object.
const std::string bag_prefix_
Definition: MockDriver.h:63

References mock_drivers::MockDriverNode::addSub(), mock_drivers::MockDriver::bag_prefix_, inbound_binary_topic_, mock_drivers::MockDriver::mock_driver_node_, and outbound_sub_ptr_.

Here is the call graph for this function:

◆ outboundCallback()

void mock_drivers::MockCommsDriver::outboundCallback ( const cav_msgs::ByteArray::ConstPtr &  msg) const
private

Definition at line 31 of file MockCommsDriver.cpp.

32{
33 ROS_DEBUG_STREAM("Received Byte Array of type: " << msg->message_type);
34};

Referenced by MockCommsDriver().

Here is the caller graph for this function:

Member Data Documentation

◆ inbound_binary_topic_

const std::string mock_drivers::MockCommsDriver::inbound_binary_topic_ = "comms/inbound_binary_msg"
private

Definition at line 30 of file MockCommsDriver.h.

Referenced by onRun().

◆ outbound_binary_topic_

const std::string mock_drivers::MockCommsDriver::outbound_binary_topic_ = "comms/outbound_binary_msg"
private

Definition at line 31 of file MockCommsDriver.h.

Referenced by MockCommsDriver().

◆ outbound_sub_ptr_

ConstPtrRefROSCommsPtr<cav_msgs::ByteArray> mock_drivers::MockCommsDriver::outbound_sub_ptr_
private

Definition at line 28 of file MockCommsDriver.h.

Referenced by MockCommsDriver(), and onRun().


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