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

#include <realtime_publisher.h>

List of all members.

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.
 RealtimePublisher (const ros::NodeHandle &node, const std::string &topic, int queue_size, bool latched=false)
 Constructor for the realtime publisher.
 RealtimePublisher ()
void stop ()
 Stop the realtime publisher from sending out more ROS messages.
bool trylock ()
 Try to get the data lock from realtime.
void unlock ()
 Unlocks the data without publishing anything.
void unlockAndPublish ()
 Unlock the msg_ variable.
 ~RealtimePublisher ()
 Destructor.

Public Attributes

Msg msg_
 The msg_ variable contains the data that will get published on the ROS topic.

Private Types

enum  { REALTIME, NON_REALTIME }

Private Member Functions

void construct (int queue_size, bool latched=false)
bool is_running () const
void publishingLoop ()

Private Attributes

volatile bool is_running_
volatile bool keep_running_
boost::mutex msg_mutex_
ros::NodeHandle node_
ros::Publisher publisher_
boost::thread thread_
std::string topic_
int turn_

Detailed Description

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

Definition at line 51 of file realtime_publisher.h.


Member Enumeration Documentation

template<class Msg >
anonymous enum [private]
Enumerator:
REALTIME 
NON_REALTIME 

Definition at line 226 of file realtime_publisher.h.


Constructor & Destructor Documentation

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 65 of file realtime_publisher.h.

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

Definition at line 71 of file realtime_publisher.h.

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

Destructor.

Definition at line 77 of file realtime_publisher.h.


Member Function Documentation

template<class Msg >
void realtime_tools::RealtimePublisher< Msg >::construct ( int  queue_size,
bool  latched = false 
) [inline, private]

Definition at line 169 of file realtime_publisher.h.

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 86 of file realtime_publisher.h.

template<class Msg >
bool realtime_tools::RealtimePublisher< Msg >::is_running ( ) const [inline, private]

Definition at line 177 of file realtime_publisher.h.

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 149 of file realtime_publisher.h.

template<class Msg >
void realtime_tools::RealtimePublisher< Msg >::publishingLoop ( ) [inline, private]

Definition at line 179 of file realtime_publisher.h.

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

Stop the realtime publisher from sending out more ROS messages.

Definition at line 94 of file realtime_publisher.h.

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 108 of file realtime_publisher.h.

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

Unlocks the data without publishing anything.

Definition at line 163 of file realtime_publisher.h.

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 134 of file realtime_publisher.h.


Member Data Documentation

template<class Msg >
volatile bool realtime_tools::RealtimePublisher< Msg >::is_running_ [private]

Definition at line 215 of file realtime_publisher.h.

template<class Msg >
volatile bool realtime_tools::RealtimePublisher< Msg >::keep_running_ [private]

Definition at line 216 of file realtime_publisher.h.

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 56 of file realtime_publisher.h.

template<class Msg >
boost::mutex realtime_tools::RealtimePublisher< Msg >::msg_mutex_ [private]

Definition at line 220 of file realtime_publisher.h.

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

Definition at line 213 of file realtime_publisher.h.

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

Definition at line 214 of file realtime_publisher.h.

template<class Msg >
boost::thread realtime_tools::RealtimePublisher< Msg >::thread_ [private]

Definition at line 218 of file realtime_publisher.h.

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

Definition at line 212 of file realtime_publisher.h.

template<class Msg >
int realtime_tools::RealtimePublisher< Msg >::turn_ [private]

Definition at line 227 of file realtime_publisher.h.


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


realtime_tools
Author(s): Stuart Glaser
autogenerated on Thu Jun 6 2019 20:05:02