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.
|
Class which serves as an abstraction of a pub/sub framework. More...
#include <ROSComms.h>
Public Member Functions | |
bool | getLatch () |
Returns the latched status of this data stream. More... | |
int | getQueueSize () |
Returns the data stream queue size. More... | |
std::string | getTopic () |
Returns the name string (topic) associated with the data stream. More... | |
CommTypes | getCommType () |
returns the comms type of this object More... | |
void | callback (T msg) |
Callback function which is triggered to pass data into this comms abstraction. More... | |
T | getTemplateType () |
Returns an instance of the type this object is parameterized on. This is used for forwarding the data type. More... | |
ROSComms () | |
Default constructor. More... | |
ROSComms (CommTypes ct, bool latch, int qs, std::string t) | |
Publisher constructor. More... | |
ROSComms (std::function< void(T)> cbf, CommTypes ct, bool latch, int qs, std::string t) | |
Publisher constructor. More... | |
Private Attributes | |
std::function< void(T)> | callback_function_ |
CommTypes | comm_type_ |
bool | latch_ |
int | queue_size_ |
std::string | topic_ |
Class which serves as an abstraction of a pub/sub framework.
T | Message type. This should be a base message type and does not support services. For example t = std_msgs/Float64 |
Definition at line 42 of file ROSComms.h.
mock_drivers::ROSComms< T >::ROSComms |
mock_drivers::ROSComms< T >::ROSComms | ( | CommTypes | ct, |
bool | latch, | ||
int | qs, | ||
std::string | t | ||
) |
Publisher constructor.
Constructor for a publisher ROSComms.
ct | The comms type which should be pub |
latch | The latched status of this publication |
qs | The queue size of this publication |
t | The name of the topic |
Definition at line 28 of file ROSComms.ipp.
mock_drivers::ROSComms< T >::ROSComms | ( | std::function< void(T)> | cbf, |
CommTypes | ct, | ||
bool | latch, | ||
int | qs, | ||
std::string | t | ||
) |
Publisher constructor.
Constructor for a subscriber ROSComms.
ct | The comms type which should be pub |
latch | The latched status of this publication |
qs | The queue size of this publication |
t | The name of the topic |
Definition at line 38 of file ROSComms.ipp.
void mock_drivers::ROSComms< T >::callback | ( | T | msg | ) |
Callback function which is triggered to pass data into this comms abstraction.
Used to call the ROSComms callback function.
msg | The message to pass |
Definition at line 57 of file ROSComms.ipp.
|
inline |
returns the comms type of this object
Definition at line 87 of file ROSComms.h.
|
inline |
Returns the latched status of this data stream.
Definition at line 57 of file ROSComms.h.
|
inline |
Returns the data stream queue size.
Definition at line 67 of file ROSComms.h.
T mock_drivers::ROSComms< T >::getTemplateType | ( | ) |
Returns an instance of the type this object is parameterized on. This is used for forwarding the data type.
|
inline |
Returns the name string (topic) associated with the data stream.
Definition at line 77 of file ROSComms.h.
|
private |
Definition at line 45 of file ROSComms.h.
|
private |
Definition at line 46 of file ROSComms.h.
|
private |
Definition at line 47 of file ROSComms.h.
|
private |
Definition at line 48 of file ROSComms.h.
|
private |
Definition at line 49 of file ROSComms.h.