velocity_smoother_nodelet.cpp
Go to the documentation of this file.
1 
9 /*****************************************************************************
10  ** Includes
11  *****************************************************************************/
12 
13 #include <ros/ros.h>
14 #include <nodelet/nodelet.h>
16 
17 #include <dynamic_reconfigure/server.h>
18 #include <yocs_velocity_smoother/paramsConfig.h>
19 
20 #include <ecl/threads/thread.hpp>
21 
23 
24 /*****************************************************************************
25  ** Preprocessing
26  *****************************************************************************/
27 
28 #define PERIOD_RECORD_SIZE 5
29 #define ZERO_VEL_COMMAND geometry_msgs::Twist();
30 #define IS_ZERO_VEOCITY(a) ((a.linear.x == 0.0) && (a.angular.z == 0.0))
31 
32 /*****************************************************************************
33 ** Namespaces
34 *****************************************************************************/
35 
36 namespace yocs_velocity_smoother {
37 
38 /*********************
39 ** Implementation
40 **********************/
41 
42 VelocitySmoother::VelocitySmoother(const std::string &name)
43 : name(name)
44 , quiet(false)
45 , shutdown_req(false)
46 , input_active(false)
47 , pr_next(0)
48 , dynamic_reconfigure_server(NULL)
49 {
50 };
51 
52 void VelocitySmoother::reconfigCB(yocs_velocity_smoother::paramsConfig &config, uint32_t level)
53 {
54  ROS_INFO("Reconfigure request : %f %f %f %f %f",
55  config.speed_lim_v, config.speed_lim_w, config.accel_lim_v, config.accel_lim_w, config.decel_factor);
56 
57  speed_lim_v = config.speed_lim_v;
58  speed_lim_w = config.speed_lim_w;
59  accel_lim_v = config.accel_lim_v;
60  accel_lim_w = config.accel_lim_w;
61  decel_factor = config.decel_factor;
64 }
65 
66 void VelocitySmoother::velocityCB(const geometry_msgs::Twist::ConstPtr& msg)
67 {
68  // Estimate commands frequency; we do continuously as it can be very different depending on the
69  // publisher type, and we don't want to impose extra constraints to keep this package flexible
70  if (period_record.size() < PERIOD_RECORD_SIZE)
71  {
72  period_record.push_back((ros::Time::now() - last_cb_time).toSec());
73  }
74  else
75  {
77  }
78 
79  pr_next++;
80  pr_next %= period_record.size();
82 
83  if (period_record.size() <= PERIOD_RECORD_SIZE/2)
84  {
85  // wait until we have some values; make a reasonable assumption (10 Hz) meanwhile
86  cb_avg_time = 0.1;
87  }
88  else
89  {
90  // enough; recalculate with the latest input
92  }
93 
94  input_active = true;
95 
96  // Bound speed with the maximum values
97  target_vel.linear.x =
98  msg->linear.x > 0.0 ? std::min(msg->linear.x, speed_lim_v) : std::max(msg->linear.x, -speed_lim_v);
99  target_vel.angular.z =
100  msg->angular.z > 0.0 ? std::min(msg->angular.z, speed_lim_w) : std::max(msg->angular.z, -speed_lim_w);
101 }
102 
103 void VelocitySmoother::odometryCB(const nav_msgs::Odometry::ConstPtr& msg)
104 {
105  if (robot_feedback == ODOMETRY)
106  current_vel = msg->twist.twist;
107 
108  // ignore otherwise
109 }
110 
111 void VelocitySmoother::robotVelCB(const geometry_msgs::Twist::ConstPtr& msg)
112 {
113  if (robot_feedback == COMMANDS)
114  current_vel = *msg;
115 
116  // ignore otherwise
117 }
118 
120 {
121  double period = 1.0/frequency;
122  ros::Rate spin_rate(frequency);
123 
124  while (! shutdown_req && ros::ok())
125  {
126  if ((input_active == true) && (cb_avg_time > 0.0) &&
127  ((ros::Time::now() - last_cb_time).toSec() > std::min(3.0*cb_avg_time, 0.5)))
128  {
129  // Velocity input no active anymore; normally last command is a zero-velocity one, but reassure
130  // this, just in case something went wrong with our input, or he just forgot good manners...
131  // Issue #2, extra check in case cb_avg_time is very big, for example with several atomic commands
132  // The cb_avg_time > 0 check is required to deal with low-rate simulated time, that can make that
133  // several messages arrive with the same time and so lead to a zero median
134  input_active = false;
135  if (IS_ZERO_VEOCITY(target_vel) == false)
136  {
137  ROS_WARN_STREAM("Velocity Smoother : input got inactive leaving us a non-zero target velocity ("
138  << target_vel.linear.x << ", " << target_vel.angular.z << "), zeroing...[" << name << "]");
140  }
141  }
142 
143  if ((robot_feedback != NONE) && (input_active == true) && (cb_avg_time > 0.0) &&
144  (((ros::Time::now() - last_cb_time).toSec() > 5.0*cb_avg_time) || // 5 missing msgs
145  (std::abs(current_vel.linear.x - last_cmd_vel.linear.x) > 0.2) ||
146  (std::abs(current_vel.angular.z - last_cmd_vel.angular.z) > 2.0)))
147  {
148  // If the publisher has been inactive for a while, or if our current commanding differs a lot
149  // from robot velocity feedback, we cannot trust the former; relay on robot's feedback instead
150  // TODO: current command/feedback difference thresholds are 진짜 arbitrary; they should somehow
151  // be proportional to max v and w...
152  // The one for angular velocity is very big because is it's less necessary (for example the
153  // reactive controller will never make the robot spin) and because the gyro has a 15 ms delay
154  if ( !quiet ) {
155  // this condition can be unavoidable due to preemption of current velocity control on
156  // velocity multiplexer so be quiet if we're instructed to do so
157  ROS_WARN_STREAM("Velocity Smoother : using robot velocity feedback " <<
158  std::string(robot_feedback == ODOMETRY ? "odometry" : "end commands") <<
159  " instead of last command: " <<
160  (ros::Time::now() - last_cb_time).toSec() << ", " <<
161  current_vel.linear.x - last_cmd_vel.linear.x << ", " <<
162  current_vel.angular.z - last_cmd_vel.angular.z << ", [" << name << "]"
163  );
164  }
166  }
167 
168  geometry_msgs::TwistPtr cmd_vel;
169 
170  if ((target_vel.linear.x != last_cmd_vel.linear.x) ||
171  (target_vel.angular.z != last_cmd_vel.angular.z))
172  {
173  // Try to reach target velocity ensuring that we don't exceed the acceleration limits
174  cmd_vel.reset(new geometry_msgs::Twist(target_vel));
175 
176  double v_inc, w_inc, max_v_inc, max_w_inc;
177 
178  v_inc = target_vel.linear.x - last_cmd_vel.linear.x;
179  if ((robot_feedback == ODOMETRY) && (current_vel.linear.x*target_vel.linear.x < 0.0))
180  {
181  // countermarch (on robots with significant inertia; requires odometry feedback to be detected)
182  max_v_inc = decel_lim_v*period;
183  }
184  else
185  {
186  max_v_inc = ((v_inc*target_vel.linear.x > 0.0)?accel_lim_v:decel_lim_v)*period;
187  }
188 
189  w_inc = target_vel.angular.z - last_cmd_vel.angular.z;
190  if ((robot_feedback == ODOMETRY) && (current_vel.angular.z*target_vel.angular.z < 0.0))
191  {
192  // countermarch (on robots with significant inertia; requires odometry feedback to be detected)
193  max_w_inc = decel_lim_w*period;
194  }
195  else
196  {
197  max_w_inc = ((w_inc*target_vel.angular.z > 0.0)?accel_lim_w:decel_lim_w)*period;
198  }
199 
200  // Calculate and normalise vectors A (desired velocity increment) and B (maximum velocity increment),
201  // where v acts as coordinate x and w as coordinate y; the sign of the angle from A to B determines
202  // which velocity (v or w) must be overconstrained to keep the direction provided as command
203  double MA = sqrt( v_inc * v_inc + w_inc * w_inc);
204  double MB = sqrt(max_v_inc * max_v_inc + max_w_inc * max_w_inc);
205 
206  double Av = std::abs(v_inc) / MA;
207  double Aw = std::abs(w_inc) / MA;
208  double Bv = max_v_inc / MB;
209  double Bw = max_w_inc / MB;
210  double theta = atan2(Bw, Bv) - atan2(Aw, Av);
211 
212  if (theta < 0)
213  {
214  // overconstrain linear velocity
215  max_v_inc = (max_w_inc*std::abs(v_inc))/std::abs(w_inc);
216  }
217  else
218  {
219  // overconstrain angular velocity
220  max_w_inc = (max_v_inc*std::abs(w_inc))/std::abs(v_inc);
221  }
222 
223  if (std::abs(v_inc) > max_v_inc)
224  {
225  // we must limit linear velocity
226  cmd_vel->linear.x = last_cmd_vel.linear.x + sign(v_inc)*max_v_inc;
227  }
228 
229  if (std::abs(w_inc) > max_w_inc)
230  {
231  // we must limit angular velocity
232  cmd_vel->angular.z = last_cmd_vel.angular.z + sign(w_inc)*max_w_inc;
233  }
234 
235  smooth_vel_pub.publish(cmd_vel);
236  last_cmd_vel = *cmd_vel;
237  }
238  else if (input_active == true)
239  {
240  // We already reached target velocity; just keep resending last command while input is active
241  cmd_vel.reset(new geometry_msgs::Twist(last_cmd_vel));
242  smooth_vel_pub.publish(cmd_vel);
243  }
244 
245  spin_rate.sleep();
246  }
247 }
248 
255 {
256  // Dynamic Reconfigure
257  dynamic_reconfigure_callback = boost::bind(&VelocitySmoother::reconfigCB, this, _1, _2);
258 
259  dynamic_reconfigure_server = new dynamic_reconfigure::Server<yocs_velocity_smoother::paramsConfig>(nh);
261 
262  // Optional parameters
263  int feedback;
264  nh.param("frequency", frequency, 20.0);
265  nh.param("quiet", quiet, quiet);
266  nh.param("decel_factor", decel_factor, 1.0);
267  nh.param("robot_feedback", feedback, (int)NONE);
268 
269  if ((int(feedback) < NONE) || (int(feedback) > COMMANDS))
270  {
271  ROS_WARN("Invalid robot feedback type (%d). Valid options are 0 (NONE, default), 1 (ODOMETRY) and 2 (COMMANDS)",
272  feedback);
273  feedback = NONE;
274  }
275 
276  robot_feedback = static_cast<RobotFeedbackType>(feedback);
277 
278  // Mandatory parameters
279  if ((nh.getParam("speed_lim_v", speed_lim_v) == false) ||
280  (nh.getParam("speed_lim_w", speed_lim_w) == false))
281  {
282  ROS_ERROR("Missing velocity limit parameter(s)");
283  return false;
284  }
285 
286  if ((nh.getParam("accel_lim_v", accel_lim_v) == false) ||
287  (nh.getParam("accel_lim_w", accel_lim_w) == false))
288  {
289  ROS_ERROR("Missing acceleration limit parameter(s)");
290  return false;
291  }
292 
293  // Deceleration can be more aggressive, if necessary
296 
297  // Publishers and subscribers
298  odometry_sub = nh.subscribe("odometry", 1, &VelocitySmoother::odometryCB, this);
299  current_vel_sub = nh.subscribe("robot_cmd_vel", 1, &VelocitySmoother::robotVelCB, this);
300  raw_in_vel_sub = nh.subscribe("raw_cmd_vel", 1, &VelocitySmoother::velocityCB, this);
301  smooth_vel_pub = nh.advertise <geometry_msgs::Twist> ("smooth_cmd_vel", 1);
302 
303  return true;
304 }
305 
306 
307 /*********************
308 ** Nodelet
309 **********************/
310 
312 {
313 public:
316  {
317  NODELET_DEBUG("Velocity Smoother : waiting for worker thread to finish...");
318  vel_smoother_->shutdown();
319  worker_thread_.join();
320  }
321 
322  std::string unresolvedName(const std::string &name) const {
323  size_t pos = name.find_last_of('/');
324  return name.substr(pos + 1);
325  }
326 
327 
328  virtual void onInit()
329  {
330  ros::NodeHandle ph = getPrivateNodeHandle();
331  std::string resolved_name = ph.getUnresolvedNamespace(); // this always returns like /robosem/goo_arm - why not unresolved?
332  std::string name = unresolvedName(resolved_name); // unresolve it ourselves
333  NODELET_DEBUG_STREAM("Velocity Smoother : initialising nodelet...[" << name << "]");
334  vel_smoother_.reset(new VelocitySmoother(name));
335  if (vel_smoother_->init(ph))
336  {
337  NODELET_DEBUG_STREAM("Velocity Smoother : nodelet initialised [" << name << "]");
338  worker_thread_.start(&VelocitySmoother::spin, *vel_smoother_);
339  }
340  else
341  {
342  NODELET_ERROR_STREAM("Velocity Smoother : nodelet initialisation failed [" << name << "]");
343  }
344  }
345 
346 private:
348  ecl::Thread worker_thread_;
349 };
350 
351 } // namespace yocs_velocity_smoother
352 
const std::string & getUnresolvedNamespace() const
void robotVelCB(const geometry_msgs::Twist::ConstPtr &msg)
void publish(const boost::shared_ptr< M > &message) const
std::string unresolvedName(const std::string &name) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
#define IS_ZERO_VEOCITY(a)
void velocityCB(const geometry_msgs::Twist::ConstPtr &msg)
enum yocs_velocity_smoother::VelocitySmoother::RobotFeedbackType robot_feedback
#define ROS_WARN(...)
PLUGINLIB_EXPORT_CLASS(yocs_velocity_smoother::VelocitySmootherNodelet, nodelet::Nodelet)
#define NODELET_ERROR_STREAM(...)
void odometryCB(const nav_msgs::Odometry::ConstPtr &msg)
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define PERIOD_RECORD_SIZE
#define ROS_WARN_STREAM(args)
#define NODELET_DEBUG_STREAM(...)
bool sleep()
#define ZERO_VEL_COMMAND
void reconfigCB(yocs_velocity_smoother::paramsConfig &config, uint32_t unused_level)
dynamic_reconfigure::Server< yocs_velocity_smoother::paramsConfig >::CallbackType dynamic_reconfigure_callback
dynamic_reconfigure::Server< yocs_velocity_smoother::paramsConfig > * dynamic_reconfigure_server
bool getParam(const std::string &key, std::string &s) const
double median(std::vector< double > values)
static Time now()
Velocity smoother interface.
#define ROS_ERROR(...)
#define NODELET_DEBUG(...)


yocs_velocity_smoother
Author(s): Jorge Santos Simon
autogenerated on Mon Jun 10 2019 15:54:03