cob_base_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 
19 
20 /****************************************************************
21  * the ros navigation doesn't run very smoothly because acceleration is too high
22  * --> cob has strong base motors and therefore reacts with shaking behavior
23  * (PR2 has much more mechanical damping)
24  * solution: the additional node cob_base_velocity_smoother smooths the velocities
25  * comming from ROS-navigation or teleoperation, by calculating the mean values of a certain number
26  * of past messages and limiting the acceleration under a given threshold.
27  * cob_base_velocity_smoother subsribes (input) and publishes (output) geometry_msgs::Twist.
28  ****************************************************************/
29 
30 // function for checking wether a new msg has been received, triggering publishers accordingly
32 {
33  pthread_mutex_lock(&m_mutex);
34  new_msg_received_ = received;
35  pthread_mutex_unlock(&m_mutex);
36 }
37 
39 {
40  pthread_mutex_lock(&m_mutex);
41  bool ret_val = new_msg_received_;
42  pthread_mutex_unlock(&m_mutex);
43  return ret_val;
44 }
45 
46 // constructor
48 {
49  m_mutex = PTHREAD_MUTEX_INITIALIZER;
50  new_msg_received_ = false;
51 
52  // create node handles
53  nh_ = ros::NodeHandle();
54  pnh_ = ros::NodeHandle("~");
55 
56  // publisher
57  pub_ = nh_.advertise<geometry_msgs::Twist>("output", 1);
58 
59  // subscriber
60  geometry_msgs_sub_ = nh_.subscribe<geometry_msgs::Twist>("input", 1, boost::bind(&cob_base_velocity_smoother::geometryCallback, this, _1));
61 
62  // get parameters from parameter server if possible or write default values to variables
63  if( !pnh_.hasParam("circular_buffer_capacity") )
64  {
65  ROS_WARN("No parameter circular_buffer_capacity on parameter server. Using default [12]");
66  }
67  pnh_.param("circular_buffer_capacity", buffer_capacity_, 12);
68 
69  if( !pnh_.hasParam("maximal_time_delay") )
70  {
71  ROS_WARN("No parameter maximal_time_delay on parameter server. Using default [4 in s]");
72  }
73  pnh_.param("maximal_time_delay", store_delay_, 4.0);
74 
75  if( !pnh_.hasParam("maximal_time_delay_to_stop") )
76  {
77  ROS_WARN("No parameter maximal_time_delay_to_stop on parameter server. Using default [0.1 in s]");
78  }
79  pnh_.param("maximal_time_delay_to_stop", stop_delay_after_no_sub_, 0.1);
80 
81  if( !pnh_.hasParam("thresh_max_acc") )
82  {
83  ROS_WARN("No parameter thresh_max_acc on parameter server. Using default [0.3 in m/s]");
84  }
85  pnh_.param("thresh_max_acc", acc_limit_, 0.3);
86 
87  if( !pnh_.hasParam("loop_rate") )
88  {
89  ROS_WARN("No parameter loop_rate on parameter server. Using default [30 in Hz]");
90  }
91  pnh_.param("loop_rate", loop_rate_, 30.0);
92 
93  double min_input_rate;
94  if( !pnh_.hasParam("min_input_rate") )
95  {
96  ROS_WARN("No parameter min_input_rate on parameter server. Using default [9 in Hz]");
97  }
98  pnh_.param("min_input_rate", min_input_rate, 9.0);
99 
100  if( min_input_rate > loop_rate_)
101  {
102  ROS_WARN("min_input_rate > loop_rate: Setting min_input_rate to loop_rate = %f", loop_rate_);
103  min_input_rate = loop_rate_;
104  }
105  max_delay_between_commands_ = 1/min_input_rate;
106 
107  // set a geometry message containing zero-values
108  zero_values_.linear.x = 0.0;
109  zero_values_.linear.y = 0.0;
110  zero_values_.linear.z = 0.0;
111 
112  zero_values_.angular.x = 0.0;
113  zero_values_.angular.y = 0.0;
114  zero_values_.angular.z = 0.0;
115 
116  // initialize circular buffers
117  cb_.set_capacity(buffer_capacity_);
118  cb_out_.set_capacity(buffer_capacity_);
119  cb_time_.set_capacity(buffer_capacity_);
120 
121  // set actual ros::Time
122  ros::Time now = ros::Time::now();
123 
124  // fill circular buffer with zero values
125  while(cb_.full() == false)
126  {
127  cb_.push_front(zero_values_);
128  cb_time_.push_front(now);
129  }
130 };
131 
132 // destructor
134 
135 // callback function to subsribe to the geometry messages cmd_vel and save them in a member variable
136 void cob_base_velocity_smoother::geometryCallback(const geometry_msgs::Twist::ConstPtr &cmd_vel)
137 {
138  sub_msg_ = *cmd_vel;
139  set_new_msg_received(true);
140 }
141 
142 // calculation function called periodically in main
144 {
145  // set current ros::Time
146  ros::Time now = ros::Time::now();
147  static ros::Time last = now;
148 
149  geometry_msgs::Twist result = geometry_msgs::Twist();
150 
151  // only publish command if we received a msg or the last message was actually zero
152  if (get_new_msg_received())
153  {
154  // generate Output messages
155  result = this->setOutput(now, sub_msg_);
156  pub_.publish(result);
157 
158  last = now;
159  set_new_msg_received(false);
160  }
161  // start writing in zeros if we did not receive a new msg within a certain amount of time.
162  // Do not publish! Otherwise, the output of other nodes will be overwritten!
163  else if ( fabs((last - now).toSec()) > max_delay_between_commands_)
164  {
165  result = this->setOutput(now, geometry_msgs::Twist());
166  }
167  // if last message was a zero msg, fill the buffer with zeros and publish again
168  else if (IsZeroMsg(sub_msg_))
169  {
170  result = this->setOutput(now, sub_msg_);
171  pub_.publish(result);
172  }
173 }
174 
175 // function for the actual computation
176 // calls the reviseCircBuff and the meanValue-functions and limits the acceleration under thresh
177 // returns the resulting geomtry message to be published to the base_controller
178 geometry_msgs::Twist cob_base_velocity_smoother::setOutput(ros::Time now, geometry_msgs::Twist cmd_vel)
179 {
180  geometry_msgs::Twist result = zero_values_;
181 
182  // update the circular buffers
183  this->reviseCircBuff(now, cmd_vel);
184 
185  // calculate the mean values for each direction
186  result.linear.x = meanValueX();
187  result.linear.y = meanValueY();
188  result.angular.z = meanValueZ();
189 
190  // limit acceleration
191  this->limitAcceleration(now, result);
192 
193  // insert the result-message into the circular-buffer storing the output
194  cb_out_.push_front(result);
195 
196  return result;
197 }
198 
199 // function that updates the circular buffer after receiving a new geometry message
200 void cob_base_velocity_smoother::reviseCircBuff(ros::Time now, geometry_msgs::Twist cmd_vel)
201 {
202  if(this->circBuffOutOfDate(now) == true)
203  {
204  // the circular buffer is out of date, so clear and refill with zero messages before adding the new command
205 
206  // clear buffers
207  cb_.clear();
208  cb_time_.clear();
209 
210  // fill circular buffer with zero_values_ and time buffer with actual time-stamp
211  while(cb_.full() == false)
212  {
213  cb_.push_front(zero_values_);
214  cb_time_.push_front(now);
215  }
216 
217  // add new command velocity message to circular buffer
218  cb_.push_front(cmd_vel);
219  // add new timestamp for subscribed command velocity message
220  cb_time_.push_front(now);
221  }
222  else
223  {
224  // only some elements of the circular buffer are out of date, so only delete those
225  double delay=(now.toSec() - cb_time_.back().toSec());
226 
227  while( delay >= store_delay_ )
228  {
229  // remove out-dated messages
230  cb_.pop_back();
231  cb_time_.pop_back();
232 
233  delay=(now.toSec() - cb_time_.back().toSec());
234  }
235  // if the circular buffer is empty now, refill with zero values
236  if(cb_.empty() == true)
237  {
238  while(cb_.full() == false)
239  {
240  cb_.push_front(zero_values_);
241  cb_time_.push_front(now);
242  }
243  }
244  if(this->IsZeroMsg(cmd_vel))
245  {
246  // here we subscribed a zero message, so we want to stop the robot
247  long unsigned int size = floor( cb_.size() / 3 );
248 
249  // to stop the robot faster, fill the circular buffer with more than one, in fact floor (cb_.size() / 3 ), zero messages
250  for(long unsigned int i=0; i< size; i++)
251  {
252  // add new command velocity message to circular buffer
253  cb_.push_front(cmd_vel);
254  // add new timestamp for subscribed command velocity message
255  cb_time_.push_front(now);
256  }
257  }
258  else
259  {
260  // add new command velocity message to circular buffer
261  cb_.push_front(cmd_vel);
262  // add new timestamp for subscribed command velocity message
263  cb_time_.push_front(now);
264  }
265  }
266 };
267 
268 // returns true if all messages in cb are out of date in consideration of store_delay
270 {
271  bool result=true;
272 
273  long unsigned int count=0;
274 
275  while( (count < cb_.size()) && (result == true) )
276  {
277  double delay=(now.toSec() - cb_time_[count].toSec());
278  if(delay < store_delay_)
279  {
280  result = false;
281  }
282  count++;
283  }
284 
285  return result;
286 };
287 
288 // returns true if the input msg cmd_vel equals zero_values_, false otherwise
289 bool cob_base_velocity_smoother::IsZeroMsg(geometry_msgs::Twist cmd_vel)
290 {
291  bool result = true;
292  if( (cmd_vel.linear.x) != 0 || (cmd_vel.linear.y != 0) || (cmd_vel.angular.z != 0) )
293  {
294  result = false;
295  }
296 
297  return result;
298 };
299 
301 {
302  if(var < 0)
303  {
304  return -1;
305  }
306  else
307  {
308  return 1;
309  }
310 };
311 
312 // functions to calculate the mean values for linear/x
314 {
315  double result = 0;
316  long unsigned int size = cb_.size();
317 
318  // calculate sum
319  for(long unsigned int i=0; i<size; i++)
320  {
321  result += cb_[i].linear.x;
322  }
323  result /= size;
324 
325  if(size > 1)
326  {
327  double help_result = 0;
328  double max = cb_[0].linear.x;
329  long unsigned int max_ind = 0;
330  for(long unsigned int i=0; i<size; i++)
331  {
332  if(abs(result-cb_[i].linear.x) > abs(result-max))
333  {
334  max = cb_[i].linear.x;
335  max_ind = i;
336  }
337  }
338 
339  // calculate sum
340  for(long unsigned int i=0; i<size; i++)
341  {
342  if(i != max_ind)
343  {
344  help_result += cb_[i].linear.x;
345  }
346  }
347  result = help_result / (size - 1);
348  }
349 
350  return result;
351 };
352 
353 // functions to calculate the mean values for linear/y
355 {
356  double result = 0;
357  long unsigned int size = cb_.size();
358 
359  // calculate sum
360  for(long unsigned int i=0; i<size; i++)
361  {
362  result += cb_[i].linear.y;
363  }
364  result /= size;
365 
366  if(size > 1)
367  {
368  double help_result = 0;
369  double max = cb_[0].linear.y;
370  long unsigned int max_ind = 0;
371  for(long unsigned int i=0; i<size; i++)
372  {
373  if(abs(result-cb_[i].linear.y) > abs(result-max))
374  {
375  max = cb_[i].linear.y;
376  max_ind = i;
377  }
378  }
379 
380  // calculate sum
381  for(long unsigned int i=0; i<size; i++)
382  {
383  if(i != max_ind)
384  {
385  help_result += cb_[i].linear.y;
386  }
387  }
388  result = help_result / (size - 1);
389  }
390 
391  return result;
392 };
393 
394 // functions to calculate the mean values for angular/z
396 {
397  double result = 0;
398  long unsigned int size = cb_.size();
399 
400  // calculate sum
401  for(long unsigned int i=0; i<size; i++)
402  {
403  result += cb_[i].angular.z;
404  }
405  result /= size;
406 
407  if(size > 1)
408  {
409  double help_result = 0;
410  double max = cb_[0].angular.z;
411  long unsigned int max_ind = 0;
412  for(long unsigned int i = 0; i < size; i++)
413  {
414  if(abs(result-cb_[i].angular.z) > abs(result-max))
415  {
416  max = cb_[i].angular.z;
417  max_ind = i;
418  }
419  }
420 
421  // calculate sum
422  for(long unsigned int i = 0; i < size; i++)
423  {
424  if(i != max_ind)
425  {
426  help_result += cb_[i].angular.z;
427  }
428  }
429  result = help_result / (size - 1);
430  }
431 
432  return result;
433 };
434 
435 // function to make the loop rate availabe outside the class
437 {
438  return loop_rate_;
439 }
440 
441 // function to compare two geometry messages
442 bool cob_base_velocity_smoother::IsEqual(geometry_msgs::Twist msg1, geometry_msgs::Twist msg2)
443 {
444  if( (msg1.linear.x == msg2.linear.x) && (msg1.linear.y == msg2.linear.y) && (msg1.angular.z == msg2.angular.z))
445  {
446  return true;
447  }
448  else
449  {
450  return false;
451  }
452 }
453 
454 //function to limit the acceleration under the given threshhold thresh
455 void cob_base_velocity_smoother::limitAcceleration(ros::Time now, geometry_msgs::Twist& result)
456 {
457  // limit the acceleration under thresh
458  // only if cob_base_velocity_smoother has published a message yet
459 
460  double deltaTime = 0;
461 
462  if(cb_time_.size() > 1)
463  {
464  deltaTime = now.toSec() - cb_time_[2].toSec();
465  }
466 
467  if( cb_out_.size() > 0)
468  {
469  if(deltaTime > 0)
470  {
471  // set delta velocity and acceleration values
472  double deltaX = result.linear.x - cb_out_.front().linear.x;
473 
474  double deltaY = result.linear.y - cb_out_.front().linear.y;
475 
476  double deltaZ = result.angular.z - cb_out_.front().angular.z;
477 
478  if( abs(deltaX) > acc_limit_)
479  {
480  result.linear.x = cb_out_.front().linear.x + this->signum(deltaX) * acc_limit_;
481  }
482  if( abs(deltaY) > acc_limit_ )
483  {
484  result.linear.y = cb_out_.front().linear.y + this->signum(deltaY) * acc_limit_;
485  }
486  if( abs(deltaZ) > acc_limit_ )
487  {
488  result.angular.z = cb_out_.front().angular.z + this->signum(deltaZ) * acc_limit_;
489  }
490  }
491  }
492 };
493 
494 
495 int main(int argc, char **argv)
496 {
497  // initialize ros and specifiy node name
498  ros::init(argc, argv, "cob_base_velocity_smoother");
499 
500  // create Node Class
501  cob_base_velocity_smoother my_velocity_smoother;
502  // get loop rate from class member
503  ros::Rate rate(my_velocity_smoother.getLoopRate());
504  // actual calculation step with given frequency
505  while(my_velocity_smoother.nh_.ok())
506  {
507  my_velocity_smoother.calculationStep();
508 
509  ros::spinOnce();
510  rate.sleep();
511  }
512 
513  return 0;
514 }
int main(int argc, char **argv)
void limitAcceleration(ros::Time now, geometry_msgs::Twist &cmd_vel)
void publish(const boost::shared_ptr< M > &message) const
geometry_msgs::Twist setOutput(ros::Time now, geometry_msgs::Twist cmd_vel)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
void reviseCircBuff(ros::Time now, geometry_msgs::Twist cmd_vel)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
#define ROS_WARN(...)
bool IsEqual(geometry_msgs::Twist msg1, geometry_msgs::Twist msg2)
bool IsZeroMsg(geometry_msgs::Twist cmd_vel)
boost::circular_buffer< geometry_msgs::Twist > cb_out_
bool param(const std::string &param_name, T &param_val, const T &default_val) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
boost::circular_buffer< geometry_msgs::Twist > cb_
void geometryCallback(const geometry_msgs::Twist::ConstPtr &cmd_vel)
boost::circular_buffer< ros::Time > cb_time_
static Time now()
bool ok() const
bool hasParam(const std::string &key) const
ROSCPP_DECL void spinOnce()


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