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

Mock Controller driver. Implements controller service and feedback logic to support CARMA Platform Guidance State Machine. More...

#include <MockControllerDriver.h>

Inheritance diagram for mock_drivers::MockControllerDriver:
Inheritance graph
Collaboration diagram for mock_drivers::MockControllerDriver:
Collaboration graph

Public Member Functions

void vehicleCmdCallback (const autoware_msgs::VehicleCmd::ConstPtr &msg)
 Callback for the vehicle command topic. This callback must be triggered at least once before the enable robotic service is called. More...
 
bool enableRoboticSrv (const cav_srvs::SetEnableRobotic::Request &req, cav_srvs::SetEnableRobotic::Response &res)
 Callback for the enable robotic service. Triggering this callback will modify the RobotEnabled message output by this driver. More...
 
 MockControllerDriver (bool dummy=false)
 
 ~MockControllerDriver ()
 
bool onSpin () override
 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...
 
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 Attributes

boost::shared_ptr< ROSComms< cav_msgs::RobotEnabled > > robot_status_ptr_
 
ConstPtrRefROSCommsPtr< autoware_msgs::VehicleCmd > vehicle_cmd_ptr_
 
boost::shared_ptr< ROSComms< cav_srvs::SetEnableRobotic::Request &, cav_srvs::SetEnableRobotic::Response & > > enable_robotic_ptr_
 
const std::string robot_status_topic_ = "controller/robot_status"
 
const std::string vehicle_cmd_topic_ = "vehicle_cmd"
 
const std::string enable_robotic_srv_ = "controller/enable_robotic"
 
bool robot_active_ = false
 
bool robot_enabled_ = false
 

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 Controller driver. Implements controller service and feedback logic to support CARMA Platform Guidance State Machine.

Definition at line 27 of file MockControllerDriver.h.

Constructor & Destructor Documentation

◆ MockControllerDriver()

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

Definition at line 51 of file MockControllerDriver.cpp.

52{
53 mock_driver_node_ = MockDriverNode(dummy);
54
56 boost::make_shared<ROSComms<cav_msgs::RobotEnabled>>(CommTypes::pub, false, 10, robot_status_topic_);
57
58 vehicle_cmd_ptr_ = boost::make_shared<ConstPtrRefROSComms<autoware_msgs::VehicleCmd>>(
59 std::bind(&MockControllerDriver::vehicleCmdCallback, this, std::placeholders::_1), CommTypes::sub, false, 10,
61
63 boost::make_shared<ROSComms<cav_srvs::SetEnableRobotic::Request&, cav_srvs::SetEnableRobotic::Response&>>(
64 std::bind(&MockControllerDriver::enableRoboticSrv, this, std::placeholders::_1, std::placeholders::_2),
66}
boost::shared_ptr< ROSComms< cav_srvs::SetEnableRobotic::Request &, cav_srvs::SetEnableRobotic::Response & > > enable_robotic_ptr_
bool enableRoboticSrv(const cav_srvs::SetEnableRobotic::Request &req, cav_srvs::SetEnableRobotic::Response &res)
Callback for the enable robotic service. Triggering this callback will modify the RobotEnabled messag...
ConstPtrRefROSCommsPtr< autoware_msgs::VehicleCmd > vehicle_cmd_ptr_
boost::shared_ptr< ROSComms< cav_msgs::RobotEnabled > > robot_status_ptr_
void vehicleCmdCallback(const autoware_msgs::VehicleCmd::ConstPtr &msg)
Callback for the vehicle command topic. This callback must be triggered at least once before the enab...
MockDriverNode mock_driver_node_
Definition: MockDriver.h:59

References enable_robotic_ptr_, enable_robotic_srv_, enableRoboticSrv(), mock_drivers::MockDriver::mock_driver_node_, pub, robot_status_ptr_, robot_status_topic_, srv, sub, vehicle_cmd_ptr_, vehicle_cmd_topic_, and vehicleCmdCallback().

Here is the call graph for this function:

◆ ~MockControllerDriver()

mock_drivers::MockControllerDriver::~MockControllerDriver ( )
inline

Definition at line 70 of file MockControllerDriver.h.

70{};

Member Function Documentation

◆ enableRoboticSrv()

bool mock_drivers::MockControllerDriver::enableRoboticSrv ( const cav_srvs::SetEnableRobotic::Request &  req,
cav_srvs::SetEnableRobotic::Response &  res 
)

Callback for the enable robotic service. Triggering this callback will modify the RobotEnabled message output by this driver.

Parameters
reqThe service request in message
resThe service response out message
Returns
Flag idicating if the service was processed successfully.

Definition at line 36 of file MockControllerDriver.cpp.

38{
39 if (robot_enabled_ && req.set == cav_srvs::SetEnableRobotic::Request::ENABLE)
40 {
41 robot_active_ = true;
42 }
43 else
44 {
45 robot_active_ = false;
46 }
47
48 return true;
49}

References robot_active_, and robot_enabled_.

Referenced by MockControllerDriver().

Here is the caller graph for this function:

◆ getDriverStatus()

uint8_t mock_drivers::MockControllerDriver::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 MockControllerDriver.cpp.

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

◆ getDriverTypes()

std::vector< DriverType > mock_drivers::MockControllerDriver::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 MockControllerDriver.cpp.

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

References CONTROLLER.

◆ getRate()

unsigned int mock_drivers::MockControllerDriver::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 79 of file MockControllerDriver.cpp.

80{
81 return 20; // 20 Hz as default spin rate to match expected controller data rate
82}

◆ onRun()

int mock_drivers::MockControllerDriver::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 84 of file MockControllerDriver.cpp.

85{
86 // driver publisher, subscriber, and service
90
91 return 0;
92}
void addSub(T comm)
Function to add a subscriber from a ROSComms object.
void addSrv(T comm)
Function to add a service from a ROSComms object.
void addPub(T comm)
Function to add a publisher from a ROSComms object.

References mock_drivers::MockDriverNode::addPub(), mock_drivers::MockDriverNode::addSrv(), mock_drivers::MockDriverNode::addSub(), enable_robotic_ptr_, mock_drivers::MockDriver::mock_driver_node_, robot_status_ptr_, and vehicle_cmd_ptr_.

Here is the call graph for this function:

◆ onSpin()

bool mock_drivers::MockControllerDriver::onSpin ( )
overridevirtual

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

Definition at line 68 of file MockControllerDriver.cpp.

69{
70 cav_msgs::RobotEnabled robot_status;
71 robot_status.robot_active = robot_active_;
72 robot_status.robot_enabled = robot_enabled_;
73
74 mock_driver_node_.publishDataNoHeader<cav_msgs::RobotEnabled>(robot_status_topic_, robot_status);
75
76 return true;
77}
void publishDataNoHeader(std::string topic, T msg)
Publish data with no header on a desired topic.

References mock_drivers::MockDriver::mock_driver_node_, mock_drivers::MockDriverNode::publishDataNoHeader(), robot_active_, robot_enabled_, and robot_status_topic_.

Here is the call graph for this function:

◆ vehicleCmdCallback()

void mock_drivers::MockControllerDriver::vehicleCmdCallback ( const autoware_msgs::VehicleCmd::ConstPtr &  msg)

Callback for the vehicle command topic. This callback must be triggered at least once before the enable robotic service is called.

Parameters
msgThe vehicle command to receive

Definition at line 31 of file MockControllerDriver.cpp.

32{
33 robot_enabled_ = true; // If a command was received set the robot enabled status to true
34}

References robot_enabled_.

Referenced by MockControllerDriver().

Here is the caller graph for this function:

Member Data Documentation

◆ enable_robotic_ptr_

boost::shared_ptr<ROSComms<cav_srvs::SetEnableRobotic::Request&, cav_srvs::SetEnableRobotic::Response&> > mock_drivers::MockControllerDriver::enable_robotic_ptr_
private

Definition at line 33 of file MockControllerDriver.h.

Referenced by MockControllerDriver(), and onRun().

◆ enable_robotic_srv_

const std::string mock_drivers::MockControllerDriver::enable_robotic_srv_ = "controller/enable_robotic"
private

Definition at line 40 of file MockControllerDriver.h.

Referenced by MockControllerDriver().

◆ robot_active_

bool mock_drivers::MockControllerDriver::robot_active_ = false
private

Definition at line 43 of file MockControllerDriver.h.

Referenced by enableRoboticSrv(), and onSpin().

◆ robot_enabled_

bool mock_drivers::MockControllerDriver::robot_enabled_ = false
private

Definition at line 44 of file MockControllerDriver.h.

Referenced by enableRoboticSrv(), onSpin(), and vehicleCmdCallback().

◆ robot_status_ptr_

boost::shared_ptr<ROSComms<cav_msgs::RobotEnabled> > mock_drivers::MockControllerDriver::robot_status_ptr_
private

Definition at line 30 of file MockControllerDriver.h.

Referenced by MockControllerDriver(), and onRun().

◆ robot_status_topic_

const std::string mock_drivers::MockControllerDriver::robot_status_topic_ = "controller/robot_status"
private

Definition at line 36 of file MockControllerDriver.h.

Referenced by MockControllerDriver(), and onSpin().

◆ vehicle_cmd_ptr_

ConstPtrRefROSCommsPtr<autoware_msgs::VehicleCmd> mock_drivers::MockControllerDriver::vehicle_cmd_ptr_
private

Definition at line 31 of file MockControllerDriver.h.

Referenced by MockControllerDriver(), and onRun().

◆ vehicle_cmd_topic_

const std::string mock_drivers::MockControllerDriver::vehicle_cmd_topic_ = "vehicle_cmd"
private

Definition at line 39 of file MockControllerDriver.h.

Referenced by MockControllerDriver().


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