velocity_smoother.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 /*****************************************************************************
18  ** Includes
19  *****************************************************************************/
20 
21 #include <ros/ros.h>
22 
23 #include <dynamic_reconfigure/server.h>
25 
26 #include <boost/thread.hpp>
27 
28 /*****************************************************************************
29  ** Preprocessing
30  *****************************************************************************/
31 
32 #define PERIOD_RECORD_SIZE 5
33 #define ZERO_VEL_COMMAND geometry_msgs::Twist();
34 #define IS_ZERO_VEOCITY(a) ((a.linear.x == 0.0) && (a.linear.y == 0.0) && (a.angular.z == 0.0))
35 
36 /*****************************************************************************
37 ** Namespaces
38 *****************************************************************************/
39 
41 
42 /*********************
43 ** Implementation
44 **********************/
45 
46 VelocitySmoother::VelocitySmoother(const std::string &name)
47 : name(name)
48 , shutdown_req(false)
49 , input_active(false)
50 , pr_next(0)
51 , dynamic_reconfigure_server(NULL)
52 {
53 }
54 
55 void VelocitySmoother::reconfigCB(cob_base_velocity_smoother::paramsConfig &config, uint32_t level)
56 {
57  ROS_INFO("Reconfigure request : %f %f %f %f %f %f %f %f",
58  config.speed_lim_vx, config.speed_lim_vy, config.speed_lim_w, config.accel_lim_vx, config.accel_lim_vy, config.accel_lim_w, config.decel_factor, config.decel_factor_safe);
59 
60  speed_lim_vx = config.speed_lim_vx;
61  speed_lim_vy = config.speed_lim_vy;
62  speed_lim_w = config.speed_lim_w;
63  accel_lim_vx = config.accel_lim_vx;
64  accel_lim_vy = config.accel_lim_vy;
65  accel_lim_w = config.accel_lim_w;
66  decel_factor = config.decel_factor;
67  decel_factor_safe = config.decel_factor_safe;
74 }
75 
76 void VelocitySmoother::velocityCB(const geometry_msgs::Twist::ConstPtr& msg)
77 {
78  // Estimate commands frequency; we do continuously as it can be very different depending on the
79  // publisher type, and we don't want to impose extra constraints to keep this package flexible
80  if (period_record.size() < PERIOD_RECORD_SIZE)
81  {
82  period_record.push_back((ros::Time::now() - last_cb_time).toSec());
83  }
84  else
85  {
87  }
88 
89  pr_next++;
90  pr_next %= period_record.size();
92 
93  if (period_record.size() <= PERIOD_RECORD_SIZE/2)
94  {
95  // wait until we have some values; make a reasonable assumption (10 Hz) meanwhile
96  cb_avg_time = 0.1;
97  }
98  else
99  {
100  // enough; recalculate with the latest input
102  }
103 
104  input_active = true;
105 
106  // Bound speed with the maximum values
107  target_vel.linear.x =
108  msg->linear.x > 0.0 ? std::min(msg->linear.x, speed_lim_vx) : std::max(msg->linear.x, -speed_lim_vx);
109  target_vel.linear.y =
110  msg->linear.y > 0.0 ? std::min(msg->linear.y, speed_lim_vy) : std::max(msg->linear.y, -speed_lim_vy);
111  target_vel.angular.z =
112  msg->angular.z > 0.0 ? std::min(msg->angular.z, speed_lim_w) : std::max(msg->angular.z, -speed_lim_w);
113 }
114 
115 void VelocitySmoother::odometryCB(const nav_msgs::Odometry::ConstPtr& msg)
116 {
117  if (robot_feedback == ODOMETRY)
118  current_vel = msg->twist.twist;
119 
120  // ignore otherwise
121 }
122 
123 void VelocitySmoother::robotVelCB(const geometry_msgs::Twist::ConstPtr& msg)
124 {
125  if (robot_feedback == COMMANDS)
126  current_vel = *msg;
127 
128  // ignore otherwise
129 }
130 
132 {
133  double period = 1.0/frequency;
134  ros::Rate spin_rate(frequency);
135 
136  double decel_vx;
137  double decel_vy;
138  double decel_w;
139 
140  while (! shutdown_req && ros::ok())
141  {
142  if ((input_active == true) && (cb_avg_time > 0.0) &&
143  ((ros::Time::now() - last_cb_time).toSec() > std::min(3.0*cb_avg_time, 0.5)))
144  {
145  // Velocity input no active anymore; normally last command is a zero-velocity one, but reassure
146  // this, just in case something went wrong with our input, or he just forgot good manners...
147  // Issue #2, extra check in case cb_avg_time is very big, for example with several atomic commands
148  // The cb_avg_time > 0 check is required to deal with low-rate simulated time, that can make that
149  // several messages arrive with the same time and so lead to a zero median
150  input_active = false;
151  if (IS_ZERO_VEOCITY(target_vel) == false)
152  {
153  ROS_WARN_STREAM("Velocity Smoother : input got inactive leaving us a non-zero target velocity ("
154  << target_vel.linear.x << ", " << target_vel.linear.y << ", " << target_vel.angular.z << "), zeroing...[" << name << "]");
156  }
157  }
158 
159  if(input_active)
160  {
161  decel_vx = decel_lim_vx;
162  decel_vy = decel_lim_vy;
163  decel_w = decel_lim_w;
164  }
165  else
166  {
167  //increase decel factor because this is a safty case, no more commands means we should stop as fast as it is safe
168  decel_vx = decel_lim_vx_safe;
169  decel_vy = decel_lim_vy_safe;
170  decel_w = decel_lim_w_safe;
171  }
172 
173  if ((robot_feedback != NONE) && (input_active == true) && (cb_avg_time > 0.0) &&
174  (((ros::Time::now() - last_cb_time).toSec() > 5.0*cb_avg_time) || // 5 missing msgs
175  (std::abs(current_vel.linear.x - last_cmd_vel.linear.x) > 0.2) ||
176  (std::abs(current_vel.linear.y - last_cmd_vel.linear.y) > 0.2) ||
177  (std::abs(current_vel.angular.z - last_cmd_vel.angular.z) > 2.0)))
178  {
179  // If the publisher has been inactive for a while, or if our current commanding differs a lot
180  // from robot velocity feedback, we cannot trust the former; relay on robot's feedback instead
181  // This can happen mainly due to preemption of current controller on velocity multiplexer.
182  // TODO: current command/feedback difference thresholds are 진짜 arbitrary; they should somehow
183  // be proportional to max v and w...
184  // The one for angular velocity is very big because is it's less necessary (for example the
185  // reactive controller will never make the robot spin) and because the gyro has a 15 ms delay
186  ROS_WARN("Using robot velocity feedback (%s) instead of last command: %f, %f, %f, %f",
187  robot_feedback == ODOMETRY ? "odometry" : "end commands",
188  (ros::Time::now() - last_cb_time).toSec(),
189  current_vel.linear.x - last_cmd_vel.linear.x,
190  current_vel.linear.y - last_cmd_vel.linear.y,
191  current_vel.angular.z - last_cmd_vel.angular.z);
193  }
194 
195  geometry_msgs::TwistPtr cmd_vel;
196 
197  if ((target_vel.linear.x != last_cmd_vel.linear.x) ||
198  (target_vel.linear.y != last_cmd_vel.linear.y) ||
199  (target_vel.angular.z != last_cmd_vel.angular.z))
200  {
201  // Try to reach target velocity ensuring that we don't exceed the acceleration limits
202  cmd_vel.reset(new geometry_msgs::Twist(target_vel));
203 
204  double vx_inc, vy_inc, w_inc, max_vx_inc, max_vy_inc, max_w_inc;
205 
206  vx_inc = target_vel.linear.x - last_cmd_vel.linear.x;
207  if ((robot_feedback == ODOMETRY) && (current_vel.linear.x*target_vel.linear.x < 0.0))
208  {
209  // countermarch (on robots with significant inertia; requires odometry feedback to be detected)
210  max_vx_inc = decel_vx*period;
211  }
212  else
213  {
214  max_vx_inc = ((vx_inc*target_vel.linear.x > 0.0)?accel_lim_vx:decel_vx)*period;
215  }
216 
217  vy_inc = target_vel.linear.y - last_cmd_vel.linear.y;
218  if ((robot_feedback == ODOMETRY) && (current_vel.linear.y*target_vel.linear.y < 0.0))
219  {
220  // countermarch (on robots with significant inertia; requires odometry feedback to be detected)
221  max_vy_inc = decel_vy*period;
222  }
223  else
224  {
225  max_vy_inc = ((vy_inc*target_vel.linear.y > 0.0)?accel_lim_vy:decel_vy)*period;
226  }
227 
228  w_inc = target_vel.angular.z - last_cmd_vel.angular.z;
229  if ((robot_feedback == ODOMETRY) && (current_vel.angular.z*target_vel.angular.z < 0.0))
230  {
231  // countermarch (on robots with significant inertia; requires odometry feedback to be detected)
232  max_w_inc = decel_w*period;
233  }
234  else
235  {
236  max_w_inc = ((w_inc*target_vel.angular.z > 0.0)?accel_lim_w:decel_w)*period;
237  }
238 
239 /*
240  // Calculate and normalise vectors A (desired velocity increment) and B (maximum velocity increment),
241  // where v acts as coordinate x and w as coordinate y; the sign of the angle from A to B determines
242  // which velocity (v or w) must be overconstrained to keep the direction provided as command
243  double MA = sqrt( vx_inc * vx_inc + w_inc * w_inc);
244  double MB = sqrt(max_vx_inc * max_vx_inc + max_w_inc * max_w_inc);
245 
246  double Av = std::abs(vx_inc) / MA;
247  double Aw = std::abs(w_inc) / MA;
248  double Bv = max_vx_inc / MB;
249  double Bw = max_w_inc / MB;
250  double theta = atan2(Bw, Bv) - atan2(Aw, Av);
251 
252  if (theta < 0)
253  {
254  // overconstrain linear velocity
255  max_vx_inc = (max_w_inc*std::abs(vx_inc))/std::abs(w_inc);
256  }
257  else
258  {
259  // overconstrain angular velocity
260  max_w_inc = (max_vx_inc*std::abs(w_inc))/std::abs(vx_inc);
261  }
262 */
263  if (std::abs(vx_inc) > max_vx_inc)
264  {
265  // we must limit linear velocity
266  cmd_vel->linear.x = last_cmd_vel.linear.x + sign(vx_inc)*max_vx_inc;
267  }
268 
269  if (std::abs(vy_inc) > max_vy_inc)
270  {
271  // we must limit linear velocity
272  cmd_vel->linear.y = last_cmd_vel.linear.y + sign(vy_inc)*max_vy_inc;
273  }
274 
275  if (std::abs(w_inc) > max_w_inc)
276  {
277  // we must limit angular velocity
278  cmd_vel->angular.z = last_cmd_vel.angular.z + sign(w_inc)*max_w_inc;
279  }
280 
281  smooth_vel_pub.publish(cmd_vel);
282  last_cmd_vel = *cmd_vel;
283  }
284  else if (input_active == true)
285  {
286  // We already reached target velocity; just keep resending last command while input is active
287  cmd_vel.reset(new geometry_msgs::Twist(last_cmd_vel));
288  smooth_vel_pub.publish(cmd_vel);
289  }
290 
291  spin_rate.sleep();
292  }
293 }
294 
301 {
302  // Dynamic Reconfigure
303  dynamic_reconfigure_callback = boost::bind(&VelocitySmoother::reconfigCB, this, _1, _2);
304 
305  dynamic_reconfigure_server = new dynamic_reconfigure::Server<cob_base_velocity_smoother::paramsConfig>(nh);
307 
308  // Optional parameters
309  int feedback;
310  nh.param("frequency", frequency, 20.0);
311  nh.param("decel_factor", decel_factor, 1.0);
312  nh.param("decel_factor_safe", decel_factor_safe, 1.0);
313  nh.param("robot_feedback", feedback, (int)NONE);
314 
315  if ((int(feedback) < NONE) || (int(feedback) > COMMANDS))
316  {
317  ROS_WARN("Invalid robot feedback type (%d). Valid options are 0 (NONE, default), 1 (ODOMETRY) and 2 (COMMANDS)",
318  feedback);
319  feedback = NONE;
320  }
321 
322  robot_feedback = static_cast<RobotFeedbackType>(feedback);
323 
324  // Mandatory parameters
325  if ((nh.getParam("speed_lim_vx", speed_lim_vx) == false) ||
326  (nh.getParam("speed_lim_vy", speed_lim_vy) == false) ||
327  (nh.getParam("speed_lim_w", speed_lim_w) == false))
328  {
329  ROS_ERROR("Missing velocity limit parameter(s)");
330  return false;
331  }
332 
333  if ((nh.getParam("accel_lim_vx", accel_lim_vx) == false) ||
334  (nh.getParam("accel_lim_vy", accel_lim_vy) == false) ||
335  (nh.getParam("accel_lim_w", accel_lim_w) == false))
336  {
337  ROS_ERROR("Missing acceleration limit parameter(s)");
338  return false;
339  }
340 
341  // Deceleration can be more aggressive, if necessary
345  // In safety cases (no topic command anymore), deceleration should be very aggressive
349 
350  // Publishers and subscribers
351  odometry_sub = nh.subscribe("odometry", 1, &VelocitySmoother::odometryCB, this);
352  current_vel_sub = nh.subscribe("robot_cmd_vel", 1, &VelocitySmoother::robotVelCB, this);
353  raw_in_vel_sub = nh.subscribe("raw_cmd_vel", 1, &VelocitySmoother::velocityCB, this);
354  smooth_vel_pub = nh.advertise <geometry_msgs::Twist> ("smooth_cmd_vel", 1);
355 
356  return true;
357 }
358 }
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void velocityCB(const geometry_msgs::Twist::ConstPtr &msg)
enum cob_base_velocity_smoother::VelocitySmoother::RobotFeedbackType robot_feedback
#define ROS_WARN(...)
dynamic_reconfigure::Server< cob_base_velocity_smoother::paramsConfig >::CallbackType dynamic_reconfigure_callback
#define ROS_INFO(...)
void reconfigCB(cob_base_velocity_smoother::paramsConfig &config, uint32_t unused_level)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
ROSCPP_DECL bool ok()
dynamic_reconfigure::Server< cob_base_velocity_smoother::paramsConfig > * dynamic_reconfigure_server
#define PERIOD_RECORD_SIZE
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define IS_ZERO_VEOCITY(a)
#define ROS_WARN_STREAM(args)
bool sleep()
double median(std::vector< double > values)
#define ZERO_VEL_COMMAND
bool getParam(const std::string &key, std::string &s) const
void robotVelCB(const geometry_msgs::Twist::ConstPtr &msg)
void odometryCB(const nav_msgs::Odometry::ConstPtr &msg)
static Time now()
#define ROS_ERROR(...)


cob_base_velocity_smoother
Author(s): Florian Mirus , Benjamin Maidel
autogenerated on Thu Apr 8 2021 02:39:30