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.
|
Node class which connects to the ROS network. More...
#include <MockDriverNode.h>
Public Member Functions | |
std::string | getGraphName () const |
Returns the fully qualified name of this node in the ROS network graph. More... | |
template<typename T > | |
void | addPub (T comm) |
Function to add a publisher from a ROSComms object. More... | |
template<typename T > | |
void | addSub (T comm) |
Function to add a subscriber from a ROSComms object. More... | |
template<typename T > | |
void | addSrv (T comm) |
Function to add a service from a ROSComms object. More... | |
void | spin (double rate) const |
Begin the ros node. More... | |
void | setSpinCallback (std::function< bool()> cb) const |
Set the spin callback for the ros node. More... | |
void | init () |
Initialize the CARMA Node Handle pointer for the MockDriverNode (must be called before spin) More... | |
template<typename T > | |
void | publishData (std::string topic, T msg) |
Publish data on a desired topic. More... | |
template<typename T > | |
void | publishDataNoHeader (std::string topic, T msg) |
Publish data with no header on a desired topic. More... | |
MockDriverNode () | |
MockDriverNode (bool dummy) | |
std::vector< std::string > | getTopics () |
Returns a vector of all the topics that the node would publish to (only when it is a dummy node). Used for testing. More... | |
std::vector< ros::Time > | getTimeStamps () |
Returns a vector of all the time stamps of the data that would be published (only when it is a dummy node). Used for testing. More... | |
bool | isDummy () |
Returns if the node is a dummy node. Used for testing. More... | |
Private Attributes | |
boost::shared_ptr< ros::CARMANodeHandle > | cnh_ |
std::vector< PublisherWapper > | publishers_ |
std::vector< ros::Subscriber > | subscribers_ |
std::vector< ros::ServiceServer > | services_ |
bool | dummy_ = false |
std::vector< std::string > | topics_ |
std::vector< ros::Time > | time_stamps_ |
Node class which connects to the ROS network.
Definition at line 34 of file MockDriverNode.h.
mock_drivers::MockDriverNode::MockDriverNode | ( | ) |
Definition at line 21 of file MockDriverNode.cpp.
mock_drivers::MockDriverNode::MockDriverNode | ( | bool | dummy | ) |
Definition at line 24 of file MockDriverNode.cpp.
|
inline |
Function to add a publisher from a ROSComms object.
Definition at line 59 of file MockDriverNode.h.
References cnh_, dummy_, pub, and publishers_.
Referenced by mock_drivers::MockControllerDriver::onRun(), and mock_drivers::MockDriver::run().
|
inline |
Function to add a service from a ROSComms object.
Definition at line 83 of file MockDriverNode.h.
References callback(), cnh_, dummy_, and services_.
Referenced by mock_drivers::MockControllerDriver::onRun().
|
inline |
Function to add a subscriber from a ROSComms object.
Definition at line 72 of file MockDriverNode.h.
References callback(), cnh_, dummy_, and subscribers_.
Referenced by mock_drivers::MockCommsDriver::onRun(), and mock_drivers::MockControllerDriver::onRun().
std::string mock_drivers::MockDriverNode::getGraphName | ( | ) | const |
Returns the fully qualified name of this node in the ROS network graph.
Definition at line 28 of file MockDriverNode.cpp.
References dummy_.
Referenced by mock_drivers::MockDriver::driverDiscovery().
|
inline |
Returns a vector of all the time stamps of the data that would be published (only when it is a dummy node). Used for testing.
Definition at line 159 of file MockDriverNode.h.
References time_stamps_.
|
inline |
Returns a vector of all the topics that the node would publish to (only when it is a dummy node). Used for testing.
Definition at line 153 of file MockDriverNode.h.
References topics_.
void mock_drivers::MockDriverNode::init | ( | ) |
Initialize the CARMA Node Handle pointer for the MockDriverNode (must be called before spin)
Definition at line 56 of file MockDriverNode.cpp.
Referenced by mock_drivers::MockDriver::run().
|
inline |
Returns if the node is a dummy node. Used for testing.
Definition at line 164 of file MockDriverNode.h.
References dummy_.
|
inline |
Publish data on a desired topic.
This function must take in the full name of topic that will be published including the namespaces and leading /. This can probably be made to take that information in on construction of the node but we can add that once it breaks :)
Definition at line 108 of file MockDriverNode.h.
References dummy_, pub, publishers_, time_stamps_, and topics_.
|
inline |
Publish data with no header on a desired topic.
Same as the publishData function, except this is used when the data doesn't have a header. This exists to allow for testing of the code. This can be combined with publishData once we are in c++ 17 and can use constexpr if statement.
Definition at line 132 of file MockDriverNode.h.
References dummy_, pub, publishers_, and topics_.
Referenced by mock_drivers::MockDriver::driverDiscovery(), and mock_drivers::MockControllerDriver::onSpin().
void mock_drivers::MockDriverNode::setSpinCallback | ( | std::function< bool()> | cb | ) | const |
Set the spin callback for the ros node.
Definition at line 47 of file MockDriverNode.cpp.
References dummy_.
Referenced by mock_drivers::MockDriver::run().
void mock_drivers::MockDriverNode::spin | ( | double | rate | ) | const |
Begin the ros node.
Definition at line 38 of file MockDriverNode.cpp.
References dummy_.
Referenced by mock_drivers::MockDriver::run().
|
private |
|
private |
Definition at line 43 of file MockDriverNode.h.
Referenced by addPub(), addSrv(), addSub(), getGraphName(), init(), isDummy(), publishData(), publishDataNoHeader(), setSpinCallback(), and spin().
|
private |
Definition at line 38 of file MockDriverNode.h.
Referenced by addPub(), publishData(), and publishDataNoHeader().
|
private |
Definition at line 40 of file MockDriverNode.h.
Referenced by addSrv().
|
private |
Definition at line 39 of file MockDriverNode.h.
Referenced by addSub().
|
private |
Definition at line 46 of file MockDriverNode.h.
Referenced by getTimeStamps(), and publishData().
|
private |
Definition at line 45 of file MockDriverNode.h.
Referenced by getTopics(), publishData(), and publishDataNoHeader().