Go to the documentation of this file.
22 #ifndef TOPIC_HANDLE_H
23 #define TOPIC_HANDLE_H
26 #include <std_msgs/Bool.h>
27 #include <geometry_msgs/Twist.h>
32 #include <boost/utility.hpp>
33 #include <boost/scoped_ptr.hpp>
69 "Topic handler '" <<
name_ <<
"' subscribed to topic '" <<
topic_ <<
71 ", priority = " <<
static_cast<int>(
priority_)
92 const std::string&
getName()
const
151 :
base_type(nh, name, topic, timeout, priority, mux)
161 void callback(
const geometry_msgs::TwistConstPtr& msg)
186 :
base_type(nh, name, topic, timeout, priority, mux)
200 void callback(
const std_msgs::BoolConstPtr& msg)
209 #endif // TOPIC_HANDLE_H
TopicHandle_(ros::NodeHandle &nh, const std::string &name, const std::string &topic, double timeout, priority_type priority, TwistMux *mux)
TopicHandle_.
TopicHandle_< geometry_msgs::Twist > base_type
static T clamp(T x, T min, T max)
Clamp a value to the range [min, max].
base_type::priority_type priority_type
const std::string & getName() const
const T & getMessage() const
void callback(const std_msgs::BoolConstPtr &msg)
LockTopicHandle(ros::NodeHandle &nh, const std::string &name, const std::string &topic, double timeout, priority_type priority, TwistMux *mux)
VelocityTopicHandle(ros::NodeHandle &nh, const std::string &name, const std::string &topic, double timeout, priority_type priority, TwistMux *mux)
bool hasExpired() const
hasExpired
void publishTwist(const geometry_msgs::TwistConstPtr &msg)
void callback(const geometry_msgs::TwistConstPtr &msg)
const T & getStamp() const
TopicHandle_< std_msgs::Bool > base_type
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
#define ROS_INFO_STREAM(args)
bool isLocked() const
isLocked
const priority_type & getPriority() const
getPriority Priority getter
bool hasPriority(const VelocityTopicHandle &twist)
base_type::priority_type priority_type
ros::Subscriber subscriber_
const double & getTimeout() const
const std::string & getTopic() const
bool isMasked(priority_type lock_priority) const
The TwistMux class implements a top-level twist multiplexer module that priorize different velocity c...
twist_mux
Author(s): Enrique Fernandez
, Siegfried-A. Gevatter Pujals
autogenerated on Wed Oct 26 2022 02:18:09