Public Types | Public Member Functions | Protected Attributes
twist_mux::TopicHandle_< T > Class Template Reference

#include <topic_handle.h>

Inheritance diagram for twist_mux::TopicHandle_< T >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef int priority_type

Public Member Functions

const T & getMessage () const
const std::string & getName () const
const priority_typegetPriority () const
 getPriority Priority getter
const T & getStamp () const
const double & getTimeout () const
const std::string & getTopic () const
bool hasExpired () const
 hasExpired
 TopicHandle_ (ros::NodeHandle &nh, const std::string &name, const std::string &topic, double timeout, priority_type priority, TwistMux *mux)
 TopicHandle_.
virtual ~TopicHandle_ ()

Protected Attributes

msg_
TwistMuxmux_
std::string name_
ros::NodeHandle nh_
priority_type priority_
ros::Time stamp_
ros::Subscriber subscriber_
double timeout_
std::string topic_

Detailed Description

template<typename T>
class twist_mux::TopicHandle_< T >

Definition at line 42 of file topic_handle.h.


Member Typedef Documentation

template<typename T>
typedef int twist_mux::TopicHandle_< T >::priority_type

Reimplemented in twist_mux::LockTopicHandle, and twist_mux::VelocityTopicHandle.

Definition at line 46 of file topic_handle.h.


Constructor & Destructor Documentation

template<typename T>
twist_mux::TopicHandle_< T >::TopicHandle_ ( ros::NodeHandle nh,
const std::string &  name,
const std::string &  topic,
double  timeout,
priority_type  priority,
TwistMux mux 
) [inline]

TopicHandle_.

Parameters:
nhNode handle
nameName identifier
topicTopic name
timeoutTimeout to consider that the messages are old; note that initially the message stamp is set to 0.0, so the message has expired
priorityPriority of the topic

Definition at line 58 of file topic_handle.h.

template<typename T>
virtual twist_mux::TopicHandle_< T >::~TopicHandle_ ( ) [inline, virtual]

Definition at line 75 of file topic_handle.h.


Member Function Documentation

template<typename T>
const T& twist_mux::TopicHandle_< T >::getMessage ( ) const [inline]

Definition at line 121 of file topic_handle.h.

template<typename T>
const std::string& twist_mux::TopicHandle_< T >::getName ( ) const [inline]

Definition at line 92 of file topic_handle.h.

template<typename T>
const priority_type& twist_mux::TopicHandle_< T >::getPriority ( ) const [inline]

getPriority Priority getter

Returns:
Priority

Definition at line 111 of file topic_handle.h.

template<typename T>
const T& twist_mux::TopicHandle_< T >::getStamp ( ) const [inline]

Definition at line 116 of file topic_handle.h.

template<typename T>
const double& twist_mux::TopicHandle_< T >::getTimeout ( ) const [inline]

Definition at line 102 of file topic_handle.h.

template<typename T>
const std::string& twist_mux::TopicHandle_< T >::getTopic ( ) const [inline]

Definition at line 97 of file topic_handle.h.

template<typename T>
bool twist_mux::TopicHandle_< T >::hasExpired ( ) const [inline]

hasExpired

Returns:
true if the message has expired; false otherwise. If the timeout is set to 0.0, this function always returns false

Definition at line 86 of file topic_handle.h.


Member Data Documentation

template<typename T>
T twist_mux::TopicHandle_< T >::msg_ [protected]

Definition at line 139 of file topic_handle.h.

template<typename T>
TwistMux* twist_mux::TopicHandle_< T >::mux_ [protected]

Definition at line 136 of file topic_handle.h.

template<typename T>
std::string twist_mux::TopicHandle_< T >::name_ [protected]

Definition at line 129 of file topic_handle.h.

template<typename T>
ros::NodeHandle twist_mux::TopicHandle_< T >::nh_ [protected]

Definition at line 127 of file topic_handle.h.

template<typename T>
priority_type twist_mux::TopicHandle_< T >::priority_ [protected]

Definition at line 133 of file topic_handle.h.

template<typename T>
ros::Time twist_mux::TopicHandle_< T >::stamp_ [protected]

Definition at line 138 of file topic_handle.h.

template<typename T>
ros::Subscriber twist_mux::TopicHandle_< T >::subscriber_ [protected]

Definition at line 131 of file topic_handle.h.

template<typename T>
double twist_mux::TopicHandle_< T >::timeout_ [protected]

Definition at line 132 of file topic_handle.h.

template<typename T>
std::string twist_mux::TopicHandle_< T >::topic_ [protected]

Definition at line 130 of file topic_handle.h.


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


twist_mux
Author(s): Enrique Fernandez , Siegfried-A. Gevatter Pujals
autogenerated on Sat Jun 8 2019 20:13:46