topic_handle.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (CC BY-NC-SA 4.0 License)
3  *
4  * Copyright (c) 2014, PAL Robotics, S.L.
5  * All rights reserved.
6  *
7  * This work is licensed under the Creative Commons
8  * Attribution-NonCommercial-ShareAlike 4.0 International License.
9  *
10  * To view a copy of this license, visit
11  * http://creativecommons.org/licenses/by-nc-sa/4.0/
12  * or send a letter to
13  * Creative Commons, 444 Castro Street, Suite 900,
14  * Mountain View, California, 94041, USA.
15  *********************************************************************/
16 
17 /*
18  * @author Enrique Fernandez
19  * @author Siegfried Gevatter
20  */
21 
22 #ifndef TOPIC_HANDLE_H
23 #define TOPIC_HANDLE_H
24 
25 #include <ros/ros.h>
26 #include <std_msgs/Bool.h>
27 #include <geometry_msgs/Twist.h>
28 
29 #include <twist_mux/utils.h>
30 #include <twist_mux/twist_mux.h>
31 
32 #include <boost/utility.hpp>
33 #include <boost/scoped_ptr.hpp>
34 
35 #include <string>
36 #include <vector>
37 
38 namespace twist_mux
39 {
40 
41 template<typename T>
42 class TopicHandle_ : boost::noncopyable
43 {
44 public:
45 
46  typedef int priority_type;
47 
58  TopicHandle_(ros::NodeHandle& nh, const std::string& name, const std::string& topic, double timeout, priority_type priority, TwistMux* mux)
59  : nh_(nh)
60  , name_(name)
61  , topic_(topic)
62  , timeout_(timeout)
63  , priority_(clamp(priority, priority_type(0), priority_type(255)))
64  , mux_(mux)
65  , stamp_(0.0)
66  {
68  (
69  "Topic handler '" << name_ << "' subscribed to topic '" << topic_ <<
70  "': timeout = " << ((timeout_) ? std::to_string(timeout_) + "s" : "None") <<
71  ", priority = " << static_cast<int>(priority_)
72  );
73  }
74 
75  virtual ~TopicHandle_()
76  {
78  }
79 
86  bool hasExpired() const
87  {
88  return (timeout_ > 0.0) &&
89  ((ros::Time::now() - stamp_).toSec() > timeout_);
90  }
91 
92  const std::string& getName() const
93  {
94  return name_;
95  }
96 
97  const std::string& getTopic() const
98  {
99  return topic_;
100  }
101 
102  const double& getTimeout() const
103  {
104  return timeout_;
105  }
106 
111  const priority_type& getPriority() const
112  {
113  return priority_;
114  }
115 
116  const T& getStamp() const
117  {
118  return stamp_;
119  }
120 
121  const T& getMessage() const
122  {
123  return msg_;
124  }
125 
126 protected:
128 
129  std::string name_;
130  std::string topic_;
132  double timeout_;
134 
135 protected:
136  TwistMux* mux_;
137 
139  T msg_;
140 };
141 
142 class VelocityTopicHandle : public TopicHandle_<geometry_msgs::Twist>
143 {
144 private:
146 
147 public:
148  typedef typename base_type::priority_type priority_type;
149 
150  VelocityTopicHandle(ros::NodeHandle& nh, const std::string& name, const std::string& topic, double timeout, priority_type priority, TwistMux* mux)
151  : base_type(nh, name, topic, timeout, priority, mux)
152  {
154  }
155 
156  bool isMasked(priority_type lock_priority) const
157  {
158  return hasExpired() || (getPriority() < lock_priority);
159  }
160 
161  void callback(const geometry_msgs::TwistConstPtr& msg)
162  {
164  msg_ = *msg;
165 
166  // Check if this twist has priority.
167  // Note that we have to check all the locks because they might time out
168  // and since we have several topics we must look for the highest one in
169  // all the topic list; so far there's no O(1) solution.
170  if (mux_->hasPriority(*this))
171  {
173  }
174  }
175 };
176 
177 class LockTopicHandle : public TopicHandle_<std_msgs::Bool>
178 {
179 private:
181 
182 public:
183  typedef typename base_type::priority_type priority_type;
184 
185  LockTopicHandle(ros::NodeHandle& nh, const std::string& name, const std::string& topic, double timeout, priority_type priority, TwistMux* mux)
186  : base_type(nh, name, topic, timeout, priority, mux)
187  {
189  }
190 
195  bool isLocked() const
196  {
197  return hasExpired() || getMessage().data;
198  }
199 
200  void callback(const std_msgs::BoolConstPtr& msg)
201  {
203  msg_ = *msg;
204  }
205 };
206 
207 } // namespace twist_mux
208 
209 #endif // TOPIC_HANDLE_H
twist_mux::TopicHandle_::TopicHandle_
TopicHandle_(ros::NodeHandle &nh, const std::string &name, const std::string &topic, double timeout, priority_type priority, TwistMux *mux)
TopicHandle_.
Definition: topic_handle.h:86
twist_mux::TopicHandle_::~TopicHandle_
virtual ~TopicHandle_()
Definition: topic_handle.h:103
twist_mux::VelocityTopicHandle::base_type
TopicHandle_< geometry_msgs::Twist > base_type
Definition: topic_handle.h:159
clamp
static T clamp(T x, T min, T max)
Clamp a value to the range [min, max].
Definition: utils.h:36
twist_mux::VelocityTopicHandle::priority_type
base_type::priority_type priority_type
Definition: topic_handle.h:162
msg
msg
twist_mux
Definition: topic_handle.h:38
twist_mux::TopicHandle_::priority_type
int priority_type
Definition: topic_handle.h:74
ros.h
twist_mux::TopicHandle_::getName
const std::string & getName() const
Definition: topic_handle.h:120
ros::Subscriber::shutdown
void shutdown()
twist_mux::TopicHandle_
Definition: topic_handle.h:56
twist_mux::TopicHandle_::stamp_
ros::Time stamp_
Definition: topic_handle.h:166
twist_mux::TopicHandle_::msg_
T msg_
Definition: topic_handle.h:167
twist_mux::TopicHandle_::getMessage
const T & getMessage() const
Definition: topic_handle.h:149
twist_mux::LockTopicHandle::callback
void callback(const std_msgs::BoolConstPtr &msg)
Definition: topic_handle.h:214
twist_mux::LockTopicHandle::LockTopicHandle
LockTopicHandle(ros::NodeHandle &nh, const std::string &name, const std::string &topic, double timeout, priority_type priority, TwistMux *mux)
Definition: topic_handle.h:199
twist_mux::VelocityTopicHandle::VelocityTopicHandle
VelocityTopicHandle(ros::NodeHandle &nh, const std::string &name, const std::string &topic, double timeout, priority_type priority, TwistMux *mux)
Definition: topic_handle.h:164
twist_mux::TopicHandle_::hasExpired
bool hasExpired() const
hasExpired
Definition: topic_handle.h:114
utils.h
twist_mux::VelocityTopicHandle
Definition: topic_handle.h:156
twist_mux::TopicHandle_::topic_
std::string topic_
Definition: topic_handle.h:158
twist_mux::TwistMux::publishTwist
void publishTwist(const geometry_msgs::TwistConstPtr &msg)
Definition: twist_mux.cpp:83
twist_mux::TopicHandle_::mux_
TwistMux * mux_
Definition: topic_handle.h:164
twist_mux::VelocityTopicHandle::callback
void callback(const geometry_msgs::TwistConstPtr &msg)
Definition: topic_handle.h:175
twist_mux::TopicHandle_::getStamp
const T & getStamp() const
Definition: topic_handle.h:144
twist_mux::LockTopicHandle::base_type
TopicHandle_< std_msgs::Bool > base_type
Definition: topic_handle.h:194
ros::NodeHandle::subscribe
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())
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
twist_mux::LockTopicHandle::isLocked
bool isLocked() const
isLocked
Definition: topic_handle.h:209
twist_mux::TopicHandle_::getPriority
const priority_type & getPriority() const
getPriority Priority getter
Definition: topic_handle.h:139
twist_mux::TwistMux::hasPriority
bool hasPriority(const VelocityTopicHandle &twist)
Definition: twist_mux.cpp:141
twist_mux::TopicHandle_::nh_
ros::NodeHandle nh_
Definition: topic_handle.h:155
ros::Time
twist_mux.h
twist_mux::TopicHandle_::timeout_
double timeout_
Definition: topic_handle.h:160
twist_mux::LockTopicHandle::priority_type
base_type::priority_type priority_type
Definition: topic_handle.h:197
twist_mux::TopicHandle_::subscriber_
ros::Subscriber subscriber_
Definition: topic_handle.h:159
twist_mux::LockTopicHandle
Definition: topic_handle.h:191
twist_mux::TopicHandle_::getTimeout
const double & getTimeout() const
Definition: topic_handle.h:130
twist_mux::TopicHandle_::getTopic
const std::string & getTopic() const
Definition: topic_handle.h:125
twist_mux::TopicHandle_::priority_
priority_type priority_
Definition: topic_handle.h:161
ros::NodeHandle
ros::Subscriber
twist_mux::TopicHandle_::name_
std::string name_
Definition: topic_handle.h:157
ros::Time::now
static Time now()
twist_mux::VelocityTopicHandle::isMasked
bool isMasked(priority_type lock_priority) const
Definition: topic_handle.h:170
twist_mux::TwistMux
The TwistMux class implements a top-level twist multiplexer module that priorize different velocity c...
Definition: twist_mux.h:58


twist_mux
Author(s): Enrique Fernandez , Siegfried-A. Gevatter Pujals
autogenerated on Wed Oct 26 2022 02:18:09