$search
00001 /**************************************************************** 00002 * 00003 * Copyright (c) 2012 00004 * 00005 * Fraunhofer Institute for Manufacturing Engineering 00006 * and Automation (IPA) 00007 * 00008 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00009 * 00010 * Project name: care-o-bot 00011 * ROS stack name: cob_driver 00012 * ROS package name: cob_base_velocity_smoother 00013 * 00014 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00015 * 00016 * Author: Florian Mirus, email:Florian.Mirus@ipa.fhg.de 00017 * 00018 * Date of creation: May 2012 00019 * 00020 * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++ 00021 * 00022 * Redistribution and use in source and binary forms, with or without 00023 * modification, are permitted provided that the following conditions are met: 00024 * 00025 * * Redistributions of source code must retain the above copyright 00026 * notice, this list of conditions and the following disclaimer. 00027 * * Redistributions in binary form must reproduce the above copyright 00028 * notice, this list of conditions and the following disclaimer in the 00029 * documentation and/or other materials provided with the distribution. 00030 * * Neither the name of the Fraunhofer Institute for Manufacturing 00031 * Engineering and Automation (IPA) nor the names of its 00032 * contributors may be used to endorse or promote products derived from 00033 * this software without specific prior written permission. 00034 * 00035 * This program is free software: you can redistribute it and/or modify 00036 * it under the terms of the GNU Lesser General Public License LGPL as 00037 * published by the Free Software Foundation, either version 3 of the 00038 * License, or (at your option) any later version. 00039 * 00040 * This program is distributed in the hope that it will be useful, 00041 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00042 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00043 * GNU Lesser General Public License LGPL for more details. 00044 * 00045 * You should have received a copy of the GNU Lesser General Public 00046 * License LGPL along with this program. 00047 * If not, see <http://www.gnu.org/licenses/>. 00048 * 00049 ****************************************************************/ 00050 #include <ros/ros.h> 00051 #include <XmlRpc.h> 00052 #include <pthread.h> 00053 #include <std_msgs/String.h> 00054 #include <geometry_msgs/Twist.h> 00055 #include <ros/console.h> 00056 #include <deque> 00057 #include <sstream> 00058 #include <iostream> 00059 #include <boost/circular_buffer.hpp> 00060 #include <boost/bind.hpp> 00061 00062 using namespace std; 00063 00064 /**************************************************************** 00065 * the ros navigation doesn't run very smoothly because acceleration is too high 00066 * --> cob has strong base motors and therefore reacts with shaking behavior 00067 * (PR2 has much more mechanical damping) 00068 * solution: the additional node cob_base_velocity_smoother smooths the velocities 00069 * comming from ROS-navigation or teleoperation, by calculating the mean values of a certain number 00070 * of past messages and limiting the acceleration under a given threshold. 00071 * cob_base_velocity_smoother subsribes (input) and publishes (output) geometry_msgs::Twist. 00072 ****************************************************************/ 00073 class cob_base_velocity_smoother 00074 { 00075 private: 00076 //capacity for circular buffers (to be loaded from parameter server, otherwise set to default value 12) 00077 int buffer_capacity; 00078 //maximal time-delay in seconds for stored messages in Circular Buffer (to be loaded from parameter server, otherwise set to default value 4) 00079 double store_delay; 00080 //threshhold for maximal allowed acceleration (to be loaded from parameter server, otherwise set to default value 0.02) 00081 double thresh; 00082 //geometry message filled with zero values 00083 geometry_msgs::Twist zero_values; 00084 00085 public: 00086 00087 //constructor 00088 cob_base_velocity_smoother(); 00089 00090 //create node handle 00091 ros::NodeHandle n; 00092 00093 //circular buffers for velocity, acceleration and time 00094 boost::circular_buffer<geometry_msgs::Twist> cb; 00095 boost::circular_buffer<geometry_msgs::Twist> cb_out; 00096 boost::circular_buffer<ros::Time> cb_time; 00097 00098 //ros publisher 00099 ros::Publisher pub; 00100 00101 //callback function to subsribe to the geometry messages cmd_vel and publish to base_controller/command 00102 void geometryCallback(const geometry_msgs::Twist& cmd_vel); 00103 //function that updates the circular buffer after receiving a new geometry message 00104 void reviseCircBuff(ros::Time now, geometry_msgs::Twist cmd_vel); 00105 //function to limit the acceleration under the given threshhold thresh 00106 void limitAcceleration(ros::Time now, geometry_msgs::Twist& cmd_vel); 00107 00108 //boolean function that returns true if all messages stored in the circular buffer are older than store_delay, 00109 //false otherwise 00110 bool CircBuffOutOfDate(ros::Time now); 00111 00112 //boolean function that returns true if the input msg cmd_vel equals zero_values, false otherwise 00113 bool IsZeroMsg(geometry_msgs::Twist cmd_vel); 00114 00115 //help-function that returns the signum of a double variable 00116 int signum(double var); 00117 00118 //functions to calculate the mean values for each direction 00119 double meanValueX(); 00120 double meanValueY(); 00121 double meanValueZ(); 00122 00123 //function for the actual computation 00124 //calls the reviseCircBuff and the meanValue-functions and limits the acceleration under thresh 00125 //returns the resulting geometry message to be published to the base_controller 00126 geometry_msgs::Twist setOutput(ros::Time now, geometry_msgs::Twist cmd_vel); 00127 00128 }; 00129 00130 //constructor 00131 cob_base_velocity_smoother::cob_base_velocity_smoother() 00132 { 00133 00134 //get parameters from parameter server if possible or take default values 00135 if(n.hasParam("circular_buffer_capacity")) 00136 { 00137 n.getParam("circular_buffer_capacity",buffer_capacity); 00138 } 00139 else 00140 { 00141 buffer_capacity = 12; 00142 ROS_WARN("Used default parameter for circular buffer capacity [12]"); 00143 } 00144 00145 if(n.hasParam("maximal_time_delay")) 00146 { 00147 n.getParam("maximal_time_delay",store_delay); 00148 } 00149 else 00150 { 00151 store_delay = 4; 00152 ROS_WARN("Used default parameter for maximal time delay in seconds for saved messages [4]"); 00153 } 00154 00155 if(n.hasParam("thresh_max_acc")) 00156 { 00157 n.getParam("thresh_max_acc",thresh); 00158 } 00159 00160 else 00161 { 00162 thresh = 0.3; 00163 ROS_WARN("Used default parameter for maximal allowed acceleration in m per s [0.3]"); 00164 } 00165 00166 //set a geometry message containing zero-values 00167 zero_values.linear.x=0; 00168 zero_values.linear.y=0; 00169 zero_values.linear.z=0; 00170 00171 zero_values.angular.x=0; 00172 zero_values.angular.y=0; 00173 zero_values.angular.z=0; 00174 00175 //initialize circular buffers 00176 cb.set_capacity(buffer_capacity); 00177 cb_out.set_capacity(buffer_capacity); 00178 cb_time.set_capacity(buffer_capacity); 00179 00180 //set actual ros::Time 00181 ros::Time now=ros::Time::now(); 00182 00183 //fill circular buffer with zero values 00184 while(cb.full() == false){ 00185 00186 cb.push_front(zero_values); 00187 cb_time.push_front(now); 00188 00189 } 00190 00191 pub = n.advertise<geometry_msgs::Twist>("output", 1); 00192 00193 }; 00194 00195 //returns true if all messages in cb are out of date in consideration of store_delay 00196 bool cob_base_velocity_smoother::CircBuffOutOfDate(ros::Time now) 00197 { 00198 bool result=true; 00199 00200 long unsigned int count=0; 00201 00202 while( (count < cb.size()) && (result == true) ){ 00203 00204 double delay=(now.toSec() - cb_time[count].toSec()); 00205 00206 if(delay < store_delay){ 00207 result = false; 00208 } 00209 count++; 00210 } 00211 00212 return result; 00213 00214 }; 00215 00216 //returns true if the input msg cmd_vel equals zero_values, false otherwise 00217 bool cob_base_velocity_smoother::IsZeroMsg(geometry_msgs::Twist cmd_vel) 00218 { 00219 bool result = true; 00220 if( (cmd_vel.linear.x) != 0 || (cmd_vel.linear.y != 0) || (cmd_vel.angular.z != 0) ){ 00221 result = false; 00222 } 00223 00224 return result; 00225 }; 00226 00227 int cob_base_velocity_smoother::signum(double var) 00228 { 00229 if(var < 0){ 00230 return -1; 00231 } 00232 else{ 00233 return 1; 00234 } 00235 }; 00236 00237 //functions to calculate the mean values for linear/x 00238 double cob_base_velocity_smoother::meanValueX() 00239 { 00240 double result = 0; 00241 long unsigned int size = cb.size(); 00242 00243 //calculate sum 00244 for(long unsigned int i=0; i<size; i++){ 00245 00246 result = result + cb[i].linear.x; 00247 00248 } 00249 result = result / size; 00250 00251 if(size > 1){ 00252 00253 double help_result = 0; 00254 double max = cb[0].linear.x; 00255 long unsigned int max_ind = 0; 00256 for(long unsigned int i=0; i<size; i++){ 00257 00258 if(abs(result-cb[i].linear.x) > abs(result-max)){ 00259 max = cb[i].linear.x; 00260 max_ind = i; 00261 } 00262 00263 } 00264 00265 //calculate sum 00266 for(long unsigned int i=0; i<size; i++){ 00267 00268 if(i != max_ind){ 00269 help_result = help_result + cb[i].linear.x; 00270 } 00271 } 00272 result = help_result / (size - 1); 00273 } 00274 00275 return result; 00276 00277 }; 00278 00279 //functions to calculate the mean values for linear/y 00280 double cob_base_velocity_smoother::meanValueY() 00281 { 00282 double result = 0; 00283 long unsigned int size = cb.size(); 00284 00285 //calculate sum 00286 for(long unsigned int i=0; i<size; i++){ 00287 00288 result = result + cb[i].linear.y; 00289 00290 } 00291 result = result / size; 00292 00293 if(size > 1){ 00294 00295 double help_result = 0; 00296 double max = cb[0].linear.y; 00297 long unsigned int max_ind = 0; 00298 for(long unsigned int i=0; i<size; i++){ 00299 00300 if(abs(result-cb[i].linear.y) > abs(result-max)){ 00301 max = cb[i].linear.y; 00302 max_ind = i; 00303 } 00304 00305 } 00306 00307 //calculate sum 00308 for(long unsigned int i=0; i<size; i++){ 00309 00310 if(i != max_ind){ 00311 help_result = help_result + cb[i].linear.y; 00312 } 00313 } 00314 result = help_result / (size - 1); 00315 } 00316 00317 return result; 00318 00319 }; 00320 00321 //functions to calculate the mean values for angular/z 00322 double cob_base_velocity_smoother::meanValueZ() 00323 { 00324 double result = 0; 00325 long unsigned int size = cb.size(); 00326 00327 //calculate sum 00328 for(long unsigned int i=0; i<size; i++){ 00329 00330 result = result + cb[i].angular.z; 00331 00332 } 00333 result = result / size; 00334 00335 if(size > 1){ 00336 00337 double help_result = 0; 00338 double max = cb[0].angular.z; 00339 long unsigned int max_ind = 0; 00340 for(long unsigned int i=0; i<size; i++){ 00341 00342 if(abs(result-cb[i].angular.z) > abs(result-max)){ 00343 max = cb[i].angular.z; 00344 max_ind = i; 00345 } 00346 00347 } 00348 00349 //calculate sum 00350 for(long unsigned int i=0; i<size; i++){ 00351 00352 if(i != max_ind){ 00353 help_result = help_result + cb[i].angular.z; 00354 } 00355 } 00356 result = help_result / (size - 1); 00357 00358 } 00359 00360 return result; 00361 00362 }; 00363 00364 //function that updates the circular buffer after receiving a new geometry message 00365 void cob_base_velocity_smoother::reviseCircBuff(ros::Time now, geometry_msgs::Twist cmd_vel) 00366 { 00367 if(this->CircBuffOutOfDate(now) == true){ 00368 00369 //clear buffers 00370 cb.clear(); 00371 cb_time.clear(); 00372 00373 //fill circular buffer with zero_values and time buffer with actual time-stamp 00374 while(cb.full() == false){ 00375 00376 cb.push_front(zero_values); 00377 cb_time.push_front(now); 00378 00379 } 00380 00381 //add new command velocity message to circular buffer 00382 cb.push_front(cmd_vel); 00383 //add new timestamp for subscribed command velocity message 00384 cb_time.push_front(now); 00385 00386 } 00387 else{ 00388 double delay=(now.toSec() - cb_time.back().toSec()); 00389 00390 while( delay >= store_delay ){ 00391 //remove out-dated messages 00392 cb.pop_back(); 00393 cb_time.pop_back(); 00394 00395 delay=(now.toSec() - cb_time.back().toSec()); 00396 } 00397 //if the circular buffer is empty now, refill with zero values 00398 if(cb.empty() == true){ 00399 while(cb.full() == false){ 00400 00401 cb.push_front(zero_values); 00402 cb_time.push_front(now); 00403 00404 } 00405 } 00406 if(this->IsZeroMsg(cmd_vel)){ 00407 00408 long unsigned int size = floor( cb.size() / 3 ); 00409 00410 //to stop the robot faster, fill the circular buffer with more than one, in fact floor (cb.size() / 3 ), zero messages 00411 for(long unsigned int i=0; i< size; i++){ 00412 00413 //add new command velocity message to circular buffer 00414 cb.push_front(cmd_vel); 00415 //add new timestamp for subscribed command velocity message 00416 cb_time.push_front(now); 00417 } 00418 00419 } 00420 else{ 00421 00422 //add new command velocity message to circular buffer 00423 cb.push_front(cmd_vel); 00424 //add new timestamp for subscribed command velocity message 00425 cb_time.push_front(now); 00426 00427 } 00428 00429 } 00430 }; 00431 00432 //function to limit the acceleration under the given threshhold thresh 00433 void cob_base_velocity_smoother::limitAcceleration(ros::Time now, geometry_msgs::Twist& result){ 00434 00435 //limit the acceleration under thresh 00436 // only if cob_base_velocity_smoother has published a message yet 00437 00438 double deltaTime = 0; 00439 00440 if(cb_time.size() > 1){ 00441 deltaTime = now.toSec() - cb_time[2].toSec(); 00442 } 00443 00444 if( cb_out.size() > 0){ 00445 00446 if(deltaTime > 0){ 00447 //set delta velocity and acceleration values 00448 double deltaX = result.linear.x - cb_out.front().linear.x; 00449 double accX = deltaX / deltaTime; 00450 00451 double deltaY = result.linear.y - cb_out.front().linear.y; 00452 double accY = deltaY / deltaTime; 00453 00454 double deltaZ = result.angular.z - cb_out.front().angular.z; 00455 double accZ = deltaZ / deltaTime; 00456 00457 if( abs(accX) > thresh){ 00458 00459 result.linear.x = cb_out.front().linear.x + ( this->signum(accX) * thresh * deltaTime ); 00460 00461 } 00462 if( abs(accY) > thresh){ 00463 00464 result.linear.y = cb_out.front().linear.y + ( this->signum(accY) * thresh * deltaTime ); 00465 00466 } 00467 if( abs(accZ) > thresh){ 00468 00469 result.angular.z = cb_out.front().angular.z + ( this->signum(accZ) * thresh * deltaTime ); 00470 00471 } 00472 } 00473 } 00474 00475 }; 00476 00477 00478 //function for the actual computation 00479 //calls the reviseCircBuff and the meanValue-functions and limits the acceleration under thresh 00480 //returns the resulting geometry message to be published to the base_controller 00481 geometry_msgs::Twist cob_base_velocity_smoother::setOutput(ros::Time now, geometry_msgs::Twist cmd_vel) 00482 { 00483 geometry_msgs::Twist result = zero_values; 00484 00485 //update the circular buffers 00486 this->reviseCircBuff(now, cmd_vel); 00487 00488 //calculate the mean values for each direction 00489 result.linear.x = meanValueX(); 00490 result.linear.y = meanValueY(); 00491 result.angular.z = meanValueZ(); 00492 00493 //limit acceleration 00494 this->limitAcceleration(now, result); 00495 00496 //insert the result-message into the circular-buffer storing the output 00497 cb_out.push_front(result); 00498 00499 return result; 00500 00501 } 00502 00503 //callback function to subsribe to the geometry messages cmd_vel and publish to base_controller/command 00504 void cob_base_velocity_smoother::geometryCallback(const geometry_msgs::Twist& cmd_vel) 00505 { 00506 00507 //set actual ros::Time 00508 ros::Time now = ros::Time::now(); 00509 00510 //generate Output messages 00511 geometry_msgs::Twist result = this->setOutput(now, cmd_vel); 00512 00513 //publish result 00514 pub.publish(result); 00515 00516 }; 00517 00518 int main(int argc, char **argv) 00519 { 00520 00521 ros::init(argc, argv, "cob_base_velocity_smoother"); 00522 00523 cob_base_velocity_smoother my_cvi = cob_base_velocity_smoother(); 00524 00525 ros::Subscriber sub = my_cvi.n.subscribe("input", 1, &cob_base_velocity_smoother::geometryCallback, &my_cvi); 00526 00527 ros::spin(); 00528 00529 return 0; 00530 } 00531