Public Types | Public Member Functions | Private Types | List of all members
twist_mux::LockTopicHandle Class Reference

#include <topic_handle.h>

Inheritance diagram for twist_mux::LockTopicHandle:
Inheritance graph
[legend]

Public Types

typedef base_type::priority_type priority_type
 
- Public Types inherited from twist_mux::TopicHandle_< std_msgs::Bool >
typedef int priority_type
 

Public Member Functions

void callback (const std_msgs::BoolConstPtr &msg)
 
bool isLocked () const
 isLocked More...
 
 LockTopicHandle (ros::NodeHandle &nh, const std::string &name, const std::string &topic, double timeout, priority_type priority, TwistMux *mux)
 
- Public Member Functions inherited from twist_mux::TopicHandle_< std_msgs::Bool >
const std_msgs::Bool & getMessage () const
 
const std::string & getName () const
 
const priority_typegetPriority () const
 getPriority Priority getter More...
 
const std_msgs::Bool & 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_ ()
 

Private Types

typedef TopicHandle_< std_msgs::Bool > base_type
 

Additional Inherited Members

- Protected Attributes inherited from twist_mux::TopicHandle_< std_msgs::Bool >
std_msgs::Bool msg_
 
TwistMuxmux_
 
std::string name_
 
ros::NodeHandle nh_
 
priority_type priority_
 
ros::Time stamp_
 
ros::Subscriber subscriber_
 
double timeout_
 
std::string topic_
 

Detailed Description

Definition at line 177 of file topic_handle.h.

Member Typedef Documentation

◆ base_type

typedef TopicHandle_<std_msgs::Bool> twist_mux::LockTopicHandle::base_type
private

Definition at line 180 of file topic_handle.h.

◆ priority_type

Definition at line 183 of file topic_handle.h.

Constructor & Destructor Documentation

◆ LockTopicHandle()

twist_mux::LockTopicHandle::LockTopicHandle ( ros::NodeHandle nh,
const std::string &  name,
const std::string &  topic,
double  timeout,
priority_type  priority,
TwistMux mux 
)
inline

Definition at line 185 of file topic_handle.h.

Member Function Documentation

◆ callback()

void twist_mux::LockTopicHandle::callback ( const std_msgs::BoolConstPtr &  msg)
inline

Definition at line 200 of file topic_handle.h.

◆ isLocked()

bool twist_mux::LockTopicHandle::isLocked ( ) const
inline

isLocked

Returns
true if has expired or locked (i.e. bool message data is true)

Definition at line 195 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:14:17