#include <topic_handle.h>
Public Types | |
typedef base_type::priority_type | priority_type |
Public Member Functions | |
void | callback (const std_msgs::BoolConstPtr &msg) |
bool | isLocked () const |
isLocked | |
LockTopicHandle (ros::NodeHandle &nh, const std::string &name, const std::string &topic, double timeout, priority_type priority, TwistMux *mux) | |
Private Types | |
typedef TopicHandle_ < std_msgs::Bool > | base_type |
Definition at line 177 of file topic_handle.h.
typedef TopicHandle_<std_msgs::Bool> twist_mux::LockTopicHandle::base_type [private] |
Definition at line 180 of file topic_handle.h.
Reimplemented from twist_mux::TopicHandle_< std_msgs::Bool >.
Definition at line 183 of file topic_handle.h.
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.
void twist_mux::LockTopicHandle::callback | ( | const std_msgs::BoolConstPtr & | msg | ) | [inline] |
Definition at line 200 of file topic_handle.h.
bool twist_mux::LockTopicHandle::isLocked | ( | ) | const [inline] |
isLocked
Definition at line 195 of file topic_handle.h.