#include <realtime_publisher.h>
Public Member Functions | |
void | init (const ros::NodeHandle &node, const std::string &topic, int queue_size, bool latched=false) |
void | lock () |
Get the data lock form non-realtime. More... | |
RealtimePublisher () | |
RealtimePublisher (const ros::NodeHandle &node, const std::string &topic, int queue_size, bool latched=false) | |
Constructor for the realtime publisher. More... | |
void | stop () |
Stop the realtime publisher from sending out more ROS messages. More... | |
bool | trylock () |
Try to get the data lock from realtime. More... | |
void | unlock () |
Unlocks the data without publishing anything. More... | |
void | unlockAndPublish () |
Unlock the msg_ variable. More... | |
~RealtimePublisher () | |
Destructor. More... | |
Public Attributes | |
Msg | msg_ |
The msg_ variable contains the data that will get published on the ROS topic. More... | |
Private Types | |
enum | { REALTIME, NON_REALTIME, LOOP_NOT_STARTED } |
Private Member Functions | |
void | construct (int queue_size, bool latched=false) |
RealtimePublisher & | operator= (const RealtimePublisher &)=delete |
void | publishingLoop () |
RealtimePublisher (const RealtimePublisher &)=delete | |
Private Attributes | |
std::atomic< bool > | is_running_ |
std::atomic< bool > | keep_running_ |
std::mutex | msg_mutex_ |
ros::NodeHandle | node_ |
ros::Publisher | publisher_ |
std::thread | thread_ |
std::string | topic_ |
std::atomic< int > | turn_ |
Definition at line 54 of file realtime_publisher.h.
|
private |
Enumerator | |
---|---|
REALTIME | |
NON_REALTIME | |
LOOP_NOT_STARTED |
Definition at line 241 of file realtime_publisher.h.
|
inline |
Constructor for the realtime publisher.
node | the nodehandle that specifies the namespace (or prefix) that is used to advertise the ROS topic |
topic | the topic name to advertise |
queue_size | the size of the outgoing ROS buffer |
latched | . optional argument (defaults to false) to specify is publisher is latched or not |
Definition at line 68 of file realtime_publisher.h.
|
inline |
Definition at line 74 of file realtime_publisher.h.
|
inline |
Destructor.
Definition at line 80 of file realtime_publisher.h.
|
privatedelete |
|
inlineprivate |
Definition at line 184 of file realtime_publisher.h.
|
inline |
Definition at line 95 of file realtime_publisher.h.
|
inline |
Get the data lock form non-realtime.
To publish data from the realtime loop, you need to run trylock to attempt to get unique access to the msg_ variable. Trylock returns true if the lock was aquired, and false if it failed to get the lock.
Definition at line 155 of file realtime_publisher.h.
|
privatedelete |
|
inlineprivate |
Definition at line 192 of file realtime_publisher.h.
|
inline |
Stop the realtime publisher from sending out more ROS messages.
Definition at line 103 of file realtime_publisher.h.
|
inline |
Try to get the data lock from realtime.
To publish data from the realtime loop, you need to run trylock to attempt to get unique access to the msg_ variable. Trylock returns true if the lock was aquired, and false if it failed to get the lock.
Definition at line 117 of file realtime_publisher.h.
|
inline |
Unlocks the data without publishing anything.
Definition at line 171 of file realtime_publisher.h.
|
inline |
Unlock the msg_ variable.
After a successful trylock and after the data is written to the mgs_ variable, the lock has to be released for the message to get published on the specified topic.
Definition at line 143 of file realtime_publisher.h.
|
private |
Definition at line 230 of file realtime_publisher.h.
|
private |
Definition at line 231 of file realtime_publisher.h.
Msg realtime_tools::RealtimePublisher< Msg >::msg_ |
The msg_ variable contains the data that will get published on the ROS topic.
Definition at line 59 of file realtime_publisher.h.
|
private |
Definition at line 235 of file realtime_publisher.h.
|
private |
Definition at line 228 of file realtime_publisher.h.
|
private |
Definition at line 229 of file realtime_publisher.h.
|
private |
Definition at line 233 of file realtime_publisher.h.
|
private |
Definition at line 227 of file realtime_publisher.h.
|
private |
Definition at line 242 of file realtime_publisher.h.