Public Member Functions | Public Attributes | Private Types | Private Member Functions | Private Attributes | List of all members
realtime_tools::RealtimePublisher< Msg > Class Template Reference

#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)
 
RealtimePublisheroperator= (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_
 

Detailed Description

template<class Msg>
class realtime_tools::RealtimePublisher< Msg >

Definition at line 54 of file realtime_publisher.h.

Member Enumeration Documentation

◆ anonymous enum

template<class Msg >
anonymous enum
private
Enumerator
REALTIME 
NON_REALTIME 
LOOP_NOT_STARTED 

Definition at line 241 of file realtime_publisher.h.

Constructor & Destructor Documentation

◆ RealtimePublisher() [1/3]

template<class Msg >
realtime_tools::RealtimePublisher< Msg >::RealtimePublisher ( const ros::NodeHandle node,
const std::string &  topic,
int  queue_size,
bool  latched = false 
)
inline

Constructor for the realtime publisher.

Parameters
nodethe nodehandle that specifies the namespace (or prefix) that is used to advertise the ROS topic
topicthe topic name to advertise
queue_sizethe 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.

◆ RealtimePublisher() [2/3]

template<class Msg >
realtime_tools::RealtimePublisher< Msg >::RealtimePublisher ( )
inline

Definition at line 74 of file realtime_publisher.h.

◆ ~RealtimePublisher()

template<class Msg >
realtime_tools::RealtimePublisher< Msg >::~RealtimePublisher ( )
inline

Destructor.

Definition at line 80 of file realtime_publisher.h.

◆ RealtimePublisher() [3/3]

template<class Msg >
realtime_tools::RealtimePublisher< Msg >::RealtimePublisher ( const RealtimePublisher< Msg > &  )
privatedelete

Member Function Documentation

◆ construct()

template<class Msg >
void realtime_tools::RealtimePublisher< Msg >::construct ( int  queue_size,
bool  latched = false 
)
inlineprivate

Definition at line 184 of file realtime_publisher.h.

◆ init()

template<class Msg >
void realtime_tools::RealtimePublisher< Msg >::init ( const ros::NodeHandle node,
const std::string &  topic,
int  queue_size,
bool  latched = false 
)
inline

Definition at line 95 of file realtime_publisher.h.

◆ lock()

template<class Msg >
void realtime_tools::RealtimePublisher< Msg >::lock ( )
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.

◆ operator=()

template<class Msg >
RealtimePublisher& realtime_tools::RealtimePublisher< Msg >::operator= ( const RealtimePublisher< Msg > &  )
privatedelete

◆ publishingLoop()

template<class Msg >
void realtime_tools::RealtimePublisher< Msg >::publishingLoop ( )
inlineprivate

Definition at line 192 of file realtime_publisher.h.

◆ stop()

template<class Msg >
void realtime_tools::RealtimePublisher< Msg >::stop ( )
inline

Stop the realtime publisher from sending out more ROS messages.

Definition at line 103 of file realtime_publisher.h.

◆ trylock()

template<class Msg >
bool realtime_tools::RealtimePublisher< Msg >::trylock ( )
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.

◆ unlock()

template<class Msg >
void realtime_tools::RealtimePublisher< Msg >::unlock ( )
inline

Unlocks the data without publishing anything.

Definition at line 171 of file realtime_publisher.h.

◆ unlockAndPublish()

template<class Msg >
void realtime_tools::RealtimePublisher< Msg >::unlockAndPublish ( )
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.

Member Data Documentation

◆ is_running_

template<class Msg >
std::atomic<bool> realtime_tools::RealtimePublisher< Msg >::is_running_
private

Definition at line 230 of file realtime_publisher.h.

◆ keep_running_

template<class Msg >
std::atomic<bool> realtime_tools::RealtimePublisher< Msg >::keep_running_
private

Definition at line 231 of file realtime_publisher.h.

◆ msg_

template<class Msg >
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.

◆ msg_mutex_

template<class Msg >
std::mutex realtime_tools::RealtimePublisher< Msg >::msg_mutex_
private

Definition at line 235 of file realtime_publisher.h.

◆ node_

template<class Msg >
ros::NodeHandle realtime_tools::RealtimePublisher< Msg >::node_
private

Definition at line 228 of file realtime_publisher.h.

◆ publisher_

template<class Msg >
ros::Publisher realtime_tools::RealtimePublisher< Msg >::publisher_
private

Definition at line 229 of file realtime_publisher.h.

◆ thread_

template<class Msg >
std::thread realtime_tools::RealtimePublisher< Msg >::thread_
private

Definition at line 233 of file realtime_publisher.h.

◆ topic_

template<class Msg >
std::string realtime_tools::RealtimePublisher< Msg >::topic_
private

Definition at line 227 of file realtime_publisher.h.

◆ turn_

template<class Msg >
std::atomic<int> realtime_tools::RealtimePublisher< Msg >::turn_
private

Definition at line 242 of file realtime_publisher.h.


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


realtime_tools
Author(s): Stuart Glaser
autogenerated on Mon Jan 8 2024 03:20:12