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 Controller driver. Implements controller service and feedback logic to support CARMA Platform Guidance State Machine. More...
#include <MockControllerDriver.h>
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< DriverType > | getDriverTypes () 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< 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 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) |
Mock Controller driver. Implements controller service and feedback logic to support CARMA Platform Guidance State Machine.
Definition at line 27 of file MockControllerDriver.h.
mock_drivers::MockControllerDriver::MockControllerDriver | ( | bool | dummy = false | ) |
Definition at line 51 of file MockControllerDriver.cpp.
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().
|
inline |
Definition at line 70 of file MockControllerDriver.h.
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.
req | The service request in message |
res | The service response out message |
Definition at line 36 of file MockControllerDriver.cpp.
References robot_active_, and robot_enabled_.
Referenced by MockControllerDriver().
|
overridevirtual |
Pure Virtual method. Returns an integer value which corresponds to the cav_msgs/DriverStatus enum felids representing the status of the driver.
Implements mock_drivers::MockDriver.
Definition at line 26 of file MockControllerDriver.cpp.
|
overridevirtual |
Pure Virtual method which child classes must override that returns the list of all driver types that class implements.
Implements mock_drivers::MockDriver.
Definition at line 21 of file MockControllerDriver.cpp.
References CONTROLLER.
|
overridevirtual |
Pure virtual method that returns the desired operational rate of a child class.
Implements mock_drivers::MockDriver.
Definition at line 79 of file MockControllerDriver.cpp.
|
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.
Implements mock_drivers::MockDriver.
Definition at line 84 of file MockControllerDriver.cpp.
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_.
|
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()
Reimplemented from mock_drivers::MockDriver.
Definition at line 68 of file MockControllerDriver.cpp.
References mock_drivers::MockDriver::mock_driver_node_, mock_drivers::MockDriverNode::publishDataNoHeader(), robot_active_, robot_enabled_, and robot_status_topic_.
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.
msg | The vehicle command to receive |
Definition at line 31 of file MockControllerDriver.cpp.
References robot_enabled_.
Referenced by MockControllerDriver().
|
private |
Definition at line 33 of file MockControllerDriver.h.
Referenced by MockControllerDriver(), and onRun().
|
private |
Definition at line 40 of file MockControllerDriver.h.
Referenced by MockControllerDriver().
|
private |
Definition at line 43 of file MockControllerDriver.h.
Referenced by enableRoboticSrv(), and onSpin().
|
private |
Definition at line 44 of file MockControllerDriver.h.
Referenced by enableRoboticSrv(), onSpin(), and vehicleCmdCallback().
|
private |
Definition at line 30 of file MockControllerDriver.h.
Referenced by MockControllerDriver(), and onRun().
|
private |
Definition at line 36 of file MockControllerDriver.h.
Referenced by MockControllerDriver(), and onSpin().
|
private |
Definition at line 31 of file MockControllerDriver.h.
Referenced by MockControllerDriver(), and onRun().
|
private |
Definition at line 39 of file MockControllerDriver.h.
Referenced by MockControllerDriver().