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

#include <topic_handle.h>

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

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 More...
 
const T & getStamp () const
 
const double & getTimeout () const
 
const std::string & getTopic () const
 
bool hasExpired () const
 hasExpired More...
 
 TopicHandle_ (ros::NodeHandle &nh, const std::string &name, const std::string &topic, double timeout, priority_type priority, TwistMux *mux)
 TopicHandle_. More...
 
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 56 of file topic_handle.h.

Member Typedef Documentation

◆ priority_type

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

Definition at line 74 of file topic_handle.h.

Constructor & Destructor Documentation

◆ TopicHandle_()

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

◆ ~TopicHandle_()

template<typename T >
virtual twist_mux::TopicHandle_< T >::~TopicHandle_ ( )
inlinevirtual

Definition at line 103 of file topic_handle.h.

Member Function Documentation

◆ getMessage()

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

Definition at line 149 of file topic_handle.h.

◆ getName()

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

Definition at line 120 of file topic_handle.h.

◆ getPriority()

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

getPriority Priority getter

Returns
Priority

Definition at line 139 of file topic_handle.h.

◆ getStamp()

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

Definition at line 144 of file topic_handle.h.

◆ getTimeout()

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

Definition at line 130 of file topic_handle.h.

◆ getTopic()

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

Definition at line 125 of file topic_handle.h.

◆ hasExpired()

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 114 of file topic_handle.h.

Member Data Documentation

◆ msg_

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

Definition at line 167 of file topic_handle.h.

◆ mux_

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

Definition at line 164 of file topic_handle.h.

◆ name_

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

Definition at line 157 of file topic_handle.h.

◆ nh_

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

Definition at line 155 of file topic_handle.h.

◆ priority_

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

Definition at line 161 of file topic_handle.h.

◆ stamp_

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

Definition at line 166 of file topic_handle.h.

◆ subscriber_

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

Definition at line 159 of file topic_handle.h.

◆ timeout_

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

Definition at line 160 of file topic_handle.h.

◆ topic_

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

Definition at line 158 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 Wed Oct 26 2022 02:18:09