#include <topic_handle.h>
|
| 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_type & | getPriority () 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_ () |
| |
Definition at line 177 of file topic_handle.h.
◆ base_type
◆ priority_type
◆ LockTopicHandle()
◆ callback()
| void twist_mux::LockTopicHandle::callback |
( |
const std_msgs::BoolConstPtr & |
msg | ) |
|
|
inline |
◆ 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: