eband_local_planner.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 
40 
41 namespace eband_local_planner{
42 
43 
44  EBandPlanner::EBandPlanner() : costmap_ros_(NULL), initialized_(false) {}
45 
46 
47  EBandPlanner::EBandPlanner(std::string name, costmap_2d::Costmap2DROS* costmap_ros)
48  : costmap_ros_(NULL), initialized_(false)
49  {
50  // initialize planner
51  initialize(name, costmap_ros);
52  }
53 
54 
56  {
57  delete world_model_;
58  }
59 
60 
61  void EBandPlanner::initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros)
62  {
63  // check if the plugin is already initialized
64  if(!initialized_)
65  {
66  // copy adress of costmap (handed over from move_base via eband wrapper)
67  costmap_ros_ = costmap_ros;
68 
69  // get a pointer to the underlying costmap
71 
72  // create world model from costmap
74 
75  // get footprint of the robot
77 
78  // create Node Handle with name of plugin (as used in move_base for loading)
79  ros::NodeHandle pn("~/" + name);
80 
81  // clean up band
82  elastic_band_.clear();
83 
84  // set initialized flag
85  initialized_ = true;
86 
87  // set flag whether visualization availlable to false by default
88  visualization_ = false;
89  }
90  else
91  {
92  ROS_WARN("This planner has already been initialized, doing nothing.");
93  }
94  }
95 
97  eband_local_planner::EBandPlannerConfig& config)
98  {
99  // connectivity checking
100  min_bubble_overlap_ = config.eband_min_relative_overlap;
101 
102  // bubble geometric bounds
103  tiny_bubble_distance_ = config.eband_tiny_bubble_distance;
104  tiny_bubble_expansion_ = config.eband_tiny_bubble_expansion;
105 
106  // optimization - force calculation
107  internal_force_gain_ = config.eband_internal_force_gain;
108  external_force_gain_ = config.eband_external_force_gain;
109  num_optim_iterations_ = config.num_iterations_eband_optimization;
110 
111  // recursive approximation of bubble equilibrium position based
112  max_recursion_depth_approx_equi_ = config.eband_equilibrium_approx_max_recursion_depth;
113  equilibrium_relative_overshoot_ = config.eband_equilibrium_relative_overshoot;
114  significant_force_ = config.eband_significant_force_lower_bound;
115 
116  // use this parameter if a different weight is supplied to the costmap in dyn reconfigure
117  costmap_weight_ = config.costmap_weight;
118  }
119 
121  {
122  eband_visual_ = eband_visual;
123 
124  visualization_ = true;
125  }
126 
127 
128  bool EBandPlanner::setPlan(const std::vector<geometry_msgs::PoseStamped>& global_plan)
129  {
130  // check if plugin initialized
131  if(!initialized_)
132  {
133  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
134  return false;
135  }
136 
137 
138  // check if plan valid (minimum 2 frames)
139  if(global_plan.size() < 2)
140  {
141  ROS_ERROR("Attempt to pass empty path to optimization. Valid path needs to have at least 2 Frames. This one has %d.", ((int) global_plan.size()) );
142  return false;
143  }
144  // copy plan to local member variable
145  global_plan_ = global_plan;
146 
147 
148  // check whether plan and costmap are in the same frame
149  if(global_plan.front().header.frame_id != costmap_ros_->getGlobalFrameID())
150  {
151  ROS_ERROR("Elastic Band expects plan for optimization in the %s frame, the plan was sent in the %s frame.",
152  costmap_ros_->getGlobalFrameID().c_str(), global_plan.front().header.frame_id.c_str());
153  return false;
154  }
155 
156 
157  // convert frames in path into bubbles in band -> sets center of bubbles and calculates expansion
158  ROS_DEBUG("Converting Plan to Band");
160  {
161  ROS_WARN("Conversion from plan to elastic band failed. Plan probably not collision free. Plan not set for optimization");
162  // TODO try to do local repairs of band
163  return false;
164  }
165 
166 
167  // close gaps and remove redundant bubbles
168  ROS_DEBUG("Refining Band");
170  {
171  ROS_WARN("Band is broken. Could not close gaps in converted path. Path not set. Global replanning needed");
172  return false;
173  }
174 
175 
176  ROS_DEBUG("Refinement done - Band set.");
177  return true;
178  }
179 
180 
181  bool EBandPlanner::getPlan(std::vector<geometry_msgs::PoseStamped>& global_plan)
182  {
183  // check if plugin initialized
184  if(!initialized_)
185  {
186  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
187  return false;
188  }
189 
190  // check if there is a band
191  if(elastic_band_.empty())
192  {
193  ROS_WARN("Band is empty. There was no path successfully set so far.");
194  return false;
195  }
196 
197  // convert band to plan
198  if(!convertBandToPlan(global_plan, elastic_band_))
199  {
200  ROS_WARN("Conversion from Elastic Band to path failed.");
201  return false;
202  }
203 
204  return true;
205  }
206 
207 
208  bool EBandPlanner::getBand(std::vector<Bubble>& elastic_band)
209  {
210  // check if plugin initialized
211  if(!initialized_)
212  {
213  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
214  return false;
215  }
216 
217  elastic_band = elastic_band_;
218 
219  // check if there is a band
220  if(elastic_band_.empty())
221  {
222  ROS_WARN("Band is empty.");
223  return false;
224  }
225 
226  return true;
227  }
228 
229 
230  bool EBandPlanner::addFrames(const std::vector<geometry_msgs::PoseStamped>& plan_to_add, const AddAtPosition& add_frames_at)
231  {
232  // check if plugin initialized
233  if(!initialized_)
234  {
235  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
236  return false;
237  }
238 
239  // check that there is a plan at all (minimum 1 frame in this case, as robot + goal = plan)
240  if(elastic_band_.size() < 1)
241  {
242  ROS_WARN("Attempt to connect path to empty band. path not connected. Use SetPath instead");
243  return false;
244  }
245 
246  //check that plan which shall be added is not empty
247  if(plan_to_add.empty())
248  {
249  ROS_WARN("Attempt to connect empty path to band. Nothing to do here.");
250  return false;
251  }
252 
253  // check whether plan and costmap are in the same frame
254  if(plan_to_add.at(0).header.frame_id != costmap_ros_->getGlobalFrameID())
255  {
256  ROS_ERROR("Elastic Band expects robot pose for optimization in the %s frame, the pose was sent in the %s frame.",
257  costmap_ros_->getGlobalFrameID().c_str(), plan_to_add.at(0).header.frame_id.c_str());
258  return false;
259  }
260 
261 
262  // convert plan to band
263  std::vector<Bubble> band_to_add;
264  if(!convertPlanToBand(plan_to_add, band_to_add))
265  {
266  ROS_DEBUG("Conversion from plan to elastic band failed. Plan not appended");
267  // TODO try to do local repairs of band
268  return false;
269  }
270 
271 
272  // connect frames to existing band
273  ROS_DEBUG("Checking for connections between current band and new bubbles");
274  bool connected = false;
275  int bubble_connect = -1;
276  if(add_frames_at == add_front)
277  {
278  // add frames at the front of the current band
279  // - for instance to connect band and current robot position
280  for(int i = ((int) elastic_band_.size() - 1); i >= 0; i--)
281  {
282  // cycle over bubbles from End - connect to bubble furthest away but overlapping
283  if(checkOverlap(band_to_add.back(), elastic_band_.at(i)))
284  {
285  bubble_connect = i;
286  connected = true;
287  break;
288  }
289  }
290  }
291  else
292  {
293  // add frames at the end of the current band
294  // - for instance to connect new frames entering the moving window
295  for(int i = 0; i < ((int) elastic_band_.size() - 1); i++)
296  {
297  // cycle over bubbles from Start - connect to bubble furthest away but overlapping
298  if(checkOverlap(band_to_add.front(), elastic_band_.at(i)))
299  {
300  bubble_connect = i;
301  connected = true;
302  break;
303  }
304  }
305  }
306 
307  // intanstiate local copy of band
308  std::vector<Bubble> tmp_band;
309  std::vector<Bubble>::iterator tmp_iter1, tmp_iter2;
310  // copy new frames to tmp_band
311  tmp_band.assign(band_to_add.begin(), band_to_add.end());
312 
313  if(connected)
314  {
315  ROS_DEBUG("Connections found - composing new band by connecting new frames to bubble %d", bubble_connect);
316  if(add_frames_at == add_front)
317  {
318  // compose new vector by appending elastic_band to new frames
319  tmp_iter1 = elastic_band_.begin() + bubble_connect;
320  ROS_ASSERT( (tmp_iter1 >= elastic_band_.begin()) && (tmp_iter1 < elastic_band_.end()) );
321  tmp_band.insert(tmp_band.end(), tmp_iter1, elastic_band_.end());
322  }
323  else
324  {
325  // compose new vector by pre-appending elastic_band to new frames
326  tmp_iter1 = elastic_band_.begin() + bubble_connect + 1; // +1 - as insert only appends [start, end)
327  ROS_ASSERT( (tmp_iter1 > elastic_band_.begin()) && (tmp_iter1 <= elastic_band_.end()) );
328  tmp_band.insert(tmp_band.begin(), elastic_band_.begin(), tmp_iter1);
329  }
330 
331  // done
332  elastic_band_ = tmp_band;
333  return true;
334  }
335 
336  // otherwise, we need to do some more work - add complete band to tmp_band
337  ROS_DEBUG("No direct connection found - Composing tmp band and trying to fill gap");
338  if(add_frames_at == add_front)
339  {
340  // compose new vector by appending elastic_band to new frames
341  tmp_band.insert(tmp_band.end(), elastic_band_.begin(), elastic_band_.end());
342  // and get iterators to connecting bubbles
343  tmp_iter1 = tmp_band.begin() + ((int) band_to_add.size()) - 1;
344  tmp_iter2 = tmp_iter1 + 1;
345  }
346  else
347  {
348  // compose new vector by pre-appending elastic_band to new frames
349  tmp_band.insert(tmp_band.begin(), elastic_band_.begin(), elastic_band_.end());
350  // and get iterators to connecting bubbles
351  tmp_iter1 = tmp_band.begin() + ((int) elastic_band_.size()) - 1;
352  tmp_iter2 = tmp_iter1 + 1;
353  }
354 
355  // just in case
356  ROS_ASSERT( tmp_iter1 >= tmp_band.begin() );
357  ROS_ASSERT( tmp_iter2 < tmp_band.end() );
358  ROS_ASSERT( tmp_iter1 < tmp_iter2 );
359  if(!fillGap(tmp_band, tmp_iter1, tmp_iter2))
360  {
361  // we could not connect band and robot at its current position
362  ROS_DEBUG("Could not connect robot pose to band - Failed to fill gap.");
363  return false;
364  }
365 
366  // otherwise - done
367  elastic_band_ = tmp_band;
368 
369  return true;
370  }
371 
372 
374  {
375  // check if plugin initialized
376  if(!initialized_)
377  {
378  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
379  return false;
380  }
381 
382  // check if there is a band
383  if(elastic_band_.empty())
384  {
385  ROS_ERROR("Band is empty. Probably Band has not been set yet");
386  return false;
387  }
388 
389  // call optimization with member elastic_band_
390  ROS_DEBUG("Starting optimization of band");
392  {
393  ROS_DEBUG("Aborting Optimization. Changes discarded.");
394  return false;
395  }
396 
397  ROS_DEBUG("Elastic Band - Optimization successfull!");
398  return true;
399  }
400 
401 
402  bool EBandPlanner::optimizeBand(std::vector<Bubble>& band)
403  {
404  // check if plugin initialized
405  if(!initialized_)
406  {
407  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
408  return false;
409  }
410 
411  // check whether band and costmap are in the same frame
412  if(band.front().center.header.frame_id != costmap_ros_->getGlobalFrameID())
413  {
414  ROS_ERROR("Elastic Band expects plan for optimization in the %s frame, the plan was sent in the %s frame.",
415  costmap_ros_->getGlobalFrameID().c_str(), band.front().center.header.frame_id.c_str());
416  return false;
417  }
418 
419  double distance;
420  for(int i = 0; i < ((int) band.size()); i++)
421  {
422  // update Size of Bubbles in band by calculating Dist to nearest Obstacle [depends kinematic, environment]
423  if(!calcObstacleKinematicDistance(band.at(i).center.pose, distance))
424  {
425  ROS_DEBUG("Optimization (Elastic Band) - Calculation of Distance failed. Frame %d of %d Probably outside map coordinates.",
426  i, ((int) band.size()) );
427  return false;
428  }
429 
430  if(distance == 0.0)
431  {
432  // frame must not be immediately in collision -> otherwise calculation of gradient will later be invalid
433  ROS_DEBUG("Optimization (Elastic Band) - Calculation of Distance failed. Frame %d of %d in collision. Plan invalid. Trying to refine band.",
434  i, ((int) band.size()) );
435  // TODO if frame in collision try to repair band instead of aborting everything
436  return false;
437  }
438 
439  band.at(i).expansion = distance;
440  }
441 
442  // close gaps and remove redundant bubbles
443  if(!refineBand(band))
444  {
445  ROS_DEBUG("Elastic Band is broken. Could not close gaps in band. Global replanning needed.");
446  return false;
447  }
448 
449  // get a copy of current (valid) band
450  std::vector<Bubble> tmp_band = band;
451 
452  // now optimize iteratively (for instance by miminizing the energy-function of the full system)
453  for(int i = 0; i < num_optim_iterations_; i++)
454  {
455  ROS_DEBUG("Inside optimization: Cycle no %d", i);
456 
457  // calculate forces and apply changes
458  if(!modifyBandArtificialForce(tmp_band))
459  {
460  ROS_DEBUG("Optimization failed while trying to modify Band.");
461  // something went wrong -> discard changes and stop process
462  return false;
463  }
464 
465  // check whether band still valid - refine if neccesarry
466  if(!refineBand(tmp_band))
467  {
468  ROS_DEBUG("Optimization failed while trying to refine modified band");
469  // modified band is not valid anymore -> discard changes and stop process
470  return false;
471  }
472  }
473 
474  // copy changes back to band
475  band = tmp_band;
476  return true;
477  }
478 
479 
480  // private methods
481 
482  bool EBandPlanner::refineBand(std::vector<Bubble>& band)
483  {
484  // check if plugin initialized
485  if(!initialized_)
486  {
487  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
488  return false;
489  }
490 
491  // check if band valid (minimum 2 bubbles)
492  if(band.size() < 2)
493  {
494  ROS_WARN("Attempt to convert empty band to plan. Valid band needs to have at least 2 Frames. This one has %d.", ((int) band.size()) );
495  return false;
496  }
497 
498  // instantiate local variables
499  bool success;
500  std::vector<Bubble> tmp_band;
501  std::vector<Bubble>::iterator start_iter, end_iter;
502 
503  // remove redundant Bubbles and fill gabs recursively
504  tmp_band = band;
505  start_iter = tmp_band.begin();
506  end_iter = (tmp_band.end() - 1); // -1 because .end() points "past the end"!
507 
508  success = removeAndFill(tmp_band, start_iter, end_iter);
509 
510  if(!success)
511  ROS_DEBUG("Band is broken. Could not close gaps.");
512  else
513  {
514 #ifdef DEBUG_EBAND_
515  ROS_DEBUG("Recursive filling and removing DONE");
516 #endif
517  band = tmp_band;
518  }
519 
520  return success;
521  }
522 
523 
524  bool EBandPlanner::removeAndFill(std::vector<Bubble>& band, std::vector<Bubble>::iterator& start_iter,std::vector<Bubble>::iterator& end_iter)
525  {
526  // instantiate local variables
527  bool overlap;
528  std::vector<Bubble>::iterator tmp_iter;
529  int mid_int, diff_int;
530 
531 #ifdef DEBUG_EBAND_
532  int debug_dist_start, debug_dist_iters;
533  debug_dist_start = std::distance(band.begin(), start_iter);
534  debug_dist_iters = std::distance(start_iter, end_iter);
535  ROS_DEBUG("Refining Recursive - Check if Bubbles %d and %d overlapp. Total size of band %d.", debug_dist_start, (debug_dist_start + debug_dist_iters), ((int) band.size()) );
536 #endif
537 
538  // check that iterators are still valid
539  ROS_ASSERT( start_iter >= band.begin() );
540  ROS_ASSERT( end_iter < band.end() ); // "<" because .end() points _behind_ last element of vector
541  ROS_ASSERT( start_iter < end_iter );
542 
543  // check whether start and end bubbles of this intervall overlap
544  overlap = checkOverlap(*start_iter, *end_iter);
545 
546  if(overlap)
547  {
548 
549 #ifdef DEBUG_EBAND_
550  ROS_DEBUG("Refining Recursive - Bubbles overlapp, check for redundancies");
551 #endif
552 
553  // if there are bubbles between start and end of intervall remove them (they are redundant as start and end of intervall do overlap)
554  if((start_iter + 1) < end_iter)
555  {
556 #ifdef DEBUG_EBAND_
557  ROS_DEBUG("Refining Recursive - Bubbles overlapp, removing Bubbles %d to %d.", (debug_dist_start + 1), (debug_dist_start + debug_dist_iters -1));
558 #endif
559 
560  // erase bubbles between start and end (but not start and end themself) and get new iterator to end (old one is invalid)
561  tmp_iter = band.erase((start_iter+1), end_iter);
562 
563  // write back changed iterator pointing to the end of the intervall
564  end_iter = tmp_iter;
565  }
566 
567 #ifdef DEBUG_EBAND_
568  ROS_DEBUG("Refining Recursive - Bubbles overlapp - DONE");
569 #endif
570 
571  // we are done here (leaf of this branch is reached)
572  return true;
573  }
574 
575 
576  // if bubbles do not overlap -> check whether there are still bubbles between start and end
577  if((start_iter + 1) < end_iter)
578  {
579 #ifdef DEBUG_EBAND_
580  ROS_DEBUG("Refining Recursive - Bubbles do not overlapp, go one recursion deeper");
581 #endif
582 
583  // split remaining sequence of bubbles
584  // get distance between start and end iterator for this intervall
585  mid_int = std::distance(start_iter, end_iter);
586  mid_int = mid_int/2; // division by integer implies floor (round down)
587 
588  // now get iterator pointing to the middle (roughly)
589  tmp_iter = start_iter + mid_int;
590  // and realative position of end_iter to tmp_iter
591  diff_int = (int) std::distance(tmp_iter, end_iter);
592 
593  // after all this arithmetics - check that iterators are still valid
594  ROS_ASSERT( start_iter >= band.begin() );
595  ROS_ASSERT( end_iter < band.end() ); // "<" because .end() points _behind_ last element of vector
596  ROS_ASSERT( start_iter < end_iter );
597 
598 
599  // and call removeAndFill recursively for the left intervall
600  if(!removeAndFill(band, start_iter, tmp_iter))
601  {
602  // band is broken in this intervall and could not be fixed
603  return false;
604  }
605 
606  // carefull at this point!!! if we filled in or removed bubbles end_iter is not valid anymore
607  // but the relative position towards tmp_iter is still the same and tmp_iter was kept valid in the lower recursion steps
608  end_iter = tmp_iter + diff_int;
609 
610  // check that iterators are still valid - one more time
611  ROS_ASSERT( start_iter >= band.begin() );
612  ROS_ASSERT( end_iter < band.end() ); // "<" because .end() points _behind_ last element of vector
613  ROS_ASSERT( (start_iter < tmp_iter) && (tmp_iter < end_iter) );
614 
615 
616  // o.k. we are done with left hand intervall now do the same for the right hand intervall
617  // but first get relative position of start and tmp iter
618  diff_int = (int) std::distance(start_iter, tmp_iter);
619  if(!removeAndFill(band, tmp_iter, end_iter))
620  {
621  // band is broken in this intervall and could not be fixed
622  return false;
623  }
624 
625  // if we filled in bubbles vector might have been reallocated -> start_iter might be invalid
626  start_iter = tmp_iter - diff_int;
627 
628  // check that iterators are still valid - almost done
629  ROS_ASSERT( start_iter >= band.begin() );
630  ROS_ASSERT( end_iter < band.end() ); // "<" because .end() points _behind_ last element of vector
631  ROS_ASSERT( (start_iter < tmp_iter) && (tmp_iter < end_iter) );
632 
633 
634  // we reached the leaf but we are not yet done
635  // -> we know that there are no redundant elements in the left intervall taken on its own
636  // -> and we know the same holds for the right intervall
637  // but the middle bubble itself might be redundant -> check it
638  if(checkOverlap(*(tmp_iter-1), *(tmp_iter+1)))
639  {
640 #ifdef DEBUG_EBAND_
641  ROS_DEBUG("Refining Recursive - Removing middle bubble");
642 #endif
643 
644  // again: get distance between (tmp_iter + 1) and end_iter, (+1 because we will erase tmp_iter itself)
645  diff_int = (int) std::distance((tmp_iter + 1), end_iter);
646 
647  // remove middle bubble and correct end_iter
648  tmp_iter = band.erase(tmp_iter);
649  end_iter = tmp_iter + diff_int;
650  }
651 
652  // check that iterators are still valid - almost almost
653  ROS_ASSERT( start_iter >= band.begin() );
654  ROS_ASSERT( end_iter < band.end() ); // "<" because .end() points _behind_ last element of vector
655  ROS_ASSERT( start_iter < end_iter );
656 
657 #ifdef DEBUG_EBAND_
658  ROS_DEBUG("Refining Recursive - Bubbles do not overlapp, go one recursion deeper DONE");
659 #endif
660 
661  //now we are done with this case
662  return true;
663  }
664 
665 
666 #ifdef DEBUG_EBAND_
667  ROS_DEBUG("Refining Recursive - Gap detected, fill recursive");
668 #endif
669 
670  // last possible case -> bubbles do not overlap AND there are nor bubbles in between -> try to fill gap recursively
671  if(!fillGap(band, start_iter, end_iter))
672  {
673  // band is broken in this intervall and could not be fixed (this should only be called on a leaf, so we put a log_out here;)
674  ROS_DEBUG("Failed to fill gap between bubble %d and %d.", (int) distance(band.begin(), start_iter), (int) distance(band.begin(), end_iter) );
675  return false;
676  }
677 
678 #ifdef DEBUG_EBAND_
679  ROS_DEBUG("Refining Recursive - Gap detected, fill recursive DONE");
680 #endif
681 
682  // we could fill the gap (reached leaf of this branch)
683  return true;
684  }
685 
686 
687  bool EBandPlanner::fillGap(std::vector<Bubble>& band, std::vector<Bubble>::iterator& start_iter,std::vector<Bubble>::iterator& end_iter)
688  {
689  // insert bubbles in the middle between not-overlapping bubbles (e.g. (Dist > Size Bub1) && (Dist > Size Bub2) )
690  // repeat until gaps are closed
691 
692  // instantiate local variables
693  double distance = 0.0;
694  Bubble interpolated_bubble;
695  geometry_msgs::PoseStamped interpolated_center;
696  std::vector<Bubble>::iterator tmp_iter;
697  int diff_int, start_num, end_num;
698 
699  // make sure this method was called for a valid element in the forces or bubbles vector
700  ROS_ASSERT( start_iter >= band.begin() );
701  ROS_ASSERT( end_iter < band.end() ); // "<" because .end() points _behind_ last element of vector
702  ROS_ASSERT( start_iter < end_iter );
703 
704 
705 #ifdef DEBUG_EBAND_
706  ROS_DEBUG("Fill recursive - interpolate");
707 #endif
708 
709  // interpolate between bubbles [depends kinematic]
710  if(!interpolateBubbles(start_iter->center, end_iter->center, interpolated_center))
711  {
712  // interpolation failed (for whatever reason), so return with false
713  start_num = std::distance(band.begin(), start_iter);
714  end_num = std::distance(band.begin(), end_iter);
715  ROS_DEBUG("Interpolation failed while trying to fill gap between bubble %d and %d.", start_num, end_num);
716  return false;
717  }
718 
719 
720 #ifdef DEBUG_EBAND_
721  ROS_DEBUG("Fill recursive - calc expansion of interpolated bubble");
722 #endif
723 
724  // calc Size of Bubbles by calculating Dist to nearest Obstacle [depends kinematic, environment]
725  if(!calcObstacleKinematicDistance(interpolated_center.pose, distance))
726  {
727  // pose probably outside map coordinates
728  start_num = std::distance(band.begin(), start_iter);
729  end_num = std::distance(band.begin(), end_iter);
730  ROS_DEBUG("Calculation of Distance failed for interpolated bubble - failed to fill gap between bubble %d and %d.", start_num, end_num);
731  return false;
732  }
733 
734  if(distance <= tiny_bubble_expansion_)
735  {
736  // band broken! frame must not be immediately in collision -> otherwise calculation of gradient will later be invalid
737  start_num = std::distance(band.begin(), start_iter);
738  end_num = std::distance(band.begin(), end_iter);
739  ROS_DEBUG("Interpolated Bubble in Collision - failed to fill gap between bubble %d and %d.", start_num, end_num);
740  // TODO this means only that there is an obstacle on the direct interconnection between the bubbles - think about repair or rescue strategies -
741  return false;
742  }
743 
744 
745 #ifdef DEBUG_EBAND_
746  ROS_DEBUG("Fill recursive - inserting interpolated bubble at (%f, %f), with expansion %f", interpolated_center.pose.position.x, interpolated_center.pose.position.y, distance);
747 #endif
748 
749  // insert bubble and assign center and expansion
750  interpolated_bubble.center = interpolated_center;
751  interpolated_bubble.expansion = distance;
752  // insert bubble (vector.insert() inserts elements before given iterator) and get iterator pointing to it
753  tmp_iter = band.insert(end_iter, interpolated_bubble);
754  // insert is a little bit more tricky than erase, as it may require reallocation of the vector -> start and end iter could be invalid
755  start_iter = tmp_iter - 1;
756  end_iter = tmp_iter + 1;
757 
758  // check that iterators are still valid - just in case :)
759  ROS_ASSERT( start_iter >= band.begin() );
760  ROS_ASSERT( end_iter < band.end() ); // "<" because .end() points _behind_ last element of vector
761  ROS_ASSERT( (start_iter < tmp_iter) && (tmp_iter < end_iter) );
762 
763 
764 #ifdef DEBUG_EBAND_
765  ROS_DEBUG("Fill recursive - check overlap interpolated bubble and first bubble");
766 #endif
767 
768  // we have now two intervalls (left and right of inserted bubble) which need to be checked again and filled if neccessary
769  if(!checkOverlap(*start_iter, *tmp_iter))
770  {
771 
772 #ifdef DEBUG_EBAND
773  ROS_DEBUG("Fill recursive - gap btw. interpolated and first bubble - fill recursive");
774 #endif
775 
776  // gap in left intervall -> try to fill
777  if(!fillGap(band, start_iter, tmp_iter))
778  {
779  // band is broken in this intervall and could not be fixed
780  return false;
781  }
782  // bubbles were inserted -> make sure to keep end_iter iterator valid
783  end_iter = tmp_iter + 1;
784  }
785 
786  // check that iterators are still valid - just in case :)
787  ROS_ASSERT( start_iter >= band.begin() );
788  ROS_ASSERT( end_iter < band.end() ); // "<" because .end() points _behind_ last element of vector
789  ROS_ASSERT( (start_iter < tmp_iter) && (tmp_iter < end_iter) );
790 
791 
792 #ifdef DEBUG_EBAND_
793  ROS_DEBUG("Fill recursive - check overlap interpolated bubble and second bubble");
794 #endif
795 
796  if(!checkOverlap(*tmp_iter, *end_iter))
797  {
798 
799 #ifdef DEBUG_EBAND_
800  ROS_DEBUG("Fill recursive - gap btw. interpolated and second bubble - fill recursive");
801 #endif
802 
803  // get distance between start_iter and tmp_iter before filling right intervall (in case of reallocation of vector)
804  diff_int = (int) std::distance(start_iter, tmp_iter);
805 
806  // gap in left intervall -> try to fill
807  if(!fillGap(band, tmp_iter, end_iter))
808  {
809  // band is broken in this intervall and could not be fixed
810  return false;
811  }
812  // bubbles were inserted -> make sure to keep start_iter iterator valid
813  start_iter = tmp_iter - diff_int;
814  }
815 
816  // check that iterators are still valid - just in case :)
817  ROS_ASSERT( start_iter >= band.begin() );
818  ROS_ASSERT( end_iter < band.end() ); // "<" because .end() points _behind_ last element of vector
819  ROS_ASSERT( (start_iter < tmp_iter) && (tmp_iter < end_iter) );
820 
821 
822 #ifdef DEBUG_EBAND_
823  ROS_DEBUG("Fill recursive - gap closed");
824 #endif
825 
826  // bubbles overlap, iterators are kept valid -> done
827  return true;
828  }
829 
830 
831  // optimization
832 
833  bool EBandPlanner::modifyBandArtificialForce(std::vector<Bubble>& band)
834  {
835  if(band.empty())
836  {
837  ROS_ERROR("Trying to modify an empty band.");
838  return false;
839  }
840 
841  if(band.size() <= 2)
842  {
843  // nothing to do here -> we can stop right away
844  return true;
845  }
846 
847  std::vector<geometry_msgs::WrenchStamped> internal_forces, external_forces, forces;
848  geometry_msgs::WrenchStamped wrench;
849 
850 #ifdef DEBUG_EBAND_
851  //publish original band
852  if(visualization_)
853  eband_visual_->publishBand("bubbles", band);
854 #endif
855 
856  // init variables to calm down debug warnings
857  wrench.header.stamp = ros::Time::now();
858  wrench.header.frame_id = band[0].center.header.frame_id;
859  wrench.wrench.force.x = 0.0;
860  wrench.wrench.force.y = 0.0;
861  wrench.wrench.force.z = 0.0;
862  wrench.wrench.torque.x = 0.0;
863  wrench.wrench.torque.y = 0.0;
864  wrench.wrench.torque.z = 0.0;
865  internal_forces.assign(band.size(), wrench);
866  external_forces = internal_forces;
867  forces = internal_forces;
868 
869  // TODO log timigs of planner
870  // instantiate variables for timing
871  //ros::Time time_stamp1, time_stamp2;
872  //ros::Duration duration;
873  //time_stamp1 = ros::Time::now();
874 
875  // due to refinement band might change its size -> use while loop
876  int i = 1;
877  bool forward = true; // cycle 1xforwards and 1xbackwards through band
878  while( (i>0) && (i < ((int) band.size() - 1)) )
879  {
880  ROS_DEBUG("Modifying bubble %d.", i);
881 
882 
883 #ifdef DEBUG_EBAND_
884  ROS_DEBUG("Calculating internal force for bubble %d.", i);
885 #endif
886 
887  if(!calcInternalForces(i, band, band.at(i), internal_forces.at(i)))
888  {
889  // calculation of internal forces failed - stopping optimization
890  ROS_DEBUG("Calculation of internal forces failed");
891  return false;
892  }
893 
894 #ifdef DEBUG_EBAND_
895  if(visualization_)
896  // publish internal forces
897  eband_visual_->publishForce("internal_forces", i, eband_visual_->blue, internal_forces[i], band[i]);
898  // Log out debug info about next step
899  ROS_DEBUG("Calculating external force for bubble %d.", i);
900 #endif
901 
902 
903  //if(!calcExternalForces(i, band, external_forces))
904  if(!calcExternalForces(i, band.at(i), external_forces.at(i)))
905  {
906  // calculation of External Forces failed - stopping optimization
907  ROS_DEBUG("Calculation of external forces failed");
908  return false;
909  }
910 
911 #ifdef DEBUG_EBAND_
912  if(visualization_)
913  //publish external forces
914  eband_visual_->publishForce("external_forces", i, eband_visual_->red, external_forces[i], band[i]);
915  // Log out debug info about next step
916  ROS_DEBUG("Superposing internal and external forces");
917 #endif
918 
919 
920  // sum up external and internal forces over all bubbles
921  forces.at(i).wrench.force.x = internal_forces.at(i).wrench.force.x + external_forces.at(i).wrench.force.x;
922  forces.at(i).wrench.force.y = internal_forces.at(i).wrench.force.y + external_forces.at(i).wrench.force.y;
923  forces.at(i).wrench.force.z = internal_forces.at(i).wrench.force.z + external_forces.at(i).wrench.force.z;
924 
925  forces.at(i).wrench.torque.x = internal_forces.at(i).wrench.torque.x + external_forces.at(i).wrench.torque.x;
926  forces.at(i).wrench.torque.y = internal_forces.at(i).wrench.torque.y + external_forces.at(i).wrench.torque.y;
927  forces.at(i).wrench.torque.z = internal_forces.at(i).wrench.torque.z + external_forces.at(i).wrench.torque.z;
928 
929 #ifdef DEBUG_EBAND_
930  ROS_DEBUG("Superpose forces: (x, y, theta) = (%f, %f, %f)", forces.at(i).wrench.force.x, forces.at(i).wrench.force.y, forces.at(i).wrench.torque.z);
931  ROS_DEBUG("Supressing tangential forces");
932 #endif
933 
934  if(!suppressTangentialForces(i, band, forces.at(i)))
935  {
936  // suppression of tangential forces failed
937  ROS_DEBUG("Supression of tangential forces failed");
938  return false;
939  }
940 
941 #ifdef DEBUG_EBAND_
942  if(visualization_)
943  //publish resulting forces
944  eband_visual_->publishForce("resulting_forces", i, eband_visual_->green, forces[i], band[i]);
945 #endif
946 
947 
948  ROS_DEBUG("Applying forces to modify band");
949  if(!applyForces(i, band, forces))
950  {
951  // band invalid
952  ROS_DEBUG("Band is invalid - Stopping Modification");
953  return false;
954  }
955 
956 #ifdef DEBUG_EBAND_
957  if(visualization_)
958  {
959  // publish band with changed bubble at resulting position
960  eband_visual_->publishBand("bubbles", band);
961  ros::Duration(0.01).sleep();
962  }
963 #endif
964 
965 
966  //next bubble
967  if(forward)
968  {
969  i++;
970  if(i == ((int) band.size() - 1))
971  {
972  // reached end of band - start backwards cycle until at start again - then stop
973  forward = false;
974  i--;
975  ROS_DEBUG("Optimization Elastic Band - Forward cycle done, starting backward cycle");
976  }
977  }
978  else
979  {
980  i--;
981  }
982  }
983 
984  return true;
985  }
986 
987 
988  bool EBandPlanner::applyForces(int bubble_num, std::vector<Bubble>& band, std::vector<geometry_msgs::WrenchStamped> forces)
989  {
990  //cycle over all bubbles except first and last (these are fixed)
991  if(band.size() <= 2)
992  {
993  // nothing to do here -> we can stop right away - no forces calculated
994  return true;
995  }
996 
997  geometry_msgs::Pose2D bubble_pose2D, new_bubble_pose2D;
998  geometry_msgs::Pose bubble_pose, new_bubble_pose;
999  geometry_msgs::Twist bubble_jump;
1000  Bubble new_bubble = band.at(bubble_num);
1001  double distance;
1002 
1003 
1004  // move bubble
1005  bubble_pose = band.at(bubble_num).center.pose;
1006  PoseToPose2D(bubble_pose, bubble_pose2D);
1007 
1008  // move according to bubble_new = bubble_old + alpha*force -> we choose alpha to be the current expansion of the modified bubble
1009  bubble_jump.linear.x = band.at(bubble_num).expansion*forces.at(bubble_num).wrench.force.x;
1010  bubble_jump.linear.y = band.at(bubble_num).expansion*forces.at(bubble_num).wrench.force.y;
1011  bubble_jump.linear.z = 0.0;
1012  bubble_jump.angular.x = 0.0;
1013  bubble_jump.angular.y = 0.0;
1014  bubble_jump.angular.z = band.at(bubble_num).expansion/getCircumscribedRadius(*costmap_ros_) * forces.at(bubble_num).wrench.torque.z;
1015  bubble_jump.angular.z = angles::normalize_angle(bubble_jump.angular.z);
1016 
1017  // apply changes to calc tmp bubble position
1018  new_bubble_pose2D.x = bubble_pose2D.x + bubble_jump.linear.x;
1019  new_bubble_pose2D.y = bubble_pose2D.y + bubble_jump.linear.y;
1020  new_bubble_pose2D.theta = bubble_pose2D.theta + bubble_jump.angular.z;
1021  new_bubble_pose2D.theta = angles::normalize_angle(new_bubble_pose2D.theta);
1022 
1023  // apply changes to local copy
1024  Pose2DToPose(new_bubble_pose, new_bubble_pose2D);
1025  new_bubble.center.pose = new_bubble_pose;
1026 
1027 #ifdef DEBUG_EBAND_
1028  ROS_DEBUG("Try moving bubble %d at (%f, %f, %f) by (%f, %f, %f).", bubble_num, bubble_pose2D.x, bubble_pose2D.y, bubble_pose2D.theta,
1029  bubble_jump.linear.x, bubble_jump.linear.y, bubble_jump.angular.z);
1030 #endif
1031 
1032 
1033  // check validity of moved bubble
1034 
1035  // recalc expansion of bubble -> calc Size of Bubbles by calculating Dist to nearest Obstacle [depends kinematic, environment]
1036  if(!calcObstacleKinematicDistance(new_bubble_pose, distance))
1037  {
1038  ROS_DEBUG("Calculation of Distance failed. Frame %d of %d Probably outside map. Discarding Changes", bubble_num, ((int) band.size()) );
1039 
1040 #ifdef DEBUG_EBAND_
1041  if(visualization_)
1042  eband_visual_->publishBubble("bubble_hypo", bubble_num, eband_visual_->red, new_bubble);
1043 #endif
1044 
1045  // this bubble must not be changed, but band is still valid -> continue with other bubbles
1046  return true;
1047  }
1048 
1049  if(distance <= tiny_bubble_expansion_)
1050  {
1051  // frame must not be immediately in collision -> otherwise calculation of gradient will later be invalid
1052  ROS_DEBUG("Calculation of Distance failed. Frame %d of %d in collision. Plan invalid. Discarding Changes", bubble_num, ((int) band.size()) );
1053 
1054 #ifdef DEBUG_EBAND_
1055  if(visualization_)
1056  eband_visual_->publishBubble("bubble_hypo", bubble_num, eband_visual_->red, new_bubble);
1057 #endif
1058 
1059  // this bubble must not be changed, but band is still valid -> continue with other bubbles
1060  return true;
1061  }
1062 
1063  // so far o.k. -> assign distance to new bubble
1064  new_bubble.expansion = distance;
1065 
1066 
1067  // check whether step was reasonable
1068 
1069  geometry_msgs::WrenchStamped new_bubble_force = forces.at(bubble_num);
1070 
1071  // check whether we get a valid force calculation here
1072  if(!getForcesAt(bubble_num, band, new_bubble, new_bubble_force))
1073  {
1074  // error during calculation of forces for the new position - discard changes
1075  ROS_DEBUG("Cannot calculate forces on bubble %d at new position - discarding changes", bubble_num);
1076  return true;
1077  }
1078 
1079 #ifdef DEBUG_EBAND_
1080  ROS_DEBUG("Check for zero-crossings in force on bubble %d", bubble_num);
1081 #endif
1082 
1083  // check for zero-crossings in the force-vector
1084  double checksum_zero, abs_new_force, abs_old_force;
1085 
1086  // project force-vectors onto each other
1087  checksum_zero = (new_bubble_force.wrench.force.x * forces.at(bubble_num).wrench.force.x) +
1088  (new_bubble_force.wrench.force.y * forces.at(bubble_num).wrench.force.y) +
1089  (new_bubble_force.wrench.torque.z * forces.at(bubble_num).wrench.torque.z);
1090 
1091  // if sign changes and ...
1092  if(checksum_zero < 0.0)
1093  {
1094  ROS_DEBUG("Detected zero-crossings in force on bubble %d. Checking total change in force.", bubble_num);
1095  // check the absolute values of the two vectors
1096  abs_new_force = sqrt( (new_bubble_force.wrench.force.x * new_bubble_force.wrench.force.x) +
1097  (new_bubble_force.wrench.force.y * new_bubble_force.wrench.force.y) +
1098  (new_bubble_force.wrench.torque.z * new_bubble_force.wrench.torque.z) );
1099  abs_old_force = sqrt( (forces.at(bubble_num).wrench.force.x * forces.at(bubble_num).wrench.force.x) +
1100  (forces.at(bubble_num).wrench.force.x * forces.at(bubble_num).wrench.force.x) +
1101  (forces.at(bubble_num).wrench.torque.z * forces.at(bubble_num).wrench.torque.z) );
1102 
1103  // force still has a significant high value (> ~75% of old force by default)
1104  if( (abs_new_force > equilibrium_relative_overshoot_ * abs_old_force) && (abs_new_force > significant_force_) )
1105  {
1106  ROS_DEBUG("Detected significante change in force (%f to %f) on bubble %d. Entering Recursive Approximation.", abs_old_force, abs_new_force, bubble_num);
1107  // o.k. now we really have to take a closer look -> start recursive approximation to equilibrium-point
1108  int curr_recursion_depth = 0;
1109  geometry_msgs::Twist new_step_width;
1110  Bubble curr_bubble = band.at(bubble_num);
1111  geometry_msgs::WrenchStamped curr_bubble_force = forces.at(bubble_num);
1112 
1113  // half step size
1114  new_step_width.linear.x = 0.5*bubble_jump.linear.x;
1115  new_step_width.linear.y = 0.5*bubble_jump.linear.y;
1116  new_step_width.linear.z = 0.5*bubble_jump.linear.z;
1117  new_step_width.angular.x = 0.5*bubble_jump.angular.x;
1118  new_step_width.angular.y = 0.5*bubble_jump.angular.y;
1119  new_step_width.angular.z = 0.5*bubble_jump.angular.z;
1120 
1121  // one step deeper into the recursion
1122  if(moveApproximateEquilibrium(bubble_num, band, curr_bubble, curr_bubble_force, new_step_width, curr_recursion_depth))
1123  {
1124  // done with recursion - change bubble and hand it back
1125  new_bubble = curr_bubble;
1126 
1127 #ifdef DEBUG_EBAND_
1128  geometry_msgs::Pose2D curr_bubble_pose2D;
1129  PoseToPose2D(curr_bubble.center.pose, curr_bubble_pose2D);
1130  ROS_DEBUG("Instead - Try moving bubble %d at (%f, %f, %f) by (%f, %f, %f) to (%f, %f, %f).",
1131  bubble_num, bubble_pose2D.x, bubble_pose2D.y, bubble_pose2D.theta,
1132  new_step_width.linear.x, new_step_width.linear.y, new_step_width.angular.z,
1133  curr_bubble_pose2D.x, curr_bubble_pose2D.y, curr_bubble_pose2D.theta);
1134 #endif
1135  }
1136  }
1137  }
1138 
1139 
1140  // check validity of resulting band (given the moved bubble)
1141 
1142  // TODO use this routine not only to check whether gap can be filled but also to fill gap (if possible)
1143  // get local copy of band, set new position of moved bubble and init iterators
1144  std::vector<Bubble> tmp_band = band;
1145  std::vector<Bubble>::iterator start_iter, end_iter;
1146  tmp_band.at(bubble_num) = new_bubble;
1147  start_iter = tmp_band.begin();
1148 
1149  // check left connection (bubble and bubble-1)
1150  start_iter = start_iter + bubble_num - 1;
1151  end_iter = start_iter + 1;
1152 
1153  // check Overlap - if bubbles do not overlap try to fill gap
1154  if(!checkOverlap(*start_iter, *end_iter))
1155  {
1156  if(!fillGap(tmp_band, start_iter, end_iter))
1157  {
1158  ROS_DEBUG("Bubble at new position cannot be connected to neighbour. Discarding changes.");
1159  // this bubble must not be changed, but band is still valid -> continue with other bubbles
1160  return true;
1161  }
1162  }
1163 
1164 
1165  // get fresh copy of band, set new position of bubble again and reinit iterators
1166  tmp_band = band;
1167  tmp_band.at(bubble_num) = new_bubble;
1168  start_iter = tmp_band.begin();
1169 
1170  // check right connection (bubble and bubble +1)
1171  start_iter = start_iter + bubble_num;
1172  end_iter = start_iter + 1;
1173 
1174  // check Overlap - if bubbles do not overlap try to fill gap
1175  if(!checkOverlap(*start_iter, *end_iter))
1176  {
1177  if(!fillGap(tmp_band, start_iter, end_iter))
1178  {
1179  ROS_DEBUG("Bubble at new position cannot be connected to neighbour. Discarding changes.");
1180  // this bubble must not be changed, but band is still valid -> continue with other bubbles
1181  return true;
1182  }
1183  }
1184 
1185 
1186  // check successful - bubble and band valid apply changes
1187 
1188 #ifdef DEBUG_EBAND_
1189  ROS_DEBUG("Frame %d of %d: Check successful - bubble and band valid. Applying Changes", bubble_num, ((int) band.size()) );
1190 #endif
1191 
1192  band.at(bubble_num) = new_bubble;
1193 
1194  return true;
1195  }
1196 
1197 
1198  bool EBandPlanner::moveApproximateEquilibrium(const int& bubble_num, const std::vector<Bubble>& band, Bubble& curr_bubble,
1199  const geometry_msgs::WrenchStamped& curr_bubble_force, geometry_msgs::Twist& curr_step_width, const int& curr_recursion_depth)
1200  {
1201 
1202  double distance;
1203  Bubble new_bubble = curr_bubble;
1204  geometry_msgs::Pose2D new_bubble_pose2D, curr_bubble_pose2D;
1205  geometry_msgs::WrenchStamped new_bubble_force = curr_bubble_force;
1206 
1207  // move bubble
1208  PoseToPose2D(curr_bubble.center.pose, curr_bubble_pose2D);
1209  PoseToPose2D(new_bubble.center.pose, new_bubble_pose2D);
1210 
1211  // apply changes to calculate tmp bubble position
1212  new_bubble_pose2D.x = curr_bubble_pose2D.x + curr_step_width.linear.x;
1213  new_bubble_pose2D.y = curr_bubble_pose2D.y + curr_step_width.linear.y;
1214  new_bubble_pose2D.theta = curr_bubble_pose2D.theta + curr_step_width.angular.z;
1215  new_bubble_pose2D.theta = angles::normalize_angle(new_bubble_pose2D.theta);
1216 
1217  // apply changes to local copy
1218  Pose2DToPose(new_bubble.center.pose, new_bubble_pose2D);
1219 
1220 
1221  // check validity of moved bubble
1222 
1223  // recalc expansion of bubble -> calc Size of Bubbles by calculating Dist to nearest Obstacle [depends kinematic, environment]
1224  if(!calcObstacleKinematicDistance(new_bubble.center.pose, distance))
1225  return false;
1226 
1227  // we wont be able to calculate forces later on
1228  if(distance == 0.0)
1229  return false;
1230 
1231 
1232  // so far o.k. -> assign distance to new bubble
1233  new_bubble.expansion = distance;
1234 
1235  // check whether we get a valid force calculation here
1236  if(!getForcesAt(bubble_num, band, new_bubble, new_bubble_force))
1237  return false;
1238 
1239  // great - lets store this - this is better then what we had so far
1240  curr_bubble = new_bubble;
1241 
1242  // if everything is fine and we reached our maximum recursion depth
1243  if(curr_recursion_depth >= max_recursion_depth_approx_equi_)
1244  // break recursion at this point
1245  return true;
1246 
1247 
1248  // now - let's check for zero-crossing
1249 
1250 #ifdef DEBUG_EBAND_
1251  ROS_DEBUG("Check for zero-crossings in force on bubble %d - Recursion %d", bubble_num, curr_recursion_depth);
1252 #endif
1253 
1254  double checksum_zero, abs_new_force, abs_old_force;
1255  int new_recursion_depth;
1256  geometry_msgs::Twist new_step_width;
1257 
1258  // check zero-crossing by projecting force-vectors onto each other
1259  checksum_zero = (new_bubble_force.wrench.force.x * curr_bubble_force.wrench.force.x) +
1260  (new_bubble_force.wrench.force.y * curr_bubble_force.wrench.force.y) +
1261  (new_bubble_force.wrench.torque.z * curr_bubble_force.wrench.torque.z);
1262 
1263  if(checksum_zero < 0.0)
1264  {
1265 #ifdef DEBUG_EBAND_
1266  ROS_DEBUG("Detected zero-crossings in force on bubble %d - Recursion %d. Checking total change in force.", bubble_num, curr_recursion_depth);
1267 #endif
1268 
1269  // check the absolute values of the two vectors
1270  abs_new_force = sqrt( (new_bubble_force.wrench.force.x * new_bubble_force.wrench.force.x) +
1271  (new_bubble_force.wrench.force.y * new_bubble_force.wrench.force.y) +
1272  (new_bubble_force.wrench.torque.z * new_bubble_force.wrench.torque.z) );
1273  abs_old_force = sqrt( (curr_bubble_force.wrench.force.x * curr_bubble_force.wrench.force.x) +
1274  (curr_bubble_force.wrench.force.x * curr_bubble_force.wrench.force.x) +
1275  (curr_bubble_force.wrench.torque.z * curr_bubble_force.wrench.torque.z) );
1276 
1277  if( (abs_new_force > equilibrium_relative_overshoot_ * abs_old_force) && (abs_new_force > significant_force_) )
1278  {
1279 #ifdef DEBUG_EBAND_
1280  ROS_DEBUG("Detected significant change in force (%f to %f) on bubble %d - Recursion %d. Going one Recursion deeper.", abs_old_force, abs_new_force, bubble_num, curr_recursion_depth);
1281 #endif
1282 
1283  // o.k. now we really have to take a closer look -> start recursive approximation to equilibrium-point
1284  new_recursion_depth = curr_recursion_depth + 1;
1285  // half step size - backward direction
1286  new_step_width.linear.x = -0.5*curr_step_width.linear.x;
1287  new_step_width.linear.y = -0.5*curr_step_width.linear.y;
1288  new_step_width.linear.z = -0.5*curr_step_width.linear.z;
1289  new_step_width.angular.x = -0.5*curr_step_width.angular.x;
1290  new_step_width.angular.y = -0.5*curr_step_width.angular.y;
1291  new_step_width.angular.z = -0.5*curr_step_width.angular.z;
1292 
1293  // one step deeper into the recursion
1294  if(moveApproximateEquilibrium(bubble_num, band, new_bubble, new_bubble_force, new_step_width, new_recursion_depth))
1295  // done with recursion - change bubble and hand it back
1296  curr_bubble = new_bubble;
1297 
1298  // otherwise - could not get a better value - return without change (curr_bubble as asigned above)
1299  }
1300 
1301  // otherwise - this is good enough for us - return with this value (curr_bubble as asigned above)
1302  }
1303  else
1304  {
1305 #ifdef DEBUG_EBAND_
1306  ROS_DEBUG("No zero-crossings in force on bubble %d - Recursion %d. Continue walk in same direction. Going one recursion deeper.", bubble_num, curr_recursion_depth);
1307 #endif
1308 
1309  // continue walk in same direction
1310  new_recursion_depth = curr_recursion_depth + 1;
1311  // half step size - backward direction
1312  new_step_width.linear.x = 0.5*curr_step_width.linear.x;
1313  new_step_width.linear.y = 0.5*curr_step_width.linear.y;
1314  new_step_width.linear.z = 0.5*curr_step_width.linear.z;
1315  new_step_width.angular.x = 0.5*curr_step_width.angular.x;
1316  new_step_width.angular.y = 0.5*curr_step_width.angular.y;
1317  new_step_width.angular.z = 0.5*curr_step_width.angular.z;
1318 
1319  // one step deeper into the recursion
1320  if(moveApproximateEquilibrium(bubble_num, band, new_bubble, new_bubble_force, new_step_width, new_recursion_depth))
1321  // done with recursion - change bubble and hand it back
1322  curr_bubble = new_bubble;
1323 
1324  // otherwise - could not get a better value - return without change (curr_bubble as asigned above)
1325  }
1326 
1327  // done
1328  return true;
1329  }
1330 
1331 
1332  bool EBandPlanner::getForcesAt(int bubble_num, std::vector<Bubble> band, Bubble curr_bubble, geometry_msgs::WrenchStamped& forces)
1333  {
1334  geometry_msgs::WrenchStamped internal_force, external_force;
1335 
1336  if(!calcInternalForces(bubble_num, band, curr_bubble, internal_force))
1337  {
1338  // calculation of internal forces failed - stopping optimization
1339  ROS_DEBUG("Calculation of internal forces failed");
1340  return false;
1341  }
1342 
1343  if(!calcExternalForces(bubble_num, curr_bubble, external_force))
1344  {
1345  // calculation of External Forces failed - stopping optimization
1346  ROS_DEBUG("Calculation of external forces failed");
1347  return false;
1348  }
1349 
1350  // sum up external and internal forces over all bubbles
1351  forces.wrench.force.x = internal_force.wrench.force.x + external_force.wrench.force.x;
1352  forces.wrench.force.y = internal_force.wrench.force.y + external_force.wrench.force.y;
1353  forces.wrench.force.z = internal_force.wrench.force.z + external_force.wrench.force.z;
1354 
1355  forces.wrench.torque.x = internal_force.wrench.torque.x + external_force.wrench.torque.x;
1356  forces.wrench.torque.y = internal_force.wrench.torque.y + external_force.wrench.torque.y;
1357  forces.wrench.torque.z = internal_force.wrench.torque.z + external_force.wrench.torque.z;
1358 
1359  if(!suppressTangentialForces(bubble_num, band, forces))
1360  {
1361  // suppression of tangential forces failed
1362  ROS_DEBUG("Supression of tangential forces failed");
1363  return false;
1364  }
1365 
1366  return true;
1367  }
1368 
1369 
1370  bool EBandPlanner::calcInternalForces(int bubble_num, std::vector<Bubble> band, Bubble curr_bubble, geometry_msgs::WrenchStamped& forces)
1371  {
1372  // check if plugin initialized
1373  if(!initialized_)
1374  {
1375  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
1376  return false;
1377  }
1378 
1379  //cycle over all bubbles except first and last (these are fixed)
1380  if(band.size() <= 2)
1381  {
1382  // nothing to do here -> we can stop right away - no forces calculated
1383  return true;
1384  }
1385 
1386  // init tmp variables
1387  double distance1, distance2;
1388  geometry_msgs::Twist difference1, difference2;
1389  geometry_msgs::Wrench wrench;
1390 
1391  // make sure this method was called for a valid element in the forces or bubbles vector
1392  ROS_ASSERT( bubble_num > 0 );
1393  ROS_ASSERT( bubble_num < ((int) band.size() - 1) );
1394 
1395 
1396  // get distance between bubbles
1397  if(!calcBubbleDistance(curr_bubble.center.pose, band[bubble_num-1].center.pose, distance1))
1398  {
1399  ROS_ERROR("Failed to calculate Distance between two bubbles. Aborting calculation of internal forces!");
1400  return false;
1401  }
1402 
1403  if(!calcBubbleDistance(curr_bubble.center.pose, band[bubble_num+1].center.pose, distance2))
1404  {
1405  ROS_ERROR("Failed to calculate Distance between two bubbles. Aborting calculation of internal forces!");
1406  return false;
1407  }
1408 
1409  // get (elementwise) difference bewtween bubbles
1410  if(!calcBubbleDifference(curr_bubble.center.pose, band[bubble_num-1].center.pose, difference1))
1411  {
1412  ROS_ERROR("Failed to calculate Difference between two bubbles. Aborting calculation of internal forces!");
1413  return false;
1414  }
1415 
1416  if(!calcBubbleDifference(curr_bubble.center.pose, band[bubble_num+1].center.pose, difference2))
1417  {
1418  ROS_ERROR("Failed to calculate Difference between two bubbles. Aborting calculation of internal forces!");
1419  return false;
1420  }
1421 
1422  // make sure to avoid division by (almost) zero during force calculation (avoid numerical problems)
1423  // -> if difference/distance is (close to) zero then the force in this direction should be zero as well
1424  if(distance1 <= tiny_bubble_distance_)
1425  distance1 = 1000000.0;
1426  if(distance2 <= tiny_bubble_distance_)
1427  distance2 = 1000000.0;
1428 
1429  // now calculate wrench - forces model an elastic band and are normed (distance) to render forces for small and large bubbles the same
1430  wrench.force.x = internal_force_gain_*(difference1.linear.x/distance1 + difference2.linear.x/distance2);
1431  wrench.force.y = internal_force_gain_*(difference1.linear.y/distance1 + difference2.linear.y/distance2);
1432  wrench.force.z = internal_force_gain_*(difference1.linear.z/distance1 + difference2.linear.z/distance2);
1433  wrench.torque.x = internal_force_gain_*(difference1.angular.x/distance1 + difference2.angular.x/distance2);
1434  wrench.torque.y = internal_force_gain_*(difference1.angular.y/distance1 + difference2.angular.y/distance2);
1435  wrench.torque.z = internal_force_gain_*(difference1.angular.z/distance1 + difference2.angular.z/distance2);
1436 
1437 #ifdef DEBUG_EBAND_
1438  ROS_DEBUG("Calculating internal forces: (x, y, theta) = (%f, %f, %f)", wrench.force.x, wrench.force.y, wrench.torque.z);
1439 #endif
1440 
1441  // store wrench in vector
1442  forces.wrench = wrench;
1443 
1444  return true;
1445  }
1446 
1447 
1448  bool EBandPlanner::calcExternalForces(int bubble_num, Bubble curr_bubble, geometry_msgs::WrenchStamped& forces)
1449  {
1450  // check if plugin initialized
1451  if(!initialized_)
1452  {
1453  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
1454  return false;
1455  }
1456 
1457  // init tmp variables
1458  double distance1, distance2;
1459  geometry_msgs::Pose edge;
1460  geometry_msgs::Pose2D edge_pose2D;
1461  geometry_msgs::Wrench wrench;
1462 
1463 
1464  // calculate delta-poses (on upper edge of bubble) for x-direction
1465  edge = curr_bubble.center.pose;
1466  edge.position.x = edge.position.x + curr_bubble.expansion;
1467  // get expansion on bubble at this point
1468  if(!calcObstacleKinematicDistance(edge, distance1))
1469  {
1470  ROS_DEBUG("Bubble %d probably at edge of map - cannot retrieve distance information to calculate external forces", bubble_num);
1471  // we cannot calculate external forces for this bubble - but still continue for the other bubbles
1472  return true;
1473  }
1474  // calculate delta-poses (on lower edge of bubble) for x-direction
1475  edge.position.x = edge.position.x - 2.0*curr_bubble.expansion;
1476  // get expansion on bubble at this point
1477  if(!calcObstacleKinematicDistance(edge, distance2))
1478  {
1479  ROS_DEBUG("Bubble %d probably at edge of map - cannot retrieve distance information to calculate external forces", bubble_num);
1480  // we cannot calculate external forces for this bubble - but still continue for the other bubbles
1481  return true;
1482  }
1483 
1484  // calculate difference-quotient (approx. of derivative) in x-direction
1485  if(curr_bubble.expansion <= tiny_bubble_expansion_)
1486  {
1487  // avoid division by (almost) zero to avoid numerical problems
1488  wrench.force.x = -external_force_gain_*(distance2 - distance1)/(2.0*tiny_bubble_expansion_);
1489  // actually we should never end up here - band should have been considered as broken
1490  ROS_DEBUG("Calculating external forces on broken band. Bubble should have been removed. Local Planner probably ill configured");
1491  }
1492  else
1493  wrench.force.x = -external_force_gain_*(distance2 - distance1)/(2.0*curr_bubble.expansion);
1494  // TODO above equations skip term to make forces continuous at end of influence region - test to add corresponding term
1495 
1496 
1497  // calculate delta-poses (on upper edge of bubble) for y-direction
1498  edge = curr_bubble.center.pose;
1499  edge.position.y = edge.position.y + curr_bubble.expansion;
1500  // get expansion on bubble at this point
1501  if(!calcObstacleKinematicDistance(edge, distance1))
1502  {
1503  ROS_DEBUG("Bubble %d probably at edge of map - cannot retrieve distance information to calculate external forces", bubble_num);
1504  // we cannot calculate external forces for this bubble - but still continue for the other bubbles
1505  return true;
1506  }
1507  // calculate delta-poses (on lower edge of bubble) for x-direction
1508  edge.position.y = edge.position.y - 2.0*curr_bubble.expansion;
1509  // get expansion on bubble at this point
1510  if(!calcObstacleKinematicDistance(edge, distance2))
1511  {
1512  ROS_DEBUG("Bubble %d probably at edge of map - cannot retrieve distance information to calculate external forces", bubble_num);
1513  // we cannot calculate external forces for this bubble - but still continue for the other bubbles
1514  return true;
1515  }
1516 
1517  // calculate difference-quotient (approx. of derivative) in x-direction
1518  if(curr_bubble.expansion <= tiny_bubble_expansion_)
1519  {
1520  // avoid division by (almost) zero to avoid numerical problems
1521  wrench.force.y = -external_force_gain_*(distance2 - distance1)/(2.0*tiny_bubble_expansion_);
1522  // actually we should never end up here - band should have been considered as broken
1523  ROS_DEBUG("Calculating external forces on broken band. Bubble should have been removed. Local Planner probably ill configured");
1524  }
1525  else
1526  wrench.force.y = -external_force_gain_*(distance2 - distance1)/(2.0*curr_bubble.expansion);
1527  // TODO above equations skip term to make forces continuous at end of influence region - test to add corresponsing term
1528 
1529 
1530  // no force in z-direction
1531  wrench.force.z = 0.0;
1532 
1533 
1534  // no torque around x and y axis
1535  wrench.torque.x = 0.0;
1536  wrench.torque.y = 0.0;
1537 
1538 
1539  // calculate delta-poses (on upper edge of bubble) for x-direction
1540  PoseToPose2D(curr_bubble.center.pose, edge_pose2D);
1541  edge_pose2D.theta = edge_pose2D.theta + (curr_bubble.expansion/getCircumscribedRadius(*costmap_ros_));
1542  edge_pose2D.theta = angles::normalize_angle(edge_pose2D.theta);
1543  PoseToPose2D(edge, edge_pose2D);
1544  // get expansion on bubble at this point
1545  if(!calcObstacleKinematicDistance(edge, distance1))
1546  {
1547  ROS_DEBUG("Bubble %d probably at edge of map - cannot retrieve distance information to calculate external forces", bubble_num);
1548  // we cannot calculate external forces for this bubble - but still continue for the other bubbles
1549  return true;
1550  }
1551  // calculate delta-poses (on lower edge of bubble) for x-direction
1552  edge_pose2D.theta = edge_pose2D.theta - 2.0*(curr_bubble.expansion/getCircumscribedRadius(*costmap_ros_));
1553  edge_pose2D.theta = angles::normalize_angle(edge_pose2D.theta);
1554  PoseToPose2D(edge, edge_pose2D);
1555  // get expansion on bubble at this point
1556  if(!calcObstacleKinematicDistance(edge, distance2))
1557  {
1558  ROS_DEBUG("Bubble %d probably at edge of map - cannot retrieve distance information to calculate external forces", bubble_num);
1559  // we cannot calculate external forces for this bubble - but still continue for the other bubbles
1560  return true;
1561  }
1562 
1563  // calculate difference-quotient (approx. of derivative) in x-direction
1564  if(curr_bubble.expansion <= tiny_bubble_expansion_)
1565  {
1566  // avoid division by (almost) zero to avoid numerical problems
1567  wrench.torque.z = -external_force_gain_*(distance2 - distance1)/(2.0*tiny_bubble_expansion_);
1568  // actually we should never end up here - band should have been considered as broken
1569  ROS_DEBUG("Calculating external forces on broken band. Bubble should have been removed. Local Planner probably ill configured");
1570  }
1571  else
1572  wrench.torque.z = -external_force_gain_*(distance2 - distance1)/(2.0*curr_bubble.expansion);
1573  // TODO above equations skip term to make forces continuous at end of influence region - test to add corresponsing term
1574 
1575 
1576 #ifdef DEBUG_EBAND_
1577  ROS_DEBUG("Calculating external forces: (x, y, theta) = (%f, %f, %f)", wrench.force.x, wrench.force.y, wrench.torque.z);
1578 #endif
1579 
1580  // assign wrench to forces vector
1581  forces.wrench = wrench;
1582 
1583  return true;
1584  }
1585 
1586 
1587  bool EBandPlanner::suppressTangentialForces(int bubble_num, std::vector<Bubble> band, geometry_msgs::WrenchStamped& forces)
1588  {
1589  //cycle over all bubbles except first and last (these are fixed)
1590  if(band.size() <= 2)
1591  {
1592  // nothing to do here -> we can stop right away - no forces calculated
1593  return true;
1594  }
1595 
1596  double scalar_fd, scalar_dd;
1597  geometry_msgs::Twist difference;
1598 
1599  // make sure this method was called for a valid element in the forces or bubbles vector
1600  ROS_ASSERT( bubble_num > 0 );
1601  ROS_ASSERT( bubble_num < ((int) band.size() - 1) );
1602 
1603 
1604  // get pose-difference from following to preceding bubble -> "direction of the band in this bubble"
1605  if(!calcBubbleDifference(band[bubble_num+1].center.pose, band[bubble_num-1].center.pose, difference))
1606  return false;
1607 
1608  // "project wrench" in middle bubble onto connecting vector
1609  // scalar wrench*difference
1610  scalar_fd = forces.wrench.force.x*difference.linear.x + forces.wrench.force.y*difference.linear.y +
1611  forces.wrench.force.z*difference.linear.z + forces.wrench.torque.x*difference.angular.x +
1612  forces.wrench.torque.y*difference.angular.y + forces.wrench.torque.z*difference.angular.z;
1613 
1614  // abs of difference-vector: scalar difference*difference
1615  scalar_dd = difference.linear.x*difference.linear.x + difference.linear.y*difference.linear.y + difference.linear.z*difference.linear.z +
1616  difference.angular.x*difference.angular.x + difference.angular.y*difference.angular.y + difference.angular.z*difference.angular.z;
1617 
1618  // avoid division by (almost) zero -> check if bubbles have (almost) same center-pose
1619  if(scalar_dd <= tiny_bubble_distance_)
1620  {
1621  // there are redundant bubbles, this should normally not hapen -> probably error in band refinement
1622  ROS_DEBUG("Calculating tangential forces for redundant bubbles. Bubble should have been removed. Local Planner probably ill configured");
1623  }
1624 
1625  // calculate orthogonal components
1626  forces.wrench.force.x = forces.wrench.force.x - scalar_fd/scalar_dd * difference.linear.x;
1627  forces.wrench.force.y = forces.wrench.force.y - scalar_fd/scalar_dd * difference.linear.y;
1628  forces.wrench.force.z = forces.wrench.force.z - scalar_fd/scalar_dd * difference.linear.z;
1629  forces.wrench.torque.x = forces.wrench.torque.x - scalar_fd/scalar_dd * difference.angular.x;
1630  forces.wrench.torque.y = forces.wrench.torque.y - scalar_fd/scalar_dd * difference.angular.y;
1631  forces.wrench.torque.z = forces.wrench.torque.z - scalar_fd/scalar_dd * difference.angular.z;
1632 
1633 #ifdef DEBUG_EBAND_
1634  ROS_DEBUG("Supressing tangential forces: (x, y, theta) = (%f, %f, %f)",
1635  forces.wrench.force.x, forces.wrench.force.y, forces.wrench.torque.z);
1636 #endif
1637 
1638  return true;
1639  }
1640 
1641 
1642  // problem (geometry) dependant functions
1643 
1644  bool EBandPlanner::interpolateBubbles(geometry_msgs::PoseStamped start_center, geometry_msgs::PoseStamped end_center, geometry_msgs::PoseStamped& interpolated_center)
1645  {
1646  // check if plugin initialized
1647  if(!initialized_)
1648  {
1649  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
1650  return false;
1651  }
1652 
1653  // instantiate local variables
1654  geometry_msgs::Pose2D start_pose2D, end_pose2D, interpolated_pose2D;
1655  double delta_theta;
1656 
1657  // copy header
1658  interpolated_center.header = start_center.header;
1659 
1660  // interpolate angles
1661  // TODO make this in a better way
1662  // - for instance use "slerp" to interpolate directly between quaternions
1663  // - or work with pose2D right from the beginnning
1664  // convert quaternions to euler angles - at this point this no longer works in 3D !!
1665  PoseToPose2D(start_center.pose, start_pose2D);
1666  PoseToPose2D(end_center.pose, end_pose2D);
1667  // calc mean of theta angle
1668  delta_theta = end_pose2D.theta - start_pose2D.theta;
1669  delta_theta = angles::normalize_angle(delta_theta) / 2.0;
1670  interpolated_pose2D.theta = start_pose2D.theta + delta_theta;
1671  interpolated_pose2D.theta = angles::normalize_angle(interpolated_pose2D.theta);
1672  // convert back to quaternion
1673  interpolated_pose2D.x = 0.0;
1674  interpolated_pose2D.y = 0.0;
1675  Pose2DToPose(interpolated_center.pose, interpolated_pose2D);
1676 
1677  // interpolate positions
1678  interpolated_center.pose.position.x = (end_center.pose.position.x + start_center.pose.position.x)/2.0;
1679  interpolated_center.pose.position.y = (end_center.pose.position.y + start_center.pose.position.y)/2.0;
1680  interpolated_center.pose.position.z = (end_center.pose.position.z + start_center.pose.position.z)/2.0;
1681 
1682  // TODO ideally this would take into account kinematics of the robot and for instance use splines
1683 
1684  return true;
1685  }
1686 
1687 
1689  {
1690  // check if plugin initialized
1691  if(!initialized_)
1692  {
1693  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
1694  return false;
1695  }
1696 
1697  // calc (kinematic) Distance between bubbles
1698  double distance = 0.0;
1699  if(!calcBubbleDistance(bubble1.center.pose, bubble2.center.pose, distance))
1700  {
1701  ROS_ERROR("failed to calculate Distance between two bubbles. Aborting check for overlap!");
1702  return false;
1703  }
1704 
1705  // compare with size of the two bubbles
1706  if(distance >= min_bubble_overlap_ * (bubble1.expansion + bubble2.expansion))
1707  return false;
1708 
1709  // TODO this does not account for kinematic properties -> improve
1710 
1711  // everything fine - bubbles overlap
1712  return true;
1713  }
1714 
1715 
1716  bool EBandPlanner::calcBubbleDistance(geometry_msgs::Pose start_center_pose, geometry_msgs::Pose end_center_pose, double& distance)
1717  {
1718  // check if plugin initialized
1719  if(!initialized_)
1720  {
1721  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
1722  return false;
1723  }
1724 
1725  geometry_msgs::Pose2D start_pose2D, end_pose2D, diff_pose2D;
1726 
1727  // TODO make this in a better way
1728  // - or work with pose2D right from the beginnning
1729  // convert quaternions to euler angles - at this point this no longer works in 3D !!
1730  PoseToPose2D(start_center_pose, start_pose2D);
1731  PoseToPose2D(end_center_pose, end_pose2D);
1732 
1733  // get rotational difference
1734  diff_pose2D.theta = end_pose2D.theta - start_pose2D.theta;
1735  diff_pose2D.theta = angles::normalize_angle(diff_pose2D.theta);
1736  // get translational difference
1737  diff_pose2D.x = end_pose2D.x - start_pose2D.x;
1738  diff_pose2D.y = end_pose2D.y - start_pose2D.y;
1739 
1740  // calc distance
1741  double angle_to_pseudo_vel = diff_pose2D.theta * getCircumscribedRadius(*costmap_ros_);
1742  //distance = sqrt( (diff_pose2D.x * diff_pose2D.x) + (diff_pose2D.y * diff_pose2D.y) + (angle_to_pseudo_vel * angle_to_pseudo_vel) );
1743  distance = sqrt( (diff_pose2D.x * diff_pose2D.x) + (diff_pose2D.y * diff_pose2D.y));
1744 
1745  // TODO take into account kinematic properties of body
1746 
1747  return true;
1748  }
1749 
1750 
1751  bool EBandPlanner::calcBubbleDifference(geometry_msgs::Pose start_center_pose, geometry_msgs::Pose end_center_pose, geometry_msgs::Twist& difference)
1752  {
1753  // check if plugin initialized
1754  if(!initialized_)
1755  {
1756  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
1757  return false;
1758  }
1759 
1760  geometry_msgs::Pose2D start_pose2D, end_pose2D, diff_pose2D;
1761 
1762  // TODO make this in a better way
1763  // - or work with pose2D right from the beginnning
1764  // convert quaternions to euler angles - at this point this no longer works in 3D !!
1765  PoseToPose2D(start_center_pose, start_pose2D);
1766  PoseToPose2D(end_center_pose, end_pose2D);
1767 
1768  // get rotational difference
1769  diff_pose2D.theta = end_pose2D.theta - start_pose2D.theta;
1770  diff_pose2D.theta = angles::normalize_angle(diff_pose2D.theta);
1771  // get translational difference
1772  diff_pose2D.x = end_pose2D.x - start_pose2D.x;
1773  diff_pose2D.y = end_pose2D.y - start_pose2D.y;
1774 
1775  difference.linear.x = diff_pose2D.x;
1776  difference.linear.y = diff_pose2D.y;
1777  difference.linear.z = 0.0;
1778  // multiply by inscribed radius to math calculation of distance
1779  difference.angular.x = 0.0;
1780  difference.angular.y = 0.0;
1781  difference.angular.z = diff_pose2D.theta*getCircumscribedRadius(*costmap_ros_);
1782 
1783  // TODO take into account kinematic properties of body
1784 
1785  return true;
1786  }
1787 
1788 
1789  bool EBandPlanner::calcObstacleKinematicDistance(geometry_msgs::Pose center_pose, double& distance)
1790  {
1791  // calculate distance to nearest obstacle [depends kinematic, shape, environment]
1792 
1793  // check if plugin initialized
1794  if(!initialized_)
1795  {
1796  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
1797  return false;
1798  }
1799 
1800  unsigned int cell_x, cell_y;
1801  unsigned char disc_cost;
1802  double weight = costmap_weight_;
1803 
1804  // read distance to nearest obstacle directly from costmap
1805  // (does not take into account shape and kinematic properties)
1806  // get cell for coordinates of bubble center
1807  if(!costmap_->worldToMap(center_pose.position.x, center_pose.position.y, cell_x, cell_y)) {
1808  // probably at the edge of the costmap - this value should be recovered soon
1809  disc_cost = 1;
1810  } else {
1811  // get cost for this cell
1812  disc_cost = costmap_->getCost(cell_x, cell_y);
1813  }
1814 
1815  // calculate distance to nearest obstacel from this cost (see costmap_2d in wiki for details)
1816 
1817  // For reference: here comes an excerpt of the cost calculation within the costmap function
1818  /*if(distance == 0)
1819  cost = LETHAL_OBSTACLE;
1820  else if(distance <= cell_inscribed_radius_)
1821  cost = INSCRIBED_INFLATED_OBSTACLE;
1822  else {
1823  //make sure cost falls off by Euclidean distance
1824  double euclidean_distance = distance * resolution_;
1825  double factor = exp(-1.0 * weight_ * (euclidean_distance - inscribed_radius_));
1826  cost = (unsigned char) ((INSCRIBED_INFLATED_OBSTACLE - 1) * factor);
1827  }*/
1828 
1829  if (disc_cost == costmap_2d::LETHAL_OBSTACLE) {
1830  // pose is inside an obstacle - very bad
1831  distance = 0.0;
1832  } else if (disc_cost == costmap_2d::INSCRIBED_INFLATED_OBSTACLE) {
1833  // footprint is definitely inside an obstacle - still bad
1834  distance = 0.0;
1835  } else {
1836  if (disc_cost == 0) { // freespace, no estimate of distance
1837  disc_cost = 1; // lowest non freespace cost
1838  } else if (disc_cost == 255) { // unknown space, we should never be here
1839  disc_cost = 1;
1840  }
1841  double factor = ((double) disc_cost) / (costmap_2d::INSCRIBED_INFLATED_OBSTACLE - 1);
1842  distance = -log(factor) / weight;
1843  }
1844 
1845  return true;
1846  }
1847 
1848 
1849  // type conversions
1850 
1851  bool EBandPlanner::convertPlanToBand(std::vector<geometry_msgs::PoseStamped> plan, std::vector<Bubble>& band)
1852  {
1853  // check if plugin initialized
1854  if(!initialized_)
1855  {
1856  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
1857  return false;
1858  }
1859 
1860  // create local variables
1861  double distance = 0.0;
1862  std::vector<Bubble> tmp_band;
1863 
1864  ROS_DEBUG("Copying plan to band - Conversion started: %d frames to convert.", ((int) plan.size()) );
1865 
1866  // get local copy of referenced variable
1867  tmp_band = band;
1868 
1869  // adapt band to plan
1870  tmp_band.resize(plan.size());
1871  for(int i = 0; i < ((int) plan.size()); i++)
1872  {
1873 #ifdef DEBUG_EBAND_
1874  ROS_DEBUG("Checking Frame %d of %d", i, ((int) plan.size()) );
1875 #endif
1876 
1877  // set poses in plan as centers of bubbles
1878  tmp_band[i].center = plan[i];
1879 
1880  // calc Size of Bubbles by calculating Dist to nearest Obstacle [depends kinematic, environment]
1881  if(!calcObstacleKinematicDistance(tmp_band[i].center.pose, distance))
1882  {
1883  // frame must not be immediately in collision -> otherwise calculation of gradient will later be invalid
1884  ROS_WARN("Calculation of Distance between bubble and nearest obstacle failed. Frame %d of %d outside map", i, ((int) plan.size()) );
1885  return false;
1886  }
1887 
1888  if(distance <= 0.0)
1889  {
1890  // frame must not be immediately in collision -> otherwise calculation of gradient will later be invalid
1891  ROS_WARN("Calculation of Distance between bubble and nearest obstacle failed. Frame %d of %d in collision. Plan invalid", i, ((int) plan.size()) );
1892  // TODO if frame in collision try to repair band instaed of aborting averything
1893  return false;
1894  }
1895 
1896 
1897  // assign to expansion of bubble
1898  tmp_band[i].expansion = distance;
1899  }
1900 
1901  // write to referenced variable
1902  band = tmp_band;
1903 
1904  ROS_DEBUG("Successfully converted plan to band");
1905  return true;
1906  }
1907 
1908 
1909  bool EBandPlanner::convertBandToPlan(std::vector<geometry_msgs::PoseStamped>& plan, std::vector<Bubble> band)
1910  {
1911  // check if plugin initialized
1912  if(!initialized_)
1913  {
1914  ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
1915  return false;
1916  }
1917 
1918  // create local variables
1919  std::vector<geometry_msgs::PoseStamped> tmp_plan;
1920 
1921  // adapt plan to band
1922  tmp_plan.resize(band.size());
1923  for(int i = 0; i < ((int) band.size()); i++)
1924  {
1925  // set centers of bubbles to StampedPose in plan
1926  tmp_plan[i] = band[i].center;
1927  }
1928 
1929  //write to referenced variable and done
1930  plan = tmp_plan;
1931 
1932  return true;
1933  }
1934 
1935 
1936 }
std::vector< geometry_msgs::PoseStamped > global_plan_
double internal_force_gain_
gain for internal forces ("Elasticity of Band")
bool convertBandToPlan(std::vector< geometry_msgs::PoseStamped > &plan, std::vector< Bubble > band)
This converts a band from a sequence of bubbles into a plan from, a sequence of stamped poses...
bool interpolateBubbles(geometry_msgs::PoseStamped start_center, geometry_msgs::PoseStamped end_center, geometry_msgs::PoseStamped &interpolated_center)
interpolates between two bubbles by calculating the pose for the center of a bubble in the middle of ...
double equilibrium_relative_overshoot_
maximum depth for recursive approximation to constrain computational burden
bool getPlan(std::vector< geometry_msgs::PoseStamped > &global_plan)
This transforms the refined band to a path again and outputs it.
INLINE Rall1d< T, V, S > log(const Rall1d< T, V, S > &arg)
double external_force_gain_
gain for external forces ("Penalty on low distance to abstacles")
bool sleep() const
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &global_plan)
Set plan which shall be optimized to elastic band planner.
std::string getGlobalFrameID()
int num_optim_iterations_
maximal number of iteration steps during optimization of band
void setVisualization(boost::shared_ptr< EBandVisualization > eband_visual)
passes a reference to the eband visualization object which can be used to visualize the band optimiza...
bool calcBubbleDistance(geometry_msgs::Pose start_center_pose, geometry_msgs::Pose end_center_pose, double &distance)
This calculates the distance between two bubbles [depends kinematics, shape].
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...
double significant_force_
percentage of old force for which a new force is considered significant when higher as this value ...
bool getBand(std::vector< Bubble > &elastic_band)
This outputs the elastic_band.
bool suppressTangentialForces(int bubble_num, std::vector< Bubble > band, geometry_msgs::WrenchStamped &forces)
Calculates tangential portion of forces.
#define ROS_WARN(...)
void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)
Initializes the elastic band class by accesing costmap and loading parameters.
bool calcBubbleDifference(geometry_msgs::Pose start_center_pose, geometry_msgs::Pose end_center_pose, geometry_msgs::Twist &difference)
Calculates the difference between the pose of the center of two bubbles and outputs it as Twist (poin...
std::vector< geometry_msgs::Point > footprint_spec_
bool convertPlanToBand(std::vector< geometry_msgs::PoseStamped > plan, std::vector< Bubble > &band)
This converts a plan from a sequence of stamped poses into a band, a sequence of bubbles. Therefore it calculates distances to the surrounding obstacles and derives the expansion or radius of the bubble.
unsigned char getCost(unsigned int mx, unsigned int my) const
bool calcInternalForces(int bubble_num, std::vector< Bubble > band, Bubble curr_bubble, geometry_msgs::WrenchStamped &forces)
Calculates internal forces for bubbles along the band [depends kinematic].
bool moveApproximateEquilibrium(const int &bubble_num, const std::vector< Bubble > &band, Bubble &curr_bubble, const geometry_msgs::WrenchStamped &curr_bubble_force, geometry_msgs::Twist &curr_step_width, const int &curr_recursion_depth)
Checks for zero-crossings and large changes in force-vector after moving of bubble - if detected it t...
double distance(double x0, double y0, double x1, double y1)
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
double getCircumscribedRadius(costmap_2d::Costmap2DROS &costmap)
Gets the footprint of the robot and computes the circumscribed radius for the eband approach...
bool addFrames(const std::vector< geometry_msgs::PoseStamped > &robot_pose, const AddAtPosition &add_frames_at)
converts robot_pose to a bubble and tries to connect to the path
bool removeAndFill(std::vector< Bubble > &band, std::vector< Bubble >::iterator &start_iter, std::vector< Bubble >::iterator &end_iter)
recursively checks an intervall of a band whether gaps need to be filled or bubbles may be removed an...
double min_bubble_overlap_
minimum relative overlap two bubbles must have to be treated as connected
bool applyForces(int bubble_num, std::vector< Bubble > &band, std::vector< geometry_msgs::WrenchStamped > forces)
Applies forces to move bubbles and recalculates expansion of bubbles.
bool optimizeBand()
cycles over the elastic band set before and optimizes it locally by minimizing an energy-function ...
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
def normalize_angle(angle)
bool calcExternalForces(int bubble_num, Bubble curr_bubble, geometry_msgs::WrenchStamped &forces)
Calculates external forces for bubbles along the band [depends shape, environment].
double costmap_weight_
lower bound for absolute value of force below which it is treated as insignificant (no recursive appr...
double tiny_bubble_expansion_
lower bound for bubble expansion. below this bound bubble is considered as "in collision" ...
static const unsigned char LETHAL_OBSTACLE
bool refineBand(std::vector< Bubble > &band)
Cycles over an band and searches for gaps and redundant bubbles. Tries to close gaps and remove redun...
TFSIMD_FORCE_INLINE tfScalar distance2(const Vector3 &v) const
static Time now()
void reconfigure(EBandPlannerConfig &config)
Reconfigures the parameters of the planner.
geometry_msgs::PoseStamped center
Costmap2D * getCostmap()
bool getForcesAt(int bubble_num, std::vector< Bubble > band, Bubble curr_bubble, geometry_msgs::WrenchStamped &forces)
Calculates all forces for a certain bubble at a specific position in the band [depends kinematic]...
#define ROS_ASSERT(cond)
std::vector< geometry_msgs::Point > getRobotFootprint()
costmap_2d::Costmap2DROS * costmap_ros_
pointer to costmap
double tiny_bubble_distance_
internal forces between two bubbles are only calc. if there distance is bigger than this lower bound ...
bool fillGap(std::vector< Bubble > &band, std::vector< Bubble >::iterator &start_iter, std::vector< Bubble >::iterator &end_iter)
recursively fills gaps between two bubbles (if possible)
#define ROS_ERROR(...)
bool modifyBandArtificialForce(std::vector< Bubble > &band)
calculates internal and external forces and applies changes to the band
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
boost::shared_ptr< EBandVisualization > eband_visual_
base_local_planner::CostmapModel * world_model_
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...
bool checkOverlap(Bubble bubble1, Bubble bubble2)
this checks whether two bubbles overlap
#define ROS_DEBUG(...)
bool calcObstacleKinematicDistance(geometry_msgs::Pose center_pose, double &distance)
Calculates the distance between the center of a bubble and the closest obstacle [depends kinematics...


eband_local_planner
Author(s): Christian Connette, Bhaskara Marthi, Piyush Khandelwal
autogenerated on Sat Feb 22 2020 04:03:28