eband_trajectory_controller.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2010, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Christian Connette
36  *********************************************************************/
37 
39 #include <tf2/utils.h>
40 
41 namespace eband_local_planner{
42 
43  using std::min;
44  using std::max;
45 
46 
47  EBandTrajectoryCtrl::EBandTrajectoryCtrl() : costmap_ros_(NULL), initialized_(false), band_set_(false), visualization_(false) {}
48 
49 
51  : costmap_ros_(NULL), initialized_(false), band_set_(false), visualization_(false)
52  {
53  // initialize planner
54  initialize(name, costmap_ros);
55 
56  // Initialize pid object (note we'll be further clamping its output)
57  pid_.initPid(1, 0, 0, 10, -10);
58  }
59 
60 
62 
63 
64  void EBandTrajectoryCtrl::initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros)
65  {
66 
67  // check if trajectory controller is already initialized
68  if(!initialized_)
69  {
70  // create Node Handle with name of plugin (as used in move_base for loading)
71  ros::NodeHandle node_private("~/" + name);
72 
73  in_final_goal_turn_ = false;
74 
75  // copy adress of costmap and Transform Listener (handed over from move_base)
76  costmap_ros_ = costmap_ros;
77 
78  // init velocity for interpolation
79  last_vel_.linear.x = 0.0;
80  last_vel_.linear.y = 0.0;
81  last_vel_.linear.z = 0.0;
82  last_vel_.angular.x = 0.0;
83  last_vel_.angular.y = 0.0;
84  last_vel_.angular.z = 0.0;
85 
86  // set the general refernce frame to that in which the band is given
87  geometry_msgs::Pose2D tmp_pose2D;
88  tmp_pose2D.x = 0.0;
89  tmp_pose2D.y = 0.0;
90  tmp_pose2D.theta = 0.0;
91  Pose2DToPose(ref_frame_band_, tmp_pose2D);
92 
93  // set initialized flag
94  initialized_ = true;
95  }
96  else
97  {
98  ROS_WARN("This planner has already been initialized, doing nothing.");
99  }
100  }
101 
102 
104  eband_local_planner::EBandPlannerConfig& config)
105  {
106  max_vel_lin_ = config.max_vel_lin;
107  max_vel_th_ = config.max_vel_th;
108  min_vel_lin_ = config.min_vel_lin;
109  min_vel_th_ = config.min_vel_th;
110  min_in_place_vel_th_ = config.min_in_place_vel_th;
111  in_place_trans_vel_ = config.in_place_trans_vel;
112  tolerance_trans_ = config.xy_goal_tolerance;
113  tolerance_rot_ = config.yaw_goal_tolerance;
114  k_p_ = config.k_prop;
115  k_nu_ = config.k_damp;
116  ctrl_freq_ = config.Ctrl_Rate;
117  acc_max_ = config.max_acceleration;
118  virt_mass_ = config.virtual_mass;
119  acc_max_trans_ = config.max_translational_acceleration;
120  acc_max_rot_ = config.max_rotational_acceleration;
121  rotation_correction_threshold_ = config.rotation_correction_threshold;
122 
123  // diffferential drive parameters
124  differential_drive_hack_ = config.differential_drive;
125  bubble_velocity_multiplier_ = config.bubble_velocity_multiplier;
126  rotation_threshold_multiplier_ = config.rotation_threshold_multiplier;
127  disallow_hysteresis_ = config.disallow_hysteresis;
128  }
129 
130 
132  {
133  target_visual_ = target_visual;
134 
135  visualization_ = true;
136  }
137 
138  bool EBandTrajectoryCtrl::setBand(const std::vector<Bubble>& elastic_band)
139  {
140  elastic_band_ = elastic_band;
141  band_set_ = true;
142  return true;
143  }
144 
145 
146  bool EBandTrajectoryCtrl::setOdometry(const nav_msgs::Odometry& odometry)
147  {
148  odom_vel_.linear.x = odometry.twist.twist.linear.x;
149  odom_vel_.linear.y = odometry.twist.twist.linear.y;
150  odom_vel_.linear.z = 0.0;
151  odom_vel_.angular.x = 0.0;
152  odom_vel_.angular.y = 0.0;
153  odom_vel_.angular.z = odometry.twist.twist.angular.z;
154 
155  return true;
156  }
157 
158  // Return the angular difference between the direction we're pointing
159  // and the direction we want to move in
160  double angularDiff (const geometry_msgs::Twist& heading,
161  const geometry_msgs::Pose& pose)
162  {
163  const double pi = 3.14159265;
164  const double t1 = atan2(heading.linear.y, heading.linear.x);
165  const double t2 = tf2::getYaw(pose.orientation);
166  const double d = t1-t2;
167 
168  if (fabs(d)<pi)
169  return d;
170  else if (d<0)
171  return d+2*pi;
172  else
173  return d-2*pi;
174  }
175 
176  bool EBandTrajectoryCtrl::getTwistDifferentialDrive(geometry_msgs::Twist& twist_cmd, bool& goal_reached) {
177  goal_reached = false;
178 
179  geometry_msgs::Twist robot_cmd, bubble_diff;
180  robot_cmd.linear.x = 0.0;
181  robot_cmd.angular.z = 0.0;
182 
183  bool command_provided = false;
184 
185  // check if plugin initialized
186  if(!initialized_) {
187  ROS_ERROR("Requesting feedforward command from not initialized planner. Please call initialize() before using this planner");
188  return false;
189  }
190 
191  // check there is a plan at all (minimum 1 frame in this case, as robot + goal = plan)
192  if( (!band_set_) || (elastic_band_.size() < 2) ) {
193  ROS_WARN("Requesting feedforward command from empty band.");
194  return false;
195  }
196 
197  // Get the differences between the first 2 bubbles in the robot's frame
198  bubble_diff = getFrame1ToFrame2InRefFrameNew(
199  elastic_band_.at(0).center.pose,
200  elastic_band_.at(1).center.pose,
201  elastic_band_.at(0).center.pose);
202 
203  float distance_from_goal = -1.0f;
204 
205  // Check 1
206  // We need to check if we are within the threshold of the final destination
207  if (!command_provided) {
208  int curr_target_bubble = 1;
209 
210  while(curr_target_bubble < ((int) elastic_band_.size()) - 1) {
211  curr_target_bubble++;
212  bubble_diff =
214  elastic_band_.at(0).center.pose,
215  elastic_band_.at(curr_target_bubble).center.pose,
216  elastic_band_.at(0).center.pose);
217  }
218 
219  // if you go past tolerance, then try to get closer again
220  if (!disallow_hysteresis_) {
221  if(fabs(bubble_diff.linear.x) > tolerance_trans_ ||
222  fabs(bubble_diff.linear.y) > tolerance_trans_) {
223  in_final_goal_turn_ = false;
224  }
225  }
226 
227  // Get the differences between the first 2 bubbles in the robot's frame
228  int goal_bubble = (((int) elastic_band_.size()) - 1);
229  bubble_diff = getFrame1ToFrame2InRefFrameNew(
230  elastic_band_.at(0).center.pose,
231  elastic_band_.at(goal_bubble).center.pose,
232  elastic_band_.at(0).center.pose);
233 
234  distance_from_goal = sqrtf(bubble_diff.linear.x * bubble_diff.linear.x +
235  bubble_diff.linear.y * bubble_diff.linear.y);
236 
237  // Get closer to the goal than the tolerance requires before starting the
238  // final turn. The final turn may cause you to move slightly out of
239  // position
240  if((fabs(bubble_diff.linear.x) <= 0.6 * tolerance_trans_ &&
241  fabs(bubble_diff.linear.y) <= 0.6 * tolerance_trans_) ||
243  // Calculate orientation difference to goal orientation (not captured in bubble_diff)
244  double robot_yaw = tf2::getYaw(elastic_band_.at(0).center.pose.orientation);
245  double goal_yaw = tf2::getYaw(elastic_band_.at((int)elastic_band_.size() - 1).center.pose.orientation);
246  float orientation_diff = angles::normalize_angle(goal_yaw - robot_yaw);
247  if (fabs(orientation_diff) > tolerance_rot_) {
248  in_final_goal_turn_ = true;
249  ROS_DEBUG("Performing in place rotation for goal (diff): %f", orientation_diff);
250  double rotation_sign = -2 * (orientation_diff < 0) + 1;
251  robot_cmd.angular.z =
252  rotation_sign * min_in_place_vel_th_ + k_p_ * orientation_diff;
253  if (fabs(robot_cmd.angular.z) > max_vel_th_) { // limit max rotation
254  robot_cmd.angular.z = rotation_sign * max_vel_th_;
255  }
256  } else {
257  in_final_goal_turn_ = false; // Goal reached
258  ROS_INFO ("TrajectoryController: Goal reached with distance %.2f, %.2f (od = %.2f)"
259  "; sending zero velocity",
260  bubble_diff.linear.x, bubble_diff.linear.y, orientation_diff);
261  // goal position reached
262  robot_cmd.linear.x = 0.0;
263  robot_cmd.angular.z = 0.0;
264  goal_reached = true;
265  }
266  command_provided = true;
267  }
268  }
269 
270  // Get the differences between the first 2 bubbles in the robot's frame
271  bubble_diff = getFrame1ToFrame2InRefFrameNew(
272  elastic_band_.at(0).center.pose,
273  elastic_band_.at(1).center.pose,
274  elastic_band_.at(0).center.pose);
275 
276  // Check 1 - check if the robot's current pose is too misaligned with the next bubble
277  if (!command_provided) {
278  ROS_DEBUG("Goal has not been reached, performing checks to move towards goal");
279 
280  // calculate an estimate of the in-place rotation threshold
281  double distance_to_next_bubble = sqrt(
282  bubble_diff.linear.x * bubble_diff.linear.x +
283  bubble_diff.linear.y * bubble_diff.linear.y);
284  double radius_of_next_bubble = 0.7 * elastic_band_.at(1).expansion;
285  double in_place_rotation_threshold =
287  fabs(atan2(radius_of_next_bubble,distance_to_next_bubble));
288  ROS_DEBUG("In-place rotation threshold: %f(%f,%f)",
289  in_place_rotation_threshold, radius_of_next_bubble, distance_to_next_bubble);
290 
291  // check if we are above this threshold, if so then perform in-place rotation
292  if (fabs(bubble_diff.angular.z) > in_place_rotation_threshold) {
293  robot_cmd.angular.z = k_p_ * bubble_diff.angular.z;
294  double rotation_sign = (bubble_diff.angular.z < 0) ? -1.0 : +1.0;
295  if (fabs(robot_cmd.angular.z) < min_in_place_vel_th_) {
296  robot_cmd.angular.z = rotation_sign * min_in_place_vel_th_;
297  }
298  if (fabs(robot_cmd.angular.z) > max_vel_th_) { // limit max rotation
299  robot_cmd.angular.z = rotation_sign * max_vel_th_;
300  }
301  ROS_DEBUG("Performing in place rotation for start (diff): %f with rot vel: %f", bubble_diff.angular.z, robot_cmd.angular.z);
302  command_provided = true;
303  }
304  }
305 
306  // Check 3 - If we reach here, it means we need to use our PID controller to
307  // move towards the next bubble
308  if (!command_provided) {
309 
310  // Select a linear velocity (based on the current bubble radius)
311  double forward_sign = -2 * (bubble_diff.linear.x < 0) + 1;
312  double bubble_radius = 0.7 * elastic_band_.at(0).expansion;
313  double velocity_multiplier = bubble_velocity_multiplier_ * bubble_radius;
314 
315  double max_vel_lin = max_vel_lin_;
316  if (distance_from_goal < 0.75f) {
317  max_vel_lin = (max_vel_lin < 0.3) ? 0.15 : max_vel_lin / 2;
318  }
319 
320  double linear_velocity = velocity_multiplier * max_vel_lin;
321  linear_velocity *= cos(bubble_diff.angular.z); //decrease while turning
322  if (fabs(linear_velocity) > max_vel_lin_) {
323  linear_velocity = forward_sign * max_vel_lin_;
324  } else if (fabs(linear_velocity) < min_vel_lin_) {
325  linear_velocity = forward_sign * min_vel_lin_;
326  }
327 
328  // Select an angular velocity (based on PID controller)
329  double error = bubble_diff.angular.z;
330  double rotation_sign = -2 * (bubble_diff.angular.z < 0) + 1;
331  double angular_velocity = k_p_ * error;
332  if (fabs(angular_velocity) > max_vel_th_) {
333  angular_velocity = rotation_sign * max_vel_th_;
334  } else if (fabs(angular_velocity) < min_vel_th_) {
335  angular_velocity = rotation_sign * min_vel_th_;
336  }
337 
338  ROS_DEBUG("Selected velocity: lin: %f, ang: %f",
339  linear_velocity, angular_velocity);
340 
341  robot_cmd.linear.x = linear_velocity;
342  robot_cmd.angular.z = angular_velocity;
343  command_provided = true;
344  }
345 
346  twist_cmd = robot_cmd;
347  ROS_DEBUG("Final command: %f, %f", twist_cmd.linear.x, twist_cmd.angular.z);
348  return true;
349  }
350 
351 
352  bool EBandTrajectoryCtrl::getTwist(geometry_msgs::Twist& twist_cmd, bool& goal_reached)
353  {
354  goal_reached = false;
356  return getTwistDifferentialDrive(twist_cmd, goal_reached);
357  }
358 
359  // init twist cmd to be handed back to caller
360  geometry_msgs::Twist robot_cmd, bubble_diff, control_deviation;
361  robot_cmd.linear.x = 0.0;
362  robot_cmd.linear.y = 0.0;
363  robot_cmd.linear.z = 0.0;
364  robot_cmd.angular.x = 0.0;
365  robot_cmd.angular.y = 0.0;
366  robot_cmd.angular.z = 0.0;
367 
368  // make sure command vector is clean
369  twist_cmd = robot_cmd;
370  control_deviation = robot_cmd;
371 
372  // check if plugin initialized
373  if(!initialized_)
374  {
375  ROS_ERROR("Requesting feedforward command from not initialized planner. Please call initialize() before using this planner");
376  return false;
377  }
378 
379  // check there is a plan at all (minimum 1 frame in this case, as robot + goal = plan)
380  if( (!band_set_) || (elastic_band_.size() < 2) )
381  {
382  ROS_WARN("Requesting feedforward command from empty band.");
383  return false;
384  }
385 
386  // calc intersection of bubble-radius with sequence of vector connecting the bubbles
387 
388  // get distance to target from bubble-expansion
389  double scaled_radius = 0.7 * elastic_band_.at(0).expansion;
390 
391  // get difference and distance between bubbles in odometry frame
392  double bubble_distance, ang_pseudo_dist;
393  bubble_diff = getFrame1ToFrame2InRefFrame(elastic_band_.at(0).center.pose,
394  elastic_band_.at(1).center.pose,
396  ang_pseudo_dist = bubble_diff.angular.z * getCircumscribedRadius(*costmap_ros_);
397  bubble_distance = sqrt( (bubble_diff.linear.x * bubble_diff.linear.x) + (bubble_diff.linear.y * bubble_diff.linear.y) +
398  (ang_pseudo_dist * ang_pseudo_dist) );
399 
400  if(visualization_)
401  {
402  target_visual_->publishBubble("ctrl_target", 1, target_visual_->blue, elastic_band_.at(0));
403  target_visual_->publishBubble("ctrl_target", 2, target_visual_->blue, elastic_band_.at(1));
404  }
405 
406  // by default our control deviation is the difference between the bubble centers
407  double abs_ctrl_dev;
408  control_deviation = bubble_diff;
409 
410 
411  ang_pseudo_dist = control_deviation.angular.z * getCircumscribedRadius(*costmap_ros_);
412  abs_ctrl_dev = sqrt( (control_deviation.linear.x * control_deviation.linear.x) +
413  (control_deviation.linear.y * control_deviation.linear.y) +
414  (ang_pseudo_dist * ang_pseudo_dist) );
415 
416  // yet depending on the expansion of our bubble we might want to adapt this point
417  if(scaled_radius < bubble_distance)
418  {
419  // triviale case - simply scale bubble_diff
420  double scale_difference = scaled_radius / bubble_distance;
421  bubble_diff.linear.x *= scale_difference;
422  bubble_diff.linear.y *= scale_difference;
423  bubble_diff.angular.z *= scale_difference;
424  // set controls
425  control_deviation = bubble_diff;
426  }
427 
428  // if scaled_radius = bubble_distance -- we have nothing to do at all
429 
430  if(scaled_radius > bubble_distance)
431  {
432  // o.k. now we have to do a little bit more -> check next but one bubble
433  if(elastic_band_.size() > 2)
434  {
435  // get difference between next and next but one bubble
436  double next_bubble_distance;
437  geometry_msgs::Twist next_bubble_diff;
438  next_bubble_diff = getFrame1ToFrame2InRefFrame(elastic_band_.at(1).center.pose,
439  elastic_band_.at(2).center.pose,
441  ang_pseudo_dist = next_bubble_diff.angular.z * getCircumscribedRadius(*costmap_ros_);
442  next_bubble_distance = sqrt( (next_bubble_diff.linear.x * next_bubble_diff.linear.x) +
443  (next_bubble_diff.linear.y * next_bubble_diff.linear.y) +
444  (ang_pseudo_dist * ang_pseudo_dist) );
445 
446  if(scaled_radius > (bubble_distance + next_bubble_distance) )
447  {
448  // we should normally not end up here - but just to be sure
449  control_deviation.linear.x = bubble_diff.linear.x + next_bubble_diff.linear.x;
450  control_deviation.linear.y = bubble_diff.linear.y + next_bubble_diff.linear.y;
451  control_deviation.angular.z = bubble_diff.angular.z + next_bubble_diff.angular.z;
452  // done
453  if(visualization_)
454  target_visual_->publishBubble("ctrl_target", 3, target_visual_->red, elastic_band_.at(2));
455  }
456  else
457  {
458  if(visualization_)
459  target_visual_->publishBubble("ctrl_target", 3, target_visual_->red, elastic_band_.at(2));
460 
461  // we want to calculate intersection point of bubble ...
462  // ... and vector connecting the following bubbles
463  double b_distance, cosine_at_bub;
464  double vec_prod, norm_vec1, norm_vec2;
465  double ang_pseudo_dist1, ang_pseudo_dist2;
466 
467  // get distance between next bubble center and intersection point
468  ang_pseudo_dist1 = bubble_diff.angular.z * getCircumscribedRadius(*costmap_ros_);
469  ang_pseudo_dist2 = next_bubble_diff.angular.z * getCircumscribedRadius(*costmap_ros_);
470  // careful! - we need this sign because of the direction of the vectors and the definition of the vector-product
471  vec_prod = - ( (bubble_diff.linear.x * next_bubble_diff.linear.x) +
472  (bubble_diff.linear.y * next_bubble_diff.linear.y) +
473  (ang_pseudo_dist1 * ang_pseudo_dist2) );
474 
475  norm_vec1 = sqrt( (bubble_diff.linear.x * bubble_diff.linear.x) +
476  (bubble_diff.linear.y * bubble_diff.linear.y) +
477  (ang_pseudo_dist1 * ang_pseudo_dist1) );
478 
479  norm_vec2 = sqrt( (next_bubble_diff.linear.x * next_bubble_diff.linear.x) +
480  (next_bubble_diff.linear.y * next_bubble_diff.linear.y) +
481  (ang_pseudo_dist2 * ang_pseudo_dist2) );
482 
483  // reform the cosine-rule
484  cosine_at_bub = vec_prod / norm_vec1 / norm_vec2;
485  b_distance = bubble_distance * cosine_at_bub + sqrt( scaled_radius*scaled_radius -
486  bubble_distance*bubble_distance * (1.0 - cosine_at_bub*cosine_at_bub) );
487 
488  // get difference vector from next_bubble to intersection point
489  double scale_next_difference = b_distance / next_bubble_distance;
490  next_bubble_diff.linear.x *= scale_next_difference;
491  next_bubble_diff.linear.y *= scale_next_difference;
492  next_bubble_diff.angular.z *= scale_next_difference;
493 
494  // and finally get the control deviation
495  control_deviation.linear.x = bubble_diff.linear.x + next_bubble_diff.linear.x;
496  control_deviation.linear.y = bubble_diff.linear.y + next_bubble_diff.linear.y;
497  control_deviation.angular.z = bubble_diff.angular.z + next_bubble_diff.angular.z;
498  // done
499  }
500  }
501  }
502 
503  // plot control deviation
504  ang_pseudo_dist = control_deviation.angular.z * getCircumscribedRadius(*costmap_ros_);
505  abs_ctrl_dev = sqrt( (control_deviation.linear.x * control_deviation.linear.x) +
506  (control_deviation.linear.y * control_deviation.linear.y) +
507  (ang_pseudo_dist * ang_pseudo_dist) );
508 
509 
510  if(visualization_)
511  {
512  // compose bubble from ctrl-target
513  geometry_msgs::Pose2D tmp_bubble_2d, curr_bubble_2d;
514  geometry_msgs::Pose tmp_pose;
515  // init bubble for visualization
516  Bubble new_bubble = elastic_band_.at(0);
517  PoseToPose2D(elastic_band_.at(0).center.pose, curr_bubble_2d);
518  tmp_bubble_2d.x = curr_bubble_2d.x + control_deviation.linear.x;
519  tmp_bubble_2d.y = curr_bubble_2d.y + control_deviation.linear.y;
520  tmp_bubble_2d.theta = curr_bubble_2d.theta + control_deviation.angular.z;
521  Pose2DToPose(tmp_pose, tmp_bubble_2d);
522  new_bubble.center.pose = tmp_pose;
523  new_bubble.expansion = 0.1; // just draw a small bubble
524  target_visual_->publishBubble("ctrl_target", 0, target_visual_->red, new_bubble);
525  }
526 
527 
528  const geometry_msgs::Point& goal = (--elastic_band_.end())->center.pose.position;
529  const double dx = elastic_band_.at(0).center.pose.position.x - goal.x;
530  const double dy = elastic_band_.at(0).center.pose.position.y - goal.y;
531  const double dist_to_goal = sqrt(dx*dx + dy*dy);
532 
533  // Assuming we're far enough from the final goal, make sure to rotate so
534  // we're facing the right way
535  if (dist_to_goal > rotation_correction_threshold_)
536  {
537 
538  const double angular_diff = angularDiff(control_deviation, elastic_band_.at(0).center.pose);
539  const double vel = pid_.computeCommand(angular_diff, ros::Duration(1/ctrl_freq_));
540  const double mult = fabs(vel) > max_vel_th_ ? max_vel_th_/fabs(vel) : 1.0;
541  control_deviation.angular.z = vel*mult;
542  const double abs_vel = fabs(control_deviation.angular.z);
543 
544  ROS_DEBUG_THROTTLE_NAMED (1.0, "angle_correction",
545  "Angular diff is %.2f and desired angular "
546  "vel is %.2f. Initial translation velocity "
547  "is %.2f, %.2f", angular_diff,
548  control_deviation.angular.z,
549  control_deviation.linear.x,
550  control_deviation.linear.y);
551  const double trans_mult = max(0.01, 1.0 - abs_vel/max_vel_th_); // There are some weird tf errors if I let it be 0
552  control_deviation.linear.x *= trans_mult;
553  control_deviation.linear.y *= trans_mult;
554  ROS_DEBUG_THROTTLE_NAMED (1.0, "angle_correction",
555  "Translation multiplier is %.2f and scaled "
556  "translational velocity is %.2f, %.2f",
557  trans_mult, control_deviation.linear.x,
558  control_deviation.linear.y);
559  }
560  else
561  ROS_DEBUG_THROTTLE_NAMED (1.0, "angle_correction",
562  "Not applying angle correction because "
563  "distance to goal is %.2f", dist_to_goal);
564 
565 
566 
567 
568  // now the actual control procedure start (using attractive Potentials)
569  geometry_msgs::Twist desired_velocity, currbub_maxvel_dir;
570  double desvel_abs, desvel_abs_trans, currbub_maxvel_abs;
571  double scale_des_vel;
572  desired_velocity = robot_cmd;
573  currbub_maxvel_dir = robot_cmd;
574 
575  // calculate "equilibrium velocity" (Khatib86 - Realtime Obstacle Avoidance)
576  desired_velocity.linear.x = k_p_/k_nu_ * control_deviation.linear.x;
577  desired_velocity.linear.y = k_p_/k_nu_ * control_deviation.linear.y;
578  desired_velocity.angular.z = k_p_/k_nu_ * control_deviation.angular.z;
579 
580  //robot_cmd = desired_velocity;
581 
582  // get max vel for current bubble
583  int curr_bub_num = 0;
584  currbub_maxvel_abs = getBubbleTargetVel(curr_bub_num, elastic_band_, currbub_maxvel_dir);
585 
586  // if neccessarry scale desired vel to stay lower than currbub_maxvel_abs
587  ang_pseudo_dist = desired_velocity.angular.z * getCircumscribedRadius(*costmap_ros_);
588  desvel_abs = sqrt( (desired_velocity.linear.x * desired_velocity.linear.x) +
589  (desired_velocity.linear.y * desired_velocity.linear.y) +
590  (ang_pseudo_dist * ang_pseudo_dist) );
591  if(desvel_abs > currbub_maxvel_abs)
592  {
593  scale_des_vel = currbub_maxvel_abs / desvel_abs;
594  desired_velocity.linear.x *= scale_des_vel;
595  desired_velocity.linear.y *= scale_des_vel;
596  desired_velocity.angular.z *= scale_des_vel;
597  }
598 
599  // make sure to stay within velocity bounds for the robot
600  desvel_abs_trans = sqrt( (desired_velocity.linear.x * desired_velocity.linear.x) + (desired_velocity.linear.y * desired_velocity.linear.y) );
601  // for translation
602  if(desvel_abs_trans > max_vel_lin_)
603  {
604  scale_des_vel = max_vel_lin_ / desvel_abs_trans;
605  desired_velocity.linear.x *= scale_des_vel;
606  desired_velocity.linear.y *= scale_des_vel;
607  // to make sure we are staying inside the bubble also scale rotation
608  desired_velocity.angular.z *= scale_des_vel;
609  }
610 
611  // for rotation
612  if(fabs(desired_velocity.angular.z) > max_vel_th_)
613  {
614  scale_des_vel = max_vel_th_ / fabs(desired_velocity.angular.z);
615  desired_velocity.angular.z *= scale_des_vel;
616  // to make sure we are staying inside the bubble also scale translation
617  desired_velocity.linear.x *= scale_des_vel;
618  desired_velocity.linear.y *= scale_des_vel;
619  }
620 
621  // calculate resulting force (accel. resp.) (Khatib86 - Realtime Obstacle Avoidance)
622  geometry_msgs::Twist acc_desired;
623  acc_desired = robot_cmd;
624  acc_desired.linear.x = (1.0/virt_mass_) * k_nu_ * (desired_velocity.linear.x - last_vel_.linear.x);
625  acc_desired.linear.y = (1.0/virt_mass_) * k_nu_ * (desired_velocity.linear.y - last_vel_.linear.y);
626  acc_desired.angular.z = (1.0/virt_mass_) * k_nu_ * (desired_velocity.angular.z - last_vel_.angular.z);
627 
628  // constrain acceleration
629  double scale_acc;
630  double abs_acc_trans = sqrt( (acc_desired.linear.x*acc_desired.linear.x) + (acc_desired.linear.y*acc_desired.linear.y) );
631  if(abs_acc_trans > acc_max_trans_)
632  {
633  scale_acc = acc_max_trans_ / abs_acc_trans;
634  acc_desired.linear.x *= scale_acc;
635  acc_desired.linear.y *= scale_acc;
636  // again - keep relations - stay in bubble
637  acc_desired.angular.z *= scale_acc;
638  }
639 
640  if(fabs(acc_desired.angular.z) > acc_max_rot_)
641  {
642  scale_acc = fabs(acc_desired.angular.z) / acc_max_rot_;
643  acc_desired.angular.z *= scale_acc;
644  // again - keep relations - stay in bubble
645  acc_desired.linear.x *= scale_acc;
646  acc_desired.linear.y *= scale_acc;
647  }
648 
649  // and get velocity-cmds by integrating them over one time-step
650  last_vel_.linear.x = last_vel_.linear.x + acc_desired.linear.x / ctrl_freq_;
651  last_vel_.linear.y = last_vel_.linear.y + acc_desired.linear.y / ctrl_freq_;
652  last_vel_.angular.z = last_vel_.angular.z + acc_desired.angular.z / ctrl_freq_;
653 
654 
655  // we are almost done now take into accoun stick-slip and similar nasty things
656 
657  // last checks - limit current twist cmd (upper and lower bounds)
659 
660  // finally set robot_cmd (to non-zero value)
661  robot_cmd = last_vel_;
662 
663  // now convert into robot-body frame
664  robot_cmd = transformTwistFromFrame1ToFrame2(robot_cmd, ref_frame_band_, elastic_band_.at(0).center.pose);
665 
666  // check whether we reached the end of the band
667  int curr_target_bubble = 1;
668  while(fabs(bubble_diff.linear.x) <= tolerance_trans_ &&
669  fabs(bubble_diff.linear.y) <= tolerance_trans_ &&
670  fabs(bubble_diff.angular.z) <= tolerance_rot_)
671  {
672  if(curr_target_bubble < ((int) elastic_band_.size()) - 1)
673  {
674  curr_target_bubble++;
675  // transform next target bubble into robot-body frame
676  // and get difference to robot bubble
677  bubble_diff = getFrame1ToFrame2InRefFrame(elastic_band_.at(0).center.pose, elastic_band_.at(curr_target_bubble).center.pose,
679  }
680  else
681  {
682  ROS_DEBUG_THROTTLE_NAMED (1.0, "controller_state",
683  "Goal reached with distance %.2f, %.2f, %.2f"
684  "; sending zero velocity",
685  bubble_diff.linear.x, bubble_diff.linear.y,
686  bubble_diff.angular.z);
687  // goal position reached
688  robot_cmd.linear.x = 0.0;
689  robot_cmd.linear.y = 0.0;
690  robot_cmd.angular.z = 0.0;
691  // reset velocity
692  last_vel_.linear.x = 0.0;
693  last_vel_.linear.y = 0.0;
694  last_vel_.angular.z = 0.0;
695  goal_reached = true;
696  break;
697  }
698  }
699 
700  twist_cmd = robot_cmd;
701 
702  return true;
703  }
704 
705 
706  double EBandTrajectoryCtrl::getBubbleTargetVel(const int& target_bub_num, const std::vector<Bubble>& band, geometry_msgs::Twist& VelDir)
707  {
708  // init reference for direction vector
709  VelDir.linear.x = 0.0;
710  VelDir.linear.y = 0.0;
711  VelDir.linear.z = 0.0;
712  VelDir.angular.x = 0.0;
713  VelDir.angular.y = 0.0;
714  VelDir.angular.z = 0.0;
715 
716  // if we are looking at the last bubble - target vel is always zero
717  if(target_bub_num >= ((int) band.size() - 1))
718  return 0.0;
719 
720 
721  // otherwise check for max_vel calculated from current bubble size
722  double v_max_curr_bub, v_max_next_bub;
723  double bubble_distance, angle_to_pseudo_vel, delta_vel_max;
724  geometry_msgs::Twist bubble_diff;
725 
726  // distance for braking s = 0.5*v*v/a
727  v_max_curr_bub = sqrt(2 * elastic_band_.at(target_bub_num).expansion * acc_max_);
728 
729  // get distance to next bubble center
730  ROS_ASSERT( (target_bub_num >= 0) && ((target_bub_num +1) < (int) band.size()) );
731  bubble_diff = getFrame1ToFrame2InRefFrame(band.at(target_bub_num).center.pose, band.at(target_bub_num + 1).center.pose,
733  angle_to_pseudo_vel = bubble_diff.angular.z * getCircumscribedRadius(*costmap_ros_);
734 
735  bubble_distance = sqrt( (bubble_diff.linear.x * bubble_diff.linear.x) + (bubble_diff.linear.y * bubble_diff.linear.y) +
736  (angle_to_pseudo_vel * angle_to_pseudo_vel) );
737 
738  // calculate direction vector - norm of diference
739  VelDir.linear.x =bubble_diff.linear.x/bubble_distance;
740  VelDir.linear.y =bubble_diff.linear.y/bubble_distance;
741  VelDir.angular.z =bubble_diff.angular.z/bubble_distance;
742 
743  // if next bubble outside this one we will always be able to break fast enough
744  if(bubble_distance > band.at(target_bub_num).expansion )
745  return v_max_curr_bub;
746 
747 
748  // next bubble center inside this bubble - take into account restrictions on next bubble
749  int next_bub_num = target_bub_num + 1;
750  geometry_msgs::Twist dummy_twist;
751  v_max_next_bub = getBubbleTargetVel(next_bub_num, band, dummy_twist); // recursive call
752 
753  // if velocity at next bubble bigger (or equal) than our velocity - we are on the safe side
754  if(v_max_next_bub >= v_max_curr_bub)
755  return v_max_curr_bub;
756 
757 
758  // otherwise max. allowed vel is next vel + plus possible reduction on the way between the bubble-centers
759  delta_vel_max = sqrt(2 * bubble_distance * acc_max_);
760  v_max_curr_bub = v_max_next_bub + delta_vel_max;
761 
762  return v_max_curr_bub;
763  }
764 
765 
766  geometry_msgs::Twist EBandTrajectoryCtrl::getFrame1ToFrame2InRefFrame(const geometry_msgs::Pose& frame1, const geometry_msgs::Pose& frame2, const geometry_msgs::Pose& ref_frame)
767  {
768 
769  geometry_msgs::Pose2D frame1_pose2D, frame2_pose2D, ref_frame_pose2D;
770  geometry_msgs::Pose2D frame1_pose2D_rf, frame2_pose2D_rf;
771  geometry_msgs::Twist frame_diff;
772 
773  // transform all frames to Pose2d
774  PoseToPose2D(frame1, frame1_pose2D);
775  PoseToPose2D(frame2, frame2_pose2D);
776  PoseToPose2D(ref_frame, ref_frame_pose2D);
777 
778  // transform frame1 into ref frame
779  frame1_pose2D_rf.x = (frame1_pose2D.x - ref_frame_pose2D.x) * cos(ref_frame_pose2D.theta) +
780  (frame1_pose2D.y - ref_frame_pose2D.y) * sin(ref_frame_pose2D.theta);
781  frame1_pose2D_rf.y = -(frame1_pose2D.x - ref_frame_pose2D.x) * sin(ref_frame_pose2D.theta) +
782  (frame1_pose2D.y - ref_frame_pose2D.y) * cos(ref_frame_pose2D.theta);
783  frame1_pose2D_rf.theta = frame1_pose2D.theta - ref_frame_pose2D.theta;
784  frame1_pose2D_rf.theta = angles::normalize_angle(frame1_pose2D_rf.theta);
785  // transform frame2 into ref frame
786  frame2_pose2D_rf.x = (frame2_pose2D.x - ref_frame_pose2D.x) * cos(ref_frame_pose2D.theta) +
787  (frame2_pose2D.y - ref_frame_pose2D.y) * sin(ref_frame_pose2D.theta);
788  frame2_pose2D_rf.y = -(frame2_pose2D.x - ref_frame_pose2D.x) * sin(ref_frame_pose2D.theta) +
789  (frame2_pose2D.y - ref_frame_pose2D.y) * cos(ref_frame_pose2D.theta);
790  frame2_pose2D_rf.theta = frame2_pose2D.theta - ref_frame_pose2D.theta;
791  frame2_pose2D_rf.theta = angles::normalize_angle(frame2_pose2D_rf.theta);
792 
793  // get differences
794  frame_diff.linear.x = frame2_pose2D_rf.x - frame1_pose2D_rf.x;
795  frame_diff.linear.y = frame2_pose2D_rf.y - frame1_pose2D_rf.y;
796  frame_diff.linear.z = 0.0;
797  frame_diff.angular.x = 0.0;
798  frame_diff.angular.y = 0.0;
799  frame_diff.angular.z = frame2_pose2D_rf.theta - frame1_pose2D_rf.theta;
800  // normalize angle
801  frame_diff.angular.z = angles::normalize_angle(frame_diff.angular.z);
802 
803  return frame_diff;
804  }
805 
806  geometry_msgs::Twist EBandTrajectoryCtrl::getFrame1ToFrame2InRefFrameNew(const geometry_msgs::Pose& frame1, const geometry_msgs::Pose& frame2, const geometry_msgs::Pose& ref_frame)
807  {
808 
809  double x1 = frame1.position.x - ref_frame.position.x;
810  double y1 = frame1.position.y - ref_frame.position.y;
811  double x2 = frame2.position.x - ref_frame.position.x;
812  double y2 = frame2.position.y - ref_frame.position.y;
813  double yaw_ref = tf2::getYaw(ref_frame.orientation);
814 
815  double x_diff = x2 - x1;
816  double y_diff = y2 - y1;
817  double theta_diff = atan2(y_diff, x_diff);
818 
819  // Now project this vector on to the reference frame
820  double rotation = angles::normalize_angle(yaw_ref);
821  double x_final = x_diff * cos(rotation) + y_diff * sin(rotation);
822  double y_final = - x_diff * sin(rotation) + y_diff * cos(rotation);
823 
824  geometry_msgs::Twist twist_msg;
825  twist_msg.linear.x = x_final;
826  twist_msg.linear.y = y_final;
827  twist_msg.angular.z = angles::normalize_angle(theta_diff - yaw_ref);
828 
829  return twist_msg;
830  }
831 
832 
833  geometry_msgs::Twist EBandTrajectoryCtrl::transformTwistFromFrame1ToFrame2(const geometry_msgs::Twist& curr_twist,
834  const geometry_msgs::Pose& frame1, const geometry_msgs::Pose& frame2)
835  {
836  geometry_msgs::Pose2D frame1_pose2D, frame2_pose2D;
837  geometry_msgs::Twist tmp_transformed;
838  double delta_ang;
839 
840  tmp_transformed = curr_twist;
841 
842  // transform all frames to Pose2d
843  PoseToPose2D(frame1, frame1_pose2D);
844  PoseToPose2D(frame2, frame2_pose2D);
845 
846  // get orientation diff of frames
847  delta_ang = frame2_pose2D.theta - frame1_pose2D.theta;
848  delta_ang = angles::normalize_angle(delta_ang);
849 
850  // tranform twist
851  tmp_transformed.linear.x = curr_twist.linear.x * cos(delta_ang) + curr_twist.linear.y * sin(delta_ang);
852  tmp_transformed.linear.y = -curr_twist.linear.x * sin(delta_ang) + curr_twist.linear.y * cos(delta_ang);
853 
854  return tmp_transformed;
855  }
856 
857 
858  geometry_msgs::Twist EBandTrajectoryCtrl::limitTwist(const geometry_msgs::Twist& twist)
859  {
860  geometry_msgs::Twist res = twist;
861 
862  //make sure to bound things by our velocity limits
863  double lin_overshoot = sqrt(res.linear.x * res.linear.x + res.linear.y * res.linear.y) / max_vel_lin_;
864  double lin_undershoot = min_vel_lin_ / sqrt(res.linear.x * res.linear.x + res.linear.y * res.linear.y);
865  if (lin_overshoot > 1.0)
866  {
867  res.linear.x /= lin_overshoot;
868  res.linear.y /= lin_overshoot;
869  // keep relations
870  res.angular.z /= lin_overshoot;
871  }
872 
873  //we only want to enforce a minimum velocity if we're not rotating in place
874  if(lin_undershoot > 1.0)
875  {
876  res.linear.x *= lin_undershoot;
877  res.linear.y *= lin_undershoot;
878  // we cannot keep relations here for stability reasons
879  }
880 
881  if (fabs(res.angular.z) > max_vel_th_)
882  {
883  double scale = max_vel_th_/fabs(res.angular.z);
884  //res.angular.z = max_vel_th_ * sign(res.angular.z);
885  res.angular.z *= scale;
886  // keep relations
887  res.linear.x *= scale;
888  res.linear.y *= scale;
889  }
890 
891  if (fabs(res.angular.z) < min_vel_th_) res.angular.z = min_vel_th_ * sign(res.angular.z);
892  // we cannot keep relations here for stability reasons
893 
894  //we want to check for whether or not we're desired to rotate in place
895  if(sqrt(twist.linear.x * twist.linear.x + twist.linear.y * twist.linear.y) < in_place_trans_vel_)
896  {
897  if (fabs(res.angular.z) < min_in_place_vel_th_)
898  res.angular.z = min_in_place_vel_th_ * sign(res.angular.z);
899 
900  res.linear.x = 0.0;
901  res.linear.y = 0.0;
902  }
903 
904  ROS_DEBUG("Angular command %f", res.angular.z);
905  return res;
906  }
907 
908 
909 }
d
geometry_msgs::Twist getFrame1ToFrame2InRefFrameNew(const geometry_msgs::Pose &frame1, const geometry_msgs::Pose &frame2, const geometry_msgs::Pose &ref_frame)
geometry_msgs::Twist transformTwistFromFrame1ToFrame2(const geometry_msgs::Twist &curr_twist, const geometry_msgs::Pose &frame1, const geometry_msgs::Pose &frame2)
bool getTwist(geometry_msgs::Twist &twist_cmd, bool &goal_reached)
calculates a twist feedforward command from the current band
f
geometry_msgs::Twist getFrame1ToFrame2InRefFrame(const geometry_msgs::Pose &frame1, const geometry_msgs::Pose &frame2, const geometry_msgs::Pose &ref_frame)
Transforms Pose of frame 1 and 2 into reference frame and gets difference of frame 1 and 2...
bool setBand(const std::vector< Bubble > &elastic_band)
This sets the elastic_band to the trajectory controller.
double sign(double n)
defines sign of a double
void reconfigure(EBandPlannerConfig &config)
Reconfigures the parameters of the planner.
void Pose2DToPose(geometry_msgs::Pose &pose, const geometry_msgs::Pose2D pose2D)
Converts a frame of type Pose to type Pose2D (mainly -> conversion of orientation from euler angles t...
bool setOdometry(const nav_msgs::Odometry &odometry)
This sets the robot velocity as provided by odometry.
#define ROS_WARN(...)
double angularDiff(const geometry_msgs::Twist &heading, const geometry_msgs::Pose &pose)
void initPid(double p, double i, double d, double i_max, double i_min, bool antiwindup=false)
bool getTwistDifferentialDrive(geometry_msgs::Twist &twist_cmd, bool &goal_reached)
double getCircumscribedRadius(costmap_2d::Costmap2DROS &costmap)
Gets the footprint of the robot and computes the circumscribed radius for the eband approach...
double computeCommand(double error, ros::Duration dt)
#define ROS_INFO(...)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
def normalize_angle(angle)
double getYaw(const A &a)
void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)
Initializes the elastic band class by accesing costmap and loading parameters.
double getBubbleTargetVel(const int &target_bub_num, const std::vector< Bubble > &band, geometry_msgs::Twist &VelDir)
gets the max velocity allowed within this bubble depending on size of the bubble and pose and size of...
void setVisualization(boost::shared_ptr< EBandVisualization > target_visual)
passes a reference to the eband visualization object which can be used to visualize the band optimiza...
#define ROS_DEBUG_THROTTLE_NAMED(period, name,...)
boost::shared_ptr< EBandVisualization > target_visual_
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
geometry_msgs::Twist limitTwist(const geometry_msgs::Twist &twist)
limits the twist to the allowed range
geometry_msgs::PoseStamped center
costmap_2d::Costmap2DROS * costmap_ros_
pointer to costmap
INLINE Rall1d< T, V, S > cos(const Rall1d< T, V, S > &arg)
#define ROS_ASSERT(cond)
double max(double a, double b)
#define ROS_ERROR(...)
INLINE Rall1d< T, V, S > sin(const Rall1d< T, V, S > &arg)
void PoseToPose2D(const geometry_msgs::Pose pose, geometry_msgs::Pose2D &pose2D)
Converts a frame of type Pose to type Pose2D (mainly -> conversion of orientation from quaternions to...
#define ROS_DEBUG(...)


eband_local_planner
Author(s): Christian Connette, Bhaskara Marthi, Piyush Khandelwal
autogenerated on Mon Feb 28 2022 22:16:50