#include <topic_handle.h>
Public Types | |
typedef base_type::priority_type | priority_type |
Public Member Functions | |
void | callback (const geometry_msgs::TwistConstPtr &msg) |
bool | isMasked (priority_type lock_priority) const |
VelocityTopicHandle (ros::NodeHandle &nh, const std::string &name, const std::string &topic, double timeout, priority_type priority, TwistMux *mux) | |
Private Types | |
typedef TopicHandle_ < geometry_msgs::Twist > | base_type |
Definition at line 142 of file topic_handle.h.
typedef TopicHandle_<geometry_msgs::Twist> twist_mux::VelocityTopicHandle::base_type [private] |
Definition at line 145 of file topic_handle.h.
Reimplemented from twist_mux::TopicHandle_< geometry_msgs::Twist >.
Definition at line 148 of file topic_handle.h.
twist_mux::VelocityTopicHandle::VelocityTopicHandle | ( | ros::NodeHandle & | nh, |
const std::string & | name, | ||
const std::string & | topic, | ||
double | timeout, | ||
priority_type | priority, | ||
TwistMux * | mux | ||
) | [inline] |
Definition at line 150 of file topic_handle.h.
void twist_mux::VelocityTopicHandle::callback | ( | const geometry_msgs::TwistConstPtr & | msg | ) | [inline] |
Definition at line 161 of file topic_handle.h.
bool twist_mux::VelocityTopicHandle::isMasked | ( | priority_type | lock_priority | ) | const [inline] |
Definition at line 156 of file topic_handle.h.