Public Member Functions | Private Types | Private Member Functions | Private Attributes
convenience_ros_functions::TypedSubscriber< MessageType > Class Template Reference

#include <TypedSubscriber.h>

List of all members.

Public Member Functions

bool getLastMessage (MessageType &msg) const
bool isActive () const
bool isRunning () const
void setActive (bool flag)
void start (const std::string &_topic)
void stop ()
 TypedSubscriber (ros::NodeHandle &_node)
bool waitForNextMessage (MessageType &msg, float timeout=-1, float wait_step=0.05) const
 ~TypedSubscriber ()

Private Types

typedef
baselib_binding::condition_variable 
condition_variable
typedef baselib_binding::mutex mutex
typedef
baselib_binding::recursive_mutex 
recursive_mutex
typedef TypedSubscriber
< MessageType > 
Self
typedef
baselib_binding::unique_lock
< mutex >::type 
unique_lock
typedef
baselib_binding::unique_lock
< recursive_mutex >::type 
unique_recursive_lock

Private Member Functions

ros::Time getLastUpdateTime () const
void msgCallback (const MessageType &_msg)

Private Attributes

recursive_mutex generalMutex
MessageType lastArrivedMessage
ros::Time lastUpdateTime
condition_variable messageArrivedCondition
mutex messageArrivedMutex
ros::NodeHandlenode
bool running
ros::Subscriber sub
bool subscriberActive
std::string topic

Detailed Description

template<class MessageType>
class convenience_ros_functions::TypedSubscriber< MessageType >

Subscribes to a topic of a message type and provides the functionality to wait for the next message.

Author:
Jennifer Buehler
Date:
March 2016

Definition at line 19 of file TypedSubscriber.h.


Member Typedef Documentation

template<class MessageType >
typedef baselib_binding::condition_variable convenience_ros_functions::TypedSubscriber< MessageType >::condition_variable [private]

Definition at line 82 of file TypedSubscriber.h.

template<class MessageType >
typedef baselib_binding::mutex convenience_ros_functions::TypedSubscriber< MessageType >::mutex [private]

Definition at line 79 of file TypedSubscriber.h.

template<class MessageType >
typedef baselib_binding::recursive_mutex convenience_ros_functions::TypedSubscriber< MessageType >::recursive_mutex [private]

Definition at line 78 of file TypedSubscriber.h.

template<class MessageType >
typedef TypedSubscriber<MessageType> convenience_ros_functions::TypedSubscriber< MessageType >::Self [private]

Definition at line 21 of file TypedSubscriber.h.

template<class MessageType >
typedef baselib_binding::unique_lock<mutex>::type convenience_ros_functions::TypedSubscriber< MessageType >::unique_lock [private]

Definition at line 80 of file TypedSubscriber.h.

template<class MessageType >
typedef baselib_binding::unique_lock<recursive_mutex>::type convenience_ros_functions::TypedSubscriber< MessageType >::unique_recursive_lock [private]

Definition at line 81 of file TypedSubscriber.h.


Constructor & Destructor Documentation

template<class MessageType >
convenience_ros_functions::TypedSubscriber< MessageType >::TypedSubscriber ( ros::NodeHandle _node) [inline]

Definition at line 25 of file TypedSubscriber.h.

template<class MessageType >
convenience_ros_functions::TypedSubscriber< MessageType >::~TypedSubscriber ( ) [inline]

Definition at line 32 of file TypedSubscriber.h.


Member Function Documentation

template<class MessageType >
bool TypedSubscriber::getLastMessage ( MessageType &  msg) const

returns last arrived message in msg.

Returns:
false if no message has arrived yet.

Definition at line 47 of file TypedSubscriber.hpp.

template<class MessageType >
ros::Time TypedSubscriber::getLastUpdateTime ( ) const [private]

Definition at line 106 of file TypedSubscriber.hpp.

template<class MessageType >
bool TypedSubscriber::isActive ( ) const
Returns:
is active. This does not mean isRunning() also returns true: the service may have been stopped, but as soon as it is re-launched, the subscriber would automatically be active.

Definition at line 33 of file TypedSubscriber.hpp.

template<class MessageType >
bool TypedSubscriber::isRunning ( ) const
Returns:
if it is subscribed to a topic. May not necessarily be active, use isActive() to check for this.

Definition at line 40 of file TypedSubscriber.hpp.

template<class MessageType >
void TypedSubscriber::msgCallback ( const MessageType &  _msg) [private]

Definition at line 113 of file TypedSubscriber.hpp.

template<class MessageType >
void TypedSubscriber::setActive ( bool  flag)

Activates or deactivates the processing of incoming messages. This can be used to save a bit of processing time when updates are currently not required, but it is not desired to completely stop the subscriber (with stop()) at times when updates are not required.

Definition at line 20 of file TypedSubscriber.hpp.

template<class MessageType >
void TypedSubscriber::start ( const std::string &  _topic)

Definition at line 2 of file TypedSubscriber.hpp.

template<class MessageType >
void TypedSubscriber::stop ( )

Definition at line 12 of file TypedSubscriber.hpp.

template<class MessageType >
bool TypedSubscriber::waitForNextMessage ( MessageType &  msg,
float  timeout = -1,
float  wait_step = 0.05 
) const

Blocks while it waits for the incoming new message and returns it in . Only succeeds if active (isActive() returns true)

Parameters:
timeoutthe timeout, or negative if no timeout to be used
wait_steptime (in seconds) to sleep in-between checks wheter a new joint state has arrived.
Returns:
true if successfully waited until next message or false if timeout reached (or isActive() returned false)

Definition at line 56 of file TypedSubscriber.hpp.


Member Data Documentation

template<class MessageType >
recursive_mutex convenience_ros_functions::TypedSubscriber< MessageType >::generalMutex [mutable, private]

Definition at line 90 of file TypedSubscriber.h.

template<class MessageType >
MessageType convenience_ros_functions::TypedSubscriber< MessageType >::lastArrivedMessage [private]

Definition at line 96 of file TypedSubscriber.h.

template<class MessageType >
ros::Time convenience_ros_functions::TypedSubscriber< MessageType >::lastUpdateTime [private]

Definition at line 98 of file TypedSubscriber.h.

template<class MessageType >
condition_variable convenience_ros_functions::TypedSubscriber< MessageType >::messageArrivedCondition [mutable, private]

Definition at line 92 of file TypedSubscriber.h.

template<class MessageType >
mutex convenience_ros_functions::TypedSubscriber< MessageType >::messageArrivedMutex [mutable, private]

Definition at line 94 of file TypedSubscriber.h.

template<class MessageType >
ros::NodeHandle& convenience_ros_functions::TypedSubscriber< MessageType >::node [private]

Definition at line 105 of file TypedSubscriber.h.

template<class MessageType >
bool convenience_ros_functions::TypedSubscriber< MessageType >::running [private]

Definition at line 100 of file TypedSubscriber.h.

template<class MessageType >
ros::Subscriber convenience_ros_functions::TypedSubscriber< MessageType >::sub [private]

Definition at line 107 of file TypedSubscriber.h.

template<class MessageType >
bool convenience_ros_functions::TypedSubscriber< MessageType >::subscriberActive [private]

Definition at line 101 of file TypedSubscriber.h.

template<class MessageType >
std::string convenience_ros_functions::TypedSubscriber< MessageType >::topic [private]

Definition at line 103 of file TypedSubscriber.h.


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


convenience_ros_functions
Author(s): Jennifer Buehler
autogenerated on Sat Mar 2 2019 03:21:42