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

Node class which connects to the ROS network. More...

#include <MockDriverNode.h>

Collaboration diagram for mock_drivers::MockDriverNode:
Collaboration graph

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< PublisherWapperpublishers_
 
std::vector< ros::Subscriber > subscribers_
 
std::vector< ros::ServiceServer > services_
 
bool dummy_ = false
 
std::vector< std::string > topics_
 
std::vector< ros::Time > time_stamps_
 

Detailed Description

Node class which connects to the ROS network.

Definition at line 34 of file MockDriverNode.h.

Constructor & Destructor Documentation

◆ MockDriverNode() [1/2]

mock_drivers::MockDriverNode::MockDriverNode ( )

Definition at line 21 of file MockDriverNode.cpp.

22{
23}

◆ MockDriverNode() [2/2]

mock_drivers::MockDriverNode::MockDriverNode ( bool  dummy)

Definition at line 24 of file MockDriverNode.cpp.

24 : dummy_(dummy)
25{
26}

Member Function Documentation

◆ addPub()

template<typename T >
void mock_drivers::MockDriverNode::addPub ( comm)
inline

Function to add a publisher from a ROSComms object.

Definition at line 59 of file MockDriverNode.h.

60 {
61 if (!dummy_)
62 {
63 PublisherWapper pub;
64 pub.pub = cnh_->advertise<decltype(comm->getTemplateType())>(comm->getTopic(), comm->getQueueSize());
65 pub.base_topic_name = comm->getTopic();
66 publishers_.push_back(pub);
67 }
68 }
std::vector< PublisherWapper > publishers_
boost::shared_ptr< ros::CARMANodeHandle > cnh_

References cnh_, dummy_, pub, and publishers_.

Referenced by mock_drivers::MockControllerDriver::onRun(), and mock_drivers::MockDriver::run().

Here is the caller graph for this function:

◆ addSrv()

template<typename T >
void mock_drivers::MockDriverNode::addSrv ( comm)
inline

Function to add a service from a ROSComms object.

Definition at line 83 of file MockDriverNode.h.

84 {
85 if (!dummy_)
86 {
87 services_.push_back(cnh_->advertiseService(
88 comm->getTopic(), &ROSComms<decltype(comm->getReqType()), decltype(comm->getResType())>::callback, comm));
89 }
90 }
std::vector< ros::ServiceServer > services_
bool callback(cav_srvs::PlanTrajectory::Request &req, cav_srvs::PlanTrajectory::Response &res)
Definition: helper.cpp:21

References callback(), cnh_, dummy_, and services_.

Referenced by mock_drivers::MockControllerDriver::onRun().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ addSub()

template<typename T >
void mock_drivers::MockDriverNode::addSub ( comm)
inline

Function to add a subscriber from a ROSComms object.

Definition at line 72 of file MockDriverNode.h.

73 {
74 if (!dummy_)
75 {
76 subscribers_.push_back(cnh_->subscribe<decltype(comm->getTemplateType())>(
77 comm->getTopic(), comm->getQueueSize(), &ROSComms<decltype(comm->getTemplateType())>::callback, comm));
78 }
79 }
std::vector< ros::Subscriber > subscribers_

References callback(), cnh_, dummy_, and subscribers_.

Referenced by mock_drivers::MockCommsDriver::onRun(), and mock_drivers::MockControllerDriver::onRun().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ getGraphName()

std::string mock_drivers::MockDriverNode::getGraphName ( ) const

Returns the fully qualified name of this node in the ROS network graph.

Returns
The fully specified name

Definition at line 28 of file MockDriverNode.cpp.

29{
30 if (dummy_)
31 {
32 return "dummy_mock_driver";
33 }
34
35 return ros::this_node::getName();
36}

References dummy_.

Referenced by mock_drivers::MockDriver::driverDiscovery().

Here is the caller graph for this function:

◆ getTimeStamps()

std::vector< ros::Time > mock_drivers::MockDriverNode::getTimeStamps ( )
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.

160 {
161 return time_stamps_;
162 }
std::vector< ros::Time > time_stamps_

References time_stamps_.

◆ getTopics()

std::vector< std::string > mock_drivers::MockDriverNode::getTopics ( )
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.

154 {
155 return topics_;
156 }
std::vector< std::string > topics_

References topics_.

◆ init()

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.

57{
58 if (!dummy_)
59 {
60 cnh_ = boost::make_shared<ros::CARMANodeHandle>(ros::CARMANodeHandle());
61 }
62}

References cnh_, and dummy_.

Referenced by mock_drivers::MockDriver::run().

Here is the caller graph for this function:

◆ isDummy()

bool mock_drivers::MockDriverNode::isDummy ( )
inline

Returns if the node is a dummy node. Used for testing.

Definition at line 164 of file MockDriverNode.h.

165 {
166 return dummy_;
167 }

References dummy_.

◆ publishData()

template<typename T >
void mock_drivers::MockDriverNode::publishData ( std::string  topic,
msg 
)
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.

109 {
110 if (!dummy_)
111 {
112 auto pub = std::find_if(publishers_.begin(), publishers_.end(),
113 [&](PublisherWapper p) { return p.base_topic_name == topic; });
114 if (pub == publishers_.end())
115 throw std::invalid_argument("Attempted to publish to topic " + topic + " but no publisher was found");
116 pub->pub.publish(msg);
117 }
118 else
119 {
120 topics_.push_back(topic);
121 time_stamps_.push_back(msg.header.stamp);
122 }
123 };

References dummy_, pub, publishers_, time_stamps_, and topics_.

◆ publishDataNoHeader()

template<typename T >
void mock_drivers::MockDriverNode::publishDataNoHeader ( std::string  topic,
msg 
)
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.

133 {
134 if (!dummy_)
135 {
136 auto pub = std::find_if(publishers_.begin(), publishers_.end(),
137 [&](PublisherWapper p) { return p.base_topic_name == topic; });
138 if (pub == publishers_.end())
139 throw std::invalid_argument("Attempted to publish to topic " + topic + " but no publisher was found");
140 pub->pub.publish(msg);
141 }
142 else
143 {
144 topics_.push_back(topic);
145 }
146 };

References dummy_, pub, publishers_, and topics_.

Referenced by mock_drivers::MockDriver::driverDiscovery(), and mock_drivers::MockControllerDriver::onSpin().

Here is the caller graph for this function:

◆ setSpinCallback()

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.

48{
49 if (!dummy_)
50 {
51 ros::CARMANodeHandle::setSpinRate(10.0); // Set spin to avoid exception until spin is called and this value updated
52 ros::CARMANodeHandle::setSpinCallback(cb);
53 }
54}

References dummy_.

Referenced by mock_drivers::MockDriver::run().

Here is the caller graph for this function:

◆ spin()

void mock_drivers::MockDriverNode::spin ( double  rate) const

Begin the ros node.

Definition at line 38 of file MockDriverNode.cpp.

39{
40 if (!dummy_)
41 {
42 ros::CARMANodeHandle::setSpinRate(rate);
43 ros::CARMANodeHandle::spin();
44 }
45}

References dummy_.

Referenced by mock_drivers::MockDriver::run().

Here is the caller graph for this function:

Member Data Documentation

◆ cnh_

boost::shared_ptr<ros::CARMANodeHandle> mock_drivers::MockDriverNode::cnh_
private

Definition at line 37 of file MockDriverNode.h.

Referenced by addPub(), addSrv(), addSub(), and init().

◆ dummy_

bool mock_drivers::MockDriverNode::dummy_ = false
private

◆ publishers_

std::vector<PublisherWapper> mock_drivers::MockDriverNode::publishers_
private

Definition at line 38 of file MockDriverNode.h.

Referenced by addPub(), publishData(), and publishDataNoHeader().

◆ services_

std::vector<ros::ServiceServer> mock_drivers::MockDriverNode::services_
private

Definition at line 40 of file MockDriverNode.h.

Referenced by addSrv().

◆ subscribers_

std::vector<ros::Subscriber> mock_drivers::MockDriverNode::subscribers_
private

Definition at line 39 of file MockDriverNode.h.

Referenced by addSub().

◆ time_stamps_

std::vector<ros::Time> mock_drivers::MockDriverNode::time_stamps_
private

Definition at line 46 of file MockDriverNode.h.

Referenced by getTimeStamps(), and publishData().

◆ topics_

std::vector<std::string> mock_drivers::MockDriverNode::topics_
private

Definition at line 45 of file MockDriverNode.h.

Referenced by getTopics(), publishData(), and publishDataNoHeader().


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