eband_local_planner.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2010, Willow Garage, Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of Willow Garage, Inc. nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  * Author: Christian Connette
00036  *********************************************************************/
00037 
00038 #include <eband_local_planner/eband_local_planner.h>
00039 
00040 
00041 namespace eband_local_planner{
00042 
00043 
00044   EBandPlanner::EBandPlanner() : costmap_ros_(NULL), initialized_(false) {}
00045 
00046 
00047   EBandPlanner::EBandPlanner(std::string name, costmap_2d::Costmap2DROS* costmap_ros)
00048     : costmap_ros_(NULL), initialized_(false)
00049   {
00050     // initialize planner
00051     initialize(name, costmap_ros);
00052   }
00053 
00054 
00055   EBandPlanner::~EBandPlanner()
00056   {
00057     delete world_model_;
00058   }
00059 
00060 
00061   void EBandPlanner::initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros)
00062   {
00063     // check if the plugin is already initialized
00064     if(!initialized_)
00065     {
00066       // copy adress of costmap (handed over from move_base via eband wrapper)
00067       costmap_ros_ = costmap_ros;
00068 
00069       // get a pointer to the underlying costmap
00070       costmap_ = costmap_ros_->getCostmap();
00071 
00072       // create world model from costmap
00073       world_model_ = new base_local_planner::CostmapModel(*costmap_);
00074 
00075       // get footprint of the robot
00076       footprint_spec_ = costmap_ros_->getRobotFootprint();
00077 
00078       // create Node Handle with name of plugin (as used in move_base for loading)
00079       ros::NodeHandle pn("~/" + name);
00080 
00081       // clean up band
00082       elastic_band_.clear();
00083 
00084       // set initialized flag
00085       initialized_ = true;
00086 
00087       // set flag whether visualization availlable to false by default
00088       visualization_ = false;
00089     }
00090     else
00091     {
00092       ROS_WARN("This planner has already been initialized, doing nothing.");
00093     }
00094   }
00095 
00096   void EBandPlanner::reconfigure(
00097     eband_local_planner::EBandPlannerConfig& config)
00098   {
00099     // connectivity checking
00100     min_bubble_overlap_ = config.eband_min_relative_overlap;
00101 
00102     // bubble geometric bounds
00103     tiny_bubble_distance_ = config.eband_tiny_bubble_distance;
00104     tiny_bubble_expansion_ = config.eband_tiny_bubble_expansion;
00105 
00106     // optimization - force calculation
00107     internal_force_gain_ = config.eband_internal_force_gain;
00108     external_force_gain_ = config.eband_external_force_gain;
00109     num_optim_iterations_ = config.num_iterations_eband_optimization;
00110 
00111     // recursive approximation of bubble equilibrium position based
00112     max_recursion_depth_approx_equi_ = config.eband_equilibrium_approx_max_recursion_depth;
00113     equilibrium_relative_overshoot_ = config.eband_equilibrium_relative_overshoot;
00114     significant_force_ = config.eband_significant_force_lower_bound;
00115 
00116     // use this parameter if a different weight is supplied to the costmap in dyn reconfigure
00117     costmap_weight_ = config.costmap_weight;
00118   }
00119 
00120   void EBandPlanner::setVisualization(boost::shared_ptr<EBandVisualization> eband_visual)
00121   {
00122     eband_visual_ = eband_visual;
00123 
00124     visualization_ = true;
00125   }
00126 
00127 
00128   bool EBandPlanner::setPlan(const std::vector<geometry_msgs::PoseStamped>& global_plan)
00129   {
00130     // check if plugin initialized
00131     if(!initialized_)
00132     {
00133       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00134       return false;
00135     }
00136 
00137 
00138     // check if plan valid (minimum 2 frames)
00139     if(global_plan.size() < 2)
00140     {
00141       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()) );
00142       return false;
00143     }
00144     // copy plan to local member variable
00145     global_plan_ = global_plan;
00146 
00147 
00148     // check whether plan and costmap are in the same frame
00149     if(global_plan.front().header.frame_id != costmap_ros_->getGlobalFrameID())
00150     {
00151       ROS_ERROR("Elastic Band expects plan for optimization in the %s frame, the plan was sent in the %s frame.",
00152           costmap_ros_->getGlobalFrameID().c_str(), global_plan.front().header.frame_id.c_str());
00153       return false;
00154     }
00155 
00156 
00157     // convert frames in path into bubbles in band -> sets center of bubbles and calculates expansion
00158     ROS_DEBUG("Converting Plan to Band");
00159     if(!convertPlanToBand(global_plan_, elastic_band_))
00160     {
00161       ROS_WARN("Conversion from plan to elastic band failed. Plan probably not collision free. Plan not set for optimization");
00162       // TODO try to do local repairs of band
00163       return false;
00164     }
00165 
00166 
00167     // close gaps and remove redundant bubbles
00168     ROS_DEBUG("Refining Band");
00169     if(!refineBand(elastic_band_))
00170     {
00171       ROS_WARN("Band is broken. Could not close gaps in converted path. Path not set. Global replanning needed");
00172       return false;
00173     }
00174 
00175 
00176     ROS_DEBUG("Refinement done - Band set.");
00177     return true;
00178   }
00179 
00180 
00181   bool EBandPlanner::getPlan(std::vector<geometry_msgs::PoseStamped>& global_plan)
00182   {
00183     // check if plugin initialized
00184     if(!initialized_)
00185     {
00186       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00187       return false;
00188     }
00189 
00190     // check if there is a band
00191     if(elastic_band_.empty())
00192     {
00193       ROS_WARN("Band is empty. There was no path successfully set so far.");
00194       return false;
00195     }
00196 
00197     // convert band to plan
00198     if(!convertBandToPlan(global_plan, elastic_band_))
00199     {
00200       ROS_WARN("Conversion from Elastic Band to path failed.");
00201       return false;
00202     }
00203 
00204     return true;
00205   }
00206 
00207 
00208   bool EBandPlanner::getBand(std::vector<Bubble>& elastic_band)
00209   {
00210     // check if plugin initialized
00211     if(!initialized_)
00212     {
00213       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00214       return false;
00215     }
00216 
00217     elastic_band = elastic_band_;
00218 
00219     // check if there is a band
00220     if(elastic_band_.empty())
00221     {
00222       ROS_WARN("Band is empty.");
00223       return false;
00224     }
00225 
00226     return true;
00227   }
00228 
00229 
00230   bool EBandPlanner::addFrames(const std::vector<geometry_msgs::PoseStamped>& plan_to_add, const AddAtPosition& add_frames_at)
00231   {
00232     // check if plugin initialized
00233     if(!initialized_)
00234     {
00235       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00236       return false;
00237     }
00238 
00239     // check that there is a plan at all (minimum 1 frame in this case, as robot + goal = plan)
00240     if(elastic_band_.size() < 1)
00241     {
00242       ROS_WARN("Attempt to connect path to empty band. path not connected. Use SetPath instead");
00243       return false;
00244     }
00245 
00246     //check that plan which shall be added is not empty
00247     if(plan_to_add.empty())
00248     {
00249       ROS_WARN("Attempt to connect empty path to band. Nothing to do here.");
00250       return false;
00251     }
00252 
00253     // check whether plan and costmap are in the same frame
00254     if(plan_to_add.at(0).header.frame_id != costmap_ros_->getGlobalFrameID())
00255     {
00256       ROS_ERROR("Elastic Band expects robot pose for optimization in the %s frame, the pose was sent in the %s frame.",
00257           costmap_ros_->getGlobalFrameID().c_str(), plan_to_add.at(0).header.frame_id.c_str());
00258       return false;
00259     }
00260 
00261 
00262     // convert plan to band
00263     std::vector<Bubble> band_to_add;
00264     if(!convertPlanToBand(plan_to_add, band_to_add))
00265     {
00266       ROS_DEBUG("Conversion from plan to elastic band failed. Plan not appended");
00267       // TODO try to do local repairs of band
00268       return false;
00269     }
00270 
00271 
00272     // connect frames to existing band
00273     ROS_DEBUG("Checking for connections between current band and new bubbles");
00274     bool connected = false;
00275     int bubble_connect = -1;
00276     if(add_frames_at == add_front)
00277     {
00278       // add frames at the front of the current band
00279       // - for instance to connect band and current robot position
00280       for(int i = ((int) elastic_band_.size() - 1); i >= 0; i--)
00281       {
00282         // cycle over bubbles from End - connect to bubble furthest away but overlapping
00283         if(checkOverlap(band_to_add.back(), elastic_band_.at(i)))
00284         {
00285           bubble_connect = i;
00286           connected = true;
00287           break;
00288         }
00289       }
00290     }
00291     else
00292     {
00293       // add frames at the end of the current band
00294       // - for instance to connect new frames entering the moving window
00295       for(int i = 0; i < ((int) elastic_band_.size() - 1); i++)
00296       {
00297         // cycle over bubbles from Start - connect to bubble furthest away but overlapping
00298         if(checkOverlap(band_to_add.front(), elastic_band_.at(i)))
00299         {
00300           bubble_connect = i;
00301           connected = true;
00302           break;
00303         }
00304       }
00305     }
00306 
00307     // intanstiate local copy of band
00308     std::vector<Bubble> tmp_band;
00309     std::vector<Bubble>::iterator tmp_iter1, tmp_iter2;
00310     // copy new frames to tmp_band
00311     tmp_band.assign(band_to_add.begin(), band_to_add.end());
00312 
00313     if(connected)
00314     {
00315       ROS_DEBUG("Connections found - composing new band by connecting new frames to bubble %d", bubble_connect);
00316       if(add_frames_at == add_front)
00317       {
00318         // compose new vector by appending elastic_band to new frames
00319         tmp_iter1 = elastic_band_.begin() + bubble_connect;
00320         ROS_ASSERT( (tmp_iter1 >= elastic_band_.begin()) && (tmp_iter1 < elastic_band_.end()) );
00321         tmp_band.insert(tmp_band.end(), tmp_iter1, elastic_band_.end());
00322       }
00323       else
00324       {
00325         // compose new vector by pre-appending elastic_band to new frames
00326         tmp_iter1 = elastic_band_.begin() + bubble_connect + 1; // +1 - as insert only appends [start, end)
00327         ROS_ASSERT( (tmp_iter1 > elastic_band_.begin()) && (tmp_iter1 <= elastic_band_.end()) );
00328         tmp_band.insert(tmp_band.begin(), elastic_band_.begin(), tmp_iter1);
00329       }
00330 
00331       // done
00332       elastic_band_ = tmp_band;
00333       return true;
00334     }
00335 
00336     // otherwise, we need to do some more work - add complete band to tmp_band
00337     ROS_DEBUG("No direct connection found - Composing tmp band and trying to fill gap");
00338     if(add_frames_at == add_front)
00339     {
00340       // compose new vector by appending elastic_band to new frames
00341       tmp_band.insert(tmp_band.end(), elastic_band_.begin(), elastic_band_.end());
00342       // and get iterators to connecting bubbles
00343       tmp_iter1 = tmp_band.begin() + ((int) band_to_add.size()) - 1;
00344       tmp_iter2 = tmp_iter1 + 1;
00345     }
00346     else
00347     {
00348       // compose new vector by pre-appending elastic_band to new frames
00349       tmp_band.insert(tmp_band.begin(), elastic_band_.begin(), elastic_band_.end());
00350       // and get iterators to connecting bubbles
00351       tmp_iter1 = tmp_band.begin() + ((int) elastic_band_.size()) - 1;
00352       tmp_iter2 = tmp_iter1 + 1;
00353     }
00354 
00355     // just in case
00356     ROS_ASSERT( tmp_iter1 >= tmp_band.begin() );
00357     ROS_ASSERT( tmp_iter2 < tmp_band.end() );
00358     ROS_ASSERT( tmp_iter1 < tmp_iter2 );
00359     if(!fillGap(tmp_band, tmp_iter1, tmp_iter2))
00360     {
00361       // we could not connect band and robot at its current position
00362       ROS_DEBUG("Could not connect robot pose to band - Failed to fill gap.");
00363       return false;
00364     }
00365 
00366     // otherwise - done
00367     elastic_band_ = tmp_band;
00368 
00369     return true;
00370   }
00371 
00372 
00373   bool EBandPlanner::optimizeBand()
00374   {
00375     // check if plugin initialized
00376     if(!initialized_)
00377     {
00378       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00379       return false;
00380     }
00381 
00382     // check if there is a band
00383     if(elastic_band_.empty())
00384     {
00385       ROS_ERROR("Band is empty. Probably Band has not been set yet");
00386       return false;
00387     }
00388 
00389     // call optimization with member elastic_band_
00390     ROS_DEBUG("Starting optimization of band");
00391     if(!optimizeBand(elastic_band_))
00392     {
00393       ROS_DEBUG("Aborting Optimization. Changes discarded.");
00394       return false;
00395     }
00396 
00397     ROS_DEBUG("Elastic Band - Optimization successfull!");
00398     return true;
00399   }
00400 
00401 
00402   bool EBandPlanner::optimizeBand(std::vector<Bubble>& band)
00403   {
00404     // check if plugin initialized
00405     if(!initialized_)
00406     {
00407       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00408       return false;
00409     }
00410 
00411     // check whether band and costmap are in the same frame
00412     if(band.front().center.header.frame_id != costmap_ros_->getGlobalFrameID())
00413     {
00414       ROS_ERROR("Elastic Band expects plan for optimization in the %s frame, the plan was sent in the %s frame.",
00415           costmap_ros_->getGlobalFrameID().c_str(), band.front().center.header.frame_id.c_str());
00416       return false;
00417     }
00418 
00419     double distance;
00420     for(int i = 0; i < ((int) band.size()); i++)
00421     {
00422       // update Size of Bubbles in band by calculating Dist to nearest Obstacle [depends kinematic, environment]
00423       if(!calcObstacleKinematicDistance(band.at(i).center.pose, distance))
00424       {
00425         ROS_DEBUG("Optimization (Elastic Band) - Calculation of Distance failed. Frame %d of %d Probably outside map coordinates.",
00426             i, ((int) band.size()) );
00427         return false;
00428       }
00429 
00430       if(distance == 0.0)
00431       {
00432         // frame must not be immediately in collision -> otherwise calculation of gradient will later be invalid
00433         ROS_DEBUG("Optimization (Elastic Band) - Calculation of Distance failed. Frame %d of %d in collision. Plan invalid. Trying to refine band.",
00434             i, ((int) band.size()) );
00435         // TODO if frame in collision try to repair band instead of aborting everything
00436         return false;
00437       }
00438 
00439       band.at(i).expansion = distance;
00440     }
00441 
00442     // close gaps and remove redundant bubbles
00443     if(!refineBand(band))
00444     {
00445       ROS_DEBUG("Elastic Band is broken. Could not close gaps in band. Global replanning needed.");
00446       return false;
00447     }
00448 
00449     // get a copy of current (valid) band
00450     std::vector<Bubble> tmp_band = band;
00451 
00452     // now optimize iteratively (for instance by miminizing the energy-function of the full system)
00453     for(int i = 0; i < num_optim_iterations_; i++)
00454     {
00455       ROS_DEBUG("Inside optimization: Cycle no %d", i);
00456 
00457       // calculate forces and apply changes
00458       if(!modifyBandArtificialForce(tmp_band))
00459       {
00460         ROS_DEBUG("Optimization failed while trying to modify Band.");
00461         // something went wrong -> discard changes and stop process
00462         return false;
00463       }
00464 
00465       // check whether band still valid - refine if neccesarry
00466       if(!refineBand(tmp_band))
00467       {
00468         ROS_DEBUG("Optimization failed while trying to refine modified band");
00469         // modified band is not valid anymore -> discard changes and stop process
00470         return false;
00471       }
00472     }
00473 
00474     // copy changes back to band
00475     band = tmp_band;
00476     return true;
00477   }
00478 
00479 
00480   // private methods
00481 
00482   bool EBandPlanner::refineBand(std::vector<Bubble>& band)
00483   {
00484     // check if plugin initialized
00485     if(!initialized_)
00486     {
00487       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
00488       return false;
00489     }
00490 
00491     // check if band valid (minimum 2 bubbles)
00492     if(band.size() < 2)
00493     {
00494       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()) );
00495       return false;
00496     }
00497 
00498     // instantiate local variables
00499     bool success;
00500     std::vector<Bubble> tmp_band;
00501     std::vector<Bubble>::iterator start_iter, end_iter;
00502 
00503     // remove redundant Bubbles and fill gabs recursively
00504     tmp_band = band;
00505     start_iter = tmp_band.begin();
00506     end_iter = (tmp_band.end() - 1); // -1 because .end() points "past the end"!
00507 
00508     success = removeAndFill(tmp_band, start_iter, end_iter);
00509 
00510     if(!success)
00511       ROS_DEBUG("Band is broken. Could not close gaps.");
00512     else
00513     {
00514 #ifdef DEBUG_EBAND_
00515       ROS_DEBUG("Recursive filling and removing DONE");
00516 #endif
00517       band = tmp_band;
00518     }
00519 
00520     return success;
00521   }
00522 
00523 
00524   bool EBandPlanner::removeAndFill(std::vector<Bubble>& band, std::vector<Bubble>::iterator& start_iter,std::vector<Bubble>::iterator& end_iter)
00525   {
00526     // instantiate local variables
00527     bool overlap;
00528     std::vector<Bubble>::iterator tmp_iter;
00529     int mid_int, diff_int;
00530 
00531 #ifdef DEBUG_EBAND_
00532     int debug_dist_start, debug_dist_iters;
00533     debug_dist_start = std::distance(band.begin(), start_iter);
00534     debug_dist_iters = std::distance(start_iter, end_iter);
00535     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()) );
00536 #endif
00537 
00538     // check that iterators are still valid
00539     ROS_ASSERT( start_iter >= band.begin() );
00540     ROS_ASSERT( end_iter < band.end() ); // "<" because .end() points _behind_ last element of vector
00541     ROS_ASSERT( start_iter < end_iter );
00542 
00543     // check whether start and end bubbles of this intervall overlap
00544     overlap = checkOverlap(*start_iter, *end_iter);
00545 
00546     if(overlap)
00547     {
00548 
00549 #ifdef DEBUG_EBAND_
00550       ROS_DEBUG("Refining Recursive - Bubbles overlapp, check for redundancies");
00551 #endif
00552 
00553       // if there are bubbles between start and end of intervall remove them (they are redundant as start and end of intervall do overlap)
00554       if((start_iter + 1) < end_iter)
00555       {
00556 #ifdef DEBUG_EBAND_
00557         ROS_DEBUG("Refining Recursive - Bubbles overlapp, removing Bubbles %d to %d.", (debug_dist_start + 1), (debug_dist_start + debug_dist_iters -1));
00558 #endif
00559 
00560         // erase bubbles between start and end (but not start and end themself) and get new iterator to end (old one is invalid)
00561         tmp_iter = band.erase((start_iter+1), end_iter);
00562 
00563         // write back changed iterator pointing to the end of the intervall
00564         end_iter = tmp_iter;
00565       }
00566 
00567 #ifdef DEBUG_EBAND_
00568       ROS_DEBUG("Refining Recursive - Bubbles overlapp - DONE");
00569 #endif
00570 
00571       // we are done here (leaf of this branch is reached)
00572       return true;
00573     }
00574 
00575 
00576     // if bubbles do not overlap -> check whether there are still bubbles between start and end
00577     if((start_iter + 1) < end_iter)
00578     {
00579 #ifdef DEBUG_EBAND_
00580       ROS_DEBUG("Refining Recursive - Bubbles do not overlapp, go one recursion deeper");
00581 #endif
00582 
00583       // split remaining sequence of bubbles
00584       // get distance between start and end iterator for this intervall
00585       mid_int = std::distance(start_iter, end_iter);
00586       mid_int = mid_int/2; // division by integer implies floor (round down)
00587 
00588       // now get iterator pointing to the middle (roughly)
00589       tmp_iter = start_iter + mid_int;
00590       // and realative position of end_iter to tmp_iter
00591       diff_int = (int) std::distance(tmp_iter, end_iter);
00592 
00593       // after all this arithmetics - check that iterators are still valid
00594       ROS_ASSERT( start_iter >= band.begin() );
00595       ROS_ASSERT( end_iter < band.end() ); // "<" because .end() points _behind_ last element of vector
00596       ROS_ASSERT( start_iter < end_iter );
00597 
00598 
00599       // and call removeAndFill recursively for the left intervall
00600       if(!removeAndFill(band, start_iter, tmp_iter))
00601       {
00602         // band is broken in this intervall and could not be fixed
00603         return false;
00604       }
00605 
00606       // carefull at this point!!! if we filled in or removed bubbles end_iter is not valid anymore
00607       // but the relative position towards tmp_iter is still the same and tmp_iter was kept valid in the lower recursion steps
00608       end_iter = tmp_iter + diff_int;
00609 
00610       // check that iterators are still valid - one more time
00611       ROS_ASSERT( start_iter >= band.begin() );
00612       ROS_ASSERT( end_iter < band.end() ); // "<" because .end() points _behind_ last element of vector
00613       ROS_ASSERT( (start_iter < tmp_iter) && (tmp_iter < end_iter) );
00614 
00615 
00616       // o.k. we are done with left hand intervall now do the same for the right hand intervall
00617       // but first get relative position of start and tmp iter
00618       diff_int = (int) std::distance(start_iter, tmp_iter);
00619       if(!removeAndFill(band, tmp_iter, end_iter))
00620       {
00621         // band is broken in this intervall and could not be fixed
00622         return false;
00623       }
00624 
00625       // if we filled in bubbles vector might have been reallocated -> start_iter might be invalid
00626       start_iter = tmp_iter - diff_int;
00627 
00628       // check that iterators are still valid - almost done
00629       ROS_ASSERT( start_iter >= band.begin() );
00630       ROS_ASSERT( end_iter < band.end() ); // "<" because .end() points _behind_ last element of vector
00631       ROS_ASSERT( (start_iter < tmp_iter) && (tmp_iter < end_iter) );
00632 
00633 
00634       // we reached the leaf but we are not yet done
00635       // -> we know that there are no redundant elements in the left intervall taken on its own
00636       // -> and we know the same holds for the right intervall
00637       // but the middle bubble itself might be redundant -> check it
00638       if(checkOverlap(*(tmp_iter-1), *(tmp_iter+1)))
00639       {
00640 #ifdef DEBUG_EBAND_
00641         ROS_DEBUG("Refining Recursive - Removing middle bubble");
00642 #endif
00643 
00644         // again: get distance between (tmp_iter + 1) and end_iter, (+1 because we will erase tmp_iter itself)
00645         diff_int = (int) std::distance((tmp_iter + 1), end_iter);
00646 
00647         // remove middle bubble and correct end_iter
00648         tmp_iter = band.erase(tmp_iter);
00649         end_iter = tmp_iter + diff_int;
00650       }
00651 
00652       // check that iterators are still valid - almost almost
00653       ROS_ASSERT( start_iter >= band.begin() );
00654       ROS_ASSERT( end_iter < band.end() ); // "<" because .end() points _behind_ last element of vector
00655       ROS_ASSERT( start_iter < end_iter );
00656 
00657 #ifdef DEBUG_EBAND_
00658       ROS_DEBUG("Refining Recursive - Bubbles do not overlapp, go one recursion deeper DONE");
00659 #endif
00660 
00661       //now we are done with this case
00662       return true;
00663     }
00664 
00665 
00666 #ifdef DEBUG_EBAND_
00667     ROS_DEBUG("Refining Recursive - Gap detected, fill recursive");
00668 #endif
00669 
00670     // last possible case -> bubbles do not overlap AND there are nor bubbles in between -> try to fill gap recursively
00671     if(!fillGap(band, start_iter, end_iter))
00672     {
00673       // 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;)
00674       ROS_DEBUG("Failed to fill gap between bubble %d and %d.", (int) distance(band.begin(), start_iter), (int) distance(band.begin(), end_iter) );
00675       return false;
00676     }
00677 
00678 #ifdef DEBUG_EBAND_
00679     ROS_DEBUG("Refining Recursive - Gap detected, fill recursive DONE");
00680 #endif
00681 
00682     // we could fill the gap (reached leaf of this branch)
00683     return true;
00684   }
00685 
00686 
00687   bool EBandPlanner::fillGap(std::vector<Bubble>& band, std::vector<Bubble>::iterator& start_iter,std::vector<Bubble>::iterator& end_iter)
00688   {
00689     // insert bubbles in the middle between not-overlapping bubbles (e.g. (Dist > Size Bub1) && (Dist > Size Bub2) )
00690     // repeat until gaps are closed
00691 
00692     // instantiate local variables
00693     double distance = 0.0;
00694     Bubble interpolated_bubble;
00695     geometry_msgs::PoseStamped interpolated_center;
00696     std::vector<Bubble>::iterator tmp_iter;
00697     int diff_int, start_num, end_num;
00698 
00699     // make sure this method was called for a valid element in the forces or bubbles vector
00700     ROS_ASSERT( start_iter >= band.begin() );
00701     ROS_ASSERT( end_iter < band.end() ); // "<" because .end() points _behind_ last element of vector
00702     ROS_ASSERT( start_iter < end_iter );
00703 
00704 
00705 #ifdef DEBUG_EBAND_
00706     ROS_DEBUG("Fill recursive - interpolate");
00707 #endif
00708 
00709     // interpolate between bubbles [depends kinematic]
00710     if(!interpolateBubbles(start_iter->center, end_iter->center, interpolated_center))
00711     {
00712       // interpolation failed (for whatever reason), so return with false
00713       start_num = std::distance(band.begin(), start_iter);
00714       end_num = std::distance(band.begin(), end_iter);
00715       ROS_DEBUG("Interpolation failed while trying to fill gap between bubble %d and %d.", start_num, end_num);
00716       return false;
00717     }
00718 
00719 
00720 #ifdef DEBUG_EBAND_
00721     ROS_DEBUG("Fill recursive - calc expansion of interpolated bubble");
00722 #endif
00723 
00724     // calc Size of Bubbles by calculating Dist to nearest Obstacle [depends kinematic, environment]
00725     if(!calcObstacleKinematicDistance(interpolated_center.pose, distance))
00726     {
00727       // pose probably outside map coordinates
00728       start_num = std::distance(band.begin(), start_iter);
00729       end_num = std::distance(band.begin(), end_iter);
00730       ROS_DEBUG("Calculation of Distance failed for interpolated bubble - failed to fill gap between bubble %d and %d.", start_num, end_num);
00731       return false;
00732     }
00733 
00734     if(distance <= tiny_bubble_expansion_)
00735     {
00736       // band broken! frame must not be immediately in collision -> otherwise calculation of gradient will later be invalid
00737       start_num = std::distance(band.begin(), start_iter);
00738       end_num = std::distance(band.begin(), end_iter);
00739       ROS_DEBUG("Interpolated Bubble in Collision - failed to fill gap between bubble %d and %d.", start_num, end_num);
00740       // TODO this means only that there is an obstacle on the direct interconnection between the bubbles - think about repair or rescue strategies -
00741       return false;
00742     }
00743 
00744 
00745 #ifdef DEBUG_EBAND_
00746     ROS_DEBUG("Fill recursive - inserting interpolated bubble at (%f, %f), with expansion %f", interpolated_center.pose.position.x, interpolated_center.pose.position.y, distance);
00747 #endif
00748 
00749     // insert bubble and assign center and expansion
00750     interpolated_bubble.center = interpolated_center;
00751     interpolated_bubble.expansion = distance;
00752     // insert bubble (vector.insert() inserts elements before given iterator) and get iterator pointing to it
00753     tmp_iter = band.insert(end_iter, interpolated_bubble);
00754     // insert is a little bit more tricky than erase, as it may require reallocation of the vector -> start and end iter could be invalid
00755     start_iter = tmp_iter - 1;
00756     end_iter = tmp_iter + 1;
00757 
00758     // check that iterators are still valid - just in case :)
00759     ROS_ASSERT( start_iter >= band.begin() );
00760     ROS_ASSERT( end_iter < band.end() ); // "<" because .end() points _behind_ last element of vector
00761     ROS_ASSERT( (start_iter < tmp_iter) && (tmp_iter < end_iter) );
00762 
00763 
00764 #ifdef DEBUG_EBAND_
00765     ROS_DEBUG("Fill recursive - check overlap interpolated bubble and first bubble");
00766 #endif
00767 
00768     // we have now two intervalls (left and right of inserted bubble) which need to be checked again and filled if neccessary
00769     if(!checkOverlap(*start_iter, *tmp_iter))
00770     {
00771 
00772 #ifdef DEBUG_EBAND
00773       ROS_DEBUG("Fill recursive - gap btw. interpolated and first bubble - fill recursive");
00774 #endif
00775 
00776       // gap in left intervall -> try to fill
00777       if(!fillGap(band, start_iter, tmp_iter))
00778       {
00779         // band is broken in this intervall and could not be fixed
00780         return false;
00781       }
00782       // bubbles were inserted -> make sure to keep end_iter iterator valid
00783       end_iter = tmp_iter + 1;
00784     }
00785 
00786     // check that iterators are still valid - just in case :)
00787     ROS_ASSERT( start_iter >= band.begin() );
00788     ROS_ASSERT( end_iter < band.end() ); // "<" because .end() points _behind_ last element of vector
00789     ROS_ASSERT( (start_iter < tmp_iter) && (tmp_iter < end_iter) );
00790 
00791 
00792 #ifdef DEBUG_EBAND_
00793     ROS_DEBUG("Fill recursive - check overlap interpolated bubble and second bubble");
00794 #endif
00795 
00796     if(!checkOverlap(*tmp_iter, *end_iter))
00797     {
00798 
00799 #ifdef DEBUG_EBAND_
00800       ROS_DEBUG("Fill recursive - gap btw. interpolated and second bubble - fill recursive");
00801 #endif
00802 
00803       // get distance between start_iter and tmp_iter before filling right intervall (in case of reallocation of vector)
00804       diff_int = (int) std::distance(start_iter, tmp_iter);
00805 
00806       // gap in left intervall -> try to fill
00807       if(!fillGap(band, tmp_iter, end_iter))
00808       {
00809         // band is broken in this intervall and could not be fixed
00810         return false;
00811       }
00812       // bubbles were inserted -> make sure to keep start_iter iterator valid
00813       start_iter = tmp_iter - diff_int;
00814     }
00815 
00816     // check that iterators are still valid - just in case :)
00817     ROS_ASSERT( start_iter >= band.begin() );
00818     ROS_ASSERT( end_iter < band.end() ); // "<" because .end() points _behind_ last element of vector
00819     ROS_ASSERT( (start_iter < tmp_iter) && (tmp_iter < end_iter) );
00820 
00821 
00822 #ifdef DEBUG_EBAND_
00823     ROS_DEBUG("Fill recursive - gap closed");
00824 #endif
00825 
00826     // bubbles overlap, iterators are kept valid -> done
00827     return true;
00828   }
00829 
00830 
00831   // optimization
00832 
00833   bool EBandPlanner::modifyBandArtificialForce(std::vector<Bubble>& band)
00834   {
00835     if(band.empty())
00836     {
00837       ROS_ERROR("Trying to modify an empty band.");
00838       return false;
00839     }
00840 
00841     if(band.size() <= 2)
00842     {
00843       // nothing to do here -> we can stop right away
00844       return true;
00845     }
00846 
00847     std::vector<geometry_msgs::WrenchStamped> internal_forces, external_forces, forces;
00848     geometry_msgs::WrenchStamped wrench;
00849 
00850 #ifdef DEBUG_EBAND_
00851     //publish original band
00852     if(visualization_)
00853       eband_visual_->publishBand("bubbles", band);
00854 #endif
00855 
00856     // init variables to calm down debug warnings
00857     wrench.header.stamp = ros::Time::now();
00858     wrench.header.frame_id = band[0].center.header.frame_id;
00859     wrench.wrench.force.x = 0.0;
00860     wrench.wrench.force.y = 0.0;
00861     wrench.wrench.force.z = 0.0;
00862     wrench.wrench.torque.x = 0.0;
00863     wrench.wrench.torque.y = 0.0;
00864     wrench.wrench.torque.z = 0.0;
00865     internal_forces.assign(band.size(), wrench);
00866     external_forces = internal_forces;
00867     forces = internal_forces;
00868 
00869     // TODO log timigs of planner
00870     // instantiate variables for timing
00871     //ros::Time time_stamp1, time_stamp2;
00872     //ros::Duration duration;
00873     //time_stamp1 = ros::Time::now();
00874 
00875     // due to refinement band might change its size -> use while loop
00876     int i = 1;
00877     bool forward = true; // cycle 1xforwards and 1xbackwards through band
00878     while( (i>0) && (i < ((int) band.size() - 1)) )
00879     {
00880       ROS_DEBUG("Modifying bubble %d.", i);
00881 
00882 
00883 #ifdef DEBUG_EBAND_
00884       ROS_DEBUG("Calculating internal force for bubble %d.", i);
00885 #endif
00886 
00887       if(!calcInternalForces(i, band, band.at(i), internal_forces.at(i)))
00888       {
00889         // calculation of internal forces failed - stopping optimization
00890         ROS_DEBUG("Calculation of internal forces failed");
00891         return false;
00892       }
00893 
00894 #ifdef DEBUG_EBAND_
00895       if(visualization_)
00896         // publish internal forces
00897         eband_visual_->publishForce("internal_forces", i, eband_visual_->blue, internal_forces[i], band[i]);
00898       // Log out debug info about next step
00899       ROS_DEBUG("Calculating external force for bubble %d.", i);
00900 #endif
00901 
00902 
00903       //if(!calcExternalForces(i, band, external_forces))
00904       if(!calcExternalForces(i, band.at(i), external_forces.at(i)))
00905       {
00906         // calculation of External Forces failed - stopping optimization
00907         ROS_DEBUG("Calculation of external forces failed");
00908         return false;
00909       }
00910 
00911 #ifdef DEBUG_EBAND_
00912       if(visualization_)
00913         //publish external forces
00914         eband_visual_->publishForce("external_forces", i, eband_visual_->red, external_forces[i], band[i]);
00915       // Log out debug info about next step
00916       ROS_DEBUG("Superposing internal and external forces");
00917 #endif
00918 
00919 
00920       // sum up external and internal forces over all bubbles
00921       forces.at(i).wrench.force.x = internal_forces.at(i).wrench.force.x + external_forces.at(i).wrench.force.x;
00922       forces.at(i).wrench.force.y = internal_forces.at(i).wrench.force.y + external_forces.at(i).wrench.force.y;
00923       forces.at(i).wrench.force.z = internal_forces.at(i).wrench.force.z + external_forces.at(i).wrench.force.z;
00924 
00925       forces.at(i).wrench.torque.x = internal_forces.at(i).wrench.torque.x + external_forces.at(i).wrench.torque.x;
00926       forces.at(i).wrench.torque.y = internal_forces.at(i).wrench.torque.y + external_forces.at(i).wrench.torque.y;
00927       forces.at(i).wrench.torque.z = internal_forces.at(i).wrench.torque.z + external_forces.at(i).wrench.torque.z;
00928 
00929 #ifdef DEBUG_EBAND_
00930       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);
00931       ROS_DEBUG("Supressing tangential forces");
00932 #endif
00933 
00934       if(!suppressTangentialForces(i, band, forces.at(i)))
00935       {
00936         // suppression of tangential forces failed
00937         ROS_DEBUG("Supression of tangential forces failed");
00938         return false;
00939       }
00940 
00941 #ifdef DEBUG_EBAND_
00942       if(visualization_)
00943         //publish resulting forces
00944         eband_visual_->publishForce("resulting_forces", i, eband_visual_->green, forces[i], band[i]);
00945 #endif
00946 
00947 
00948       ROS_DEBUG("Applying forces to modify band");
00949       if(!applyForces(i, band, forces))
00950       {
00951         // band invalid
00952         ROS_DEBUG("Band is invalid - Stopping Modification");
00953         return false;
00954       }
00955 
00956 #ifdef DEBUG_EBAND_
00957       if(visualization_)
00958       {
00959         // publish band with changed bubble at resulting position
00960         eband_visual_->publishBand("bubbles", band);
00961         ros::Duration(0.01).sleep();
00962       }
00963 #endif
00964 
00965 
00966       //next bubble
00967       if(forward)
00968       {
00969         i++;
00970         if(i == ((int) band.size() - 1))
00971         {
00972           // reached end of band - start backwards cycle until at start again - then stop
00973           forward = false;
00974           i--;
00975           ROS_DEBUG("Optimization Elastic Band - Forward cycle done, starting backward cycle");
00976         }
00977       }
00978       else
00979       {
00980         i--;
00981       }
00982     }
00983 
00984     return true;
00985   }
00986 
00987 
00988   bool EBandPlanner::applyForces(int bubble_num, std::vector<Bubble>& band, std::vector<geometry_msgs::WrenchStamped> forces)
00989   {
00990     //cycle over all bubbles except first and last (these are fixed)
00991     if(band.size() <= 2)
00992     {
00993       // nothing to do here -> we can stop right away - no forces calculated
00994       return true;
00995     }
00996 
00997     geometry_msgs::Pose2D bubble_pose2D, new_bubble_pose2D;
00998     geometry_msgs::Pose bubble_pose, new_bubble_pose;
00999     geometry_msgs::Twist bubble_jump;
01000     Bubble new_bubble = band.at(bubble_num);
01001     double distance;
01002 
01003 
01004     // move bubble
01005     bubble_pose = band.at(bubble_num).center.pose;
01006     PoseToPose2D(bubble_pose, bubble_pose2D);
01007 
01008     // move according to bubble_new = bubble_old + alpha*force -> we choose alpha to be the current expansion of the modified bubble
01009     bubble_jump.linear.x = band.at(bubble_num).expansion*forces.at(bubble_num).wrench.force.x;
01010     bubble_jump.linear.y = band.at(bubble_num).expansion*forces.at(bubble_num).wrench.force.y;
01011     bubble_jump.linear.z = 0.0;
01012     bubble_jump.angular.x = 0.0;
01013     bubble_jump.angular.y = 0.0;
01014     bubble_jump.angular.z = band.at(bubble_num).expansion/getCircumscribedRadius(*costmap_ros_) * forces.at(bubble_num).wrench.torque.z;
01015     bubble_jump.angular.z = angles::normalize_angle(bubble_jump.angular.z);
01016 
01017     // apply changes to calc tmp bubble position
01018     new_bubble_pose2D.x = bubble_pose2D.x + bubble_jump.linear.x;
01019     new_bubble_pose2D.y = bubble_pose2D.y + bubble_jump.linear.y;
01020     new_bubble_pose2D.theta = bubble_pose2D.theta + bubble_jump.angular.z;
01021     new_bubble_pose2D.theta = angles::normalize_angle(new_bubble_pose2D.theta);
01022 
01023     // apply changes to local copy
01024     Pose2DToPose(new_bubble_pose, new_bubble_pose2D);
01025     new_bubble.center.pose = new_bubble_pose;
01026 
01027 #ifdef DEBUG_EBAND_
01028     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,
01029         bubble_jump.linear.x, bubble_jump.linear.y, bubble_jump.angular.z);
01030 #endif
01031 
01032 
01033     // check validity of moved bubble
01034 
01035     // recalc expansion of bubble -> calc Size of Bubbles by calculating Dist to nearest Obstacle [depends kinematic, environment]
01036     if(!calcObstacleKinematicDistance(new_bubble_pose, distance))
01037     {
01038       ROS_DEBUG("Calculation of Distance failed. Frame %d of %d Probably outside map. Discarding Changes", bubble_num, ((int) band.size()) );
01039 
01040 #ifdef DEBUG_EBAND_
01041       if(visualization_)
01042         eband_visual_->publishBubble("bubble_hypo", bubble_num, eband_visual_->red, new_bubble);
01043 #endif
01044 
01045       // this bubble must not be changed, but band is still valid -> continue with other bubbles
01046       return true;
01047     }
01048 
01049     if(distance <= tiny_bubble_expansion_)
01050     {
01051       // frame must not be immediately in collision -> otherwise calculation of gradient will later be invalid
01052       ROS_DEBUG("Calculation of Distance failed. Frame %d of %d in collision. Plan invalid. Discarding Changes", bubble_num, ((int) band.size()) );
01053 
01054 #ifdef DEBUG_EBAND_
01055       if(visualization_)
01056         eband_visual_->publishBubble("bubble_hypo", bubble_num, eband_visual_->red, new_bubble);
01057 #endif
01058 
01059       // this bubble must not be changed, but band is still valid -> continue with other bubbles
01060       return true;
01061     }
01062 
01063     // so far o.k. -> assign distance to new bubble
01064     new_bubble.expansion = distance;
01065 
01066 
01067     // check whether step was reasonable
01068 
01069     geometry_msgs::WrenchStamped new_bubble_force = forces.at(bubble_num);
01070 
01071     // check whether we get a valid force calculation here
01072     if(!getForcesAt(bubble_num, band, new_bubble, new_bubble_force))
01073     {
01074       // error during calculation of forces for the new position - discard changes
01075       ROS_DEBUG("Cannot calculate forces on bubble %d at new position - discarding changes", bubble_num);
01076       return true;
01077     }
01078 
01079 #ifdef DEBUG_EBAND_
01080     ROS_DEBUG("Check for zero-crossings in force on bubble %d", bubble_num);
01081 #endif
01082 
01083     // check for zero-crossings in the force-vector
01084     double checksum_zero, abs_new_force, abs_old_force;
01085 
01086     // project force-vectors onto each other
01087     checksum_zero = (new_bubble_force.wrench.force.x * forces.at(bubble_num).wrench.force.x) +
01088       (new_bubble_force.wrench.force.y * forces.at(bubble_num).wrench.force.y) +
01089       (new_bubble_force.wrench.torque.z * forces.at(bubble_num).wrench.torque.z);
01090 
01091     // if sign changes and ...
01092     if(checksum_zero < 0.0)
01093     {
01094       ROS_DEBUG("Detected zero-crossings in force on bubble %d. Checking total change in force.", bubble_num);
01095       // check the absolute values of the two vectors
01096       abs_new_force = sqrt( (new_bubble_force.wrench.force.x * new_bubble_force.wrench.force.x) +
01097           (new_bubble_force.wrench.force.y * new_bubble_force.wrench.force.y) +
01098           (new_bubble_force.wrench.torque.z * new_bubble_force.wrench.torque.z) );
01099       abs_old_force = sqrt( (forces.at(bubble_num).wrench.force.x * forces.at(bubble_num).wrench.force.x) +
01100           (forces.at(bubble_num).wrench.force.x * forces.at(bubble_num).wrench.force.x) +
01101           (forces.at(bubble_num).wrench.torque.z * forces.at(bubble_num).wrench.torque.z) );
01102 
01103       // force still has a significant high value (> ~75% of old force by default)
01104       if( (abs_new_force > equilibrium_relative_overshoot_ * abs_old_force) && (abs_new_force > significant_force_) )
01105       {
01106         ROS_DEBUG("Detected significante change in force (%f to %f) on bubble %d. Entering Recursive Approximation.", abs_old_force, abs_new_force, bubble_num);
01107         // o.k. now we really have to take a closer look -> start recursive approximation to equilibrium-point
01108         int curr_recursion_depth = 0;
01109         geometry_msgs::Twist new_step_width;
01110         Bubble curr_bubble = band.at(bubble_num);
01111         geometry_msgs::WrenchStamped curr_bubble_force = forces.at(bubble_num);
01112 
01113         // half step size
01114         new_step_width.linear.x = 0.5*bubble_jump.linear.x;
01115         new_step_width.linear.y = 0.5*bubble_jump.linear.y;
01116         new_step_width.linear.z = 0.5*bubble_jump.linear.z;
01117         new_step_width.angular.x = 0.5*bubble_jump.angular.x;
01118         new_step_width.angular.y = 0.5*bubble_jump.angular.y;
01119         new_step_width.angular.z = 0.5*bubble_jump.angular.z;
01120 
01121         // one step deeper into the recursion
01122         if(moveApproximateEquilibrium(bubble_num, band, curr_bubble, curr_bubble_force, new_step_width, curr_recursion_depth))
01123         {
01124           // done with recursion - change bubble and hand it back
01125           new_bubble = curr_bubble;
01126 
01127 #ifdef DEBUG_EBAND_
01128           geometry_msgs::Pose2D curr_bubble_pose2D;
01129           PoseToPose2D(curr_bubble.center.pose, curr_bubble_pose2D);
01130           ROS_DEBUG("Instead - Try moving bubble %d at (%f, %f, %f) by (%f, %f, %f) to (%f, %f, %f).",
01131               bubble_num, bubble_pose2D.x, bubble_pose2D.y, bubble_pose2D.theta,
01132               new_step_width.linear.x, new_step_width.linear.y, new_step_width.angular.z,
01133               curr_bubble_pose2D.x, curr_bubble_pose2D.y, curr_bubble_pose2D.theta);
01134 #endif
01135         }
01136       }
01137     }
01138 
01139 
01140     // check validity of resulting band (given the moved bubble)
01141 
01142     // TODO use this routine not only to check whether gap can be filled but also to fill gap (if possible)
01143     // get local copy of band, set new position of moved bubble and init iterators
01144     std::vector<Bubble> tmp_band = band;
01145     std::vector<Bubble>::iterator start_iter, end_iter;
01146     tmp_band.at(bubble_num) = new_bubble;
01147     start_iter = tmp_band.begin();
01148 
01149     // check left connection (bubble and bubble-1)
01150     start_iter = start_iter + bubble_num - 1;
01151     end_iter = start_iter + 1;
01152 
01153     // check Overlap - if bubbles do not overlap try to fill gap
01154     if(!checkOverlap(*start_iter, *end_iter))
01155     {
01156       if(!fillGap(tmp_band, start_iter, end_iter))
01157       {
01158         ROS_DEBUG("Bubble at new position cannot be connected to neighbour. Discarding changes.");
01159         // this bubble must not be changed, but band is still valid -> continue with other bubbles
01160         return true;
01161       }
01162     }
01163 
01164 
01165     // get fresh copy of band, set new position of bubble again and reinit iterators
01166     tmp_band = band;
01167     tmp_band.at(bubble_num) = new_bubble;
01168     start_iter = tmp_band.begin();
01169 
01170     // check right connection (bubble and bubble +1)
01171     start_iter = start_iter + bubble_num;
01172     end_iter = start_iter + 1;
01173 
01174     // check Overlap - if bubbles do not overlap try to fill gap
01175     if(!checkOverlap(*start_iter, *end_iter))
01176     {
01177       if(!fillGap(tmp_band, start_iter, end_iter))
01178       {
01179         ROS_DEBUG("Bubble at new position cannot be connected to neighbour. Discarding changes.");
01180         // this bubble must not be changed, but band is still valid -> continue with other bubbles
01181         return true;
01182       }
01183     }
01184 
01185 
01186     // check successful - bubble and band valid apply changes
01187 
01188 #ifdef DEBUG_EBAND_
01189     ROS_DEBUG("Frame %d of %d: Check successful - bubble and band valid. Applying Changes", bubble_num, ((int) band.size()) );
01190 #endif
01191 
01192     band.at(bubble_num) = new_bubble;
01193 
01194     return true;
01195   }
01196 
01197 
01198   bool EBandPlanner::moveApproximateEquilibrium(const int& bubble_num, const std::vector<Bubble>& band, Bubble& curr_bubble,
01199       const geometry_msgs::WrenchStamped& curr_bubble_force, geometry_msgs::Twist& curr_step_width, const int& curr_recursion_depth)
01200   {
01201 
01202     double distance;
01203     Bubble new_bubble = curr_bubble;
01204     geometry_msgs::Pose2D new_bubble_pose2D, curr_bubble_pose2D;
01205     geometry_msgs::WrenchStamped new_bubble_force = curr_bubble_force;
01206 
01207     // move bubble
01208     PoseToPose2D(curr_bubble.center.pose, curr_bubble_pose2D);
01209     PoseToPose2D(new_bubble.center.pose, new_bubble_pose2D);
01210 
01211     // apply changes to calculate tmp bubble position
01212     new_bubble_pose2D.x = curr_bubble_pose2D.x + curr_step_width.linear.x;
01213     new_bubble_pose2D.y = curr_bubble_pose2D.y + curr_step_width.linear.y;
01214     new_bubble_pose2D.theta = curr_bubble_pose2D.theta + curr_step_width.angular.z;
01215     new_bubble_pose2D.theta = angles::normalize_angle(new_bubble_pose2D.theta);
01216 
01217     // apply changes to local copy
01218     Pose2DToPose(new_bubble.center.pose, new_bubble_pose2D);
01219 
01220 
01221     // check validity of moved bubble
01222 
01223     // recalc expansion of bubble -> calc Size of Bubbles by calculating Dist to nearest Obstacle [depends kinematic, environment]
01224     if(!calcObstacleKinematicDistance(new_bubble.center.pose, distance))
01225       return false;
01226 
01227     // we wont be able to calculate forces later on
01228     if(distance == 0.0)
01229       return false;
01230 
01231 
01232     // so far o.k. -> assign distance to new bubble
01233     new_bubble.expansion = distance;
01234 
01235     // check whether we get a valid force calculation here
01236     if(!getForcesAt(bubble_num, band, new_bubble, new_bubble_force))
01237       return false;
01238 
01239     // great - lets store this - this is better then what we had so far
01240     curr_bubble = new_bubble;
01241 
01242     // if everything is fine and we reached our maximum recursion depth
01243     if(curr_recursion_depth >= max_recursion_depth_approx_equi_)
01244       // break recursion at this point
01245       return true;
01246 
01247 
01248     // now - let's check for zero-crossing
01249 
01250 #ifdef DEBUG_EBAND_
01251     ROS_DEBUG("Check for zero-crossings in force on bubble %d - Recursion %d", bubble_num, curr_recursion_depth);
01252 #endif
01253 
01254     double checksum_zero, abs_new_force, abs_old_force;
01255     int new_recursion_depth;
01256     geometry_msgs::Twist new_step_width;
01257 
01258     // check zero-crossing by projecting force-vectors onto each other
01259     checksum_zero = (new_bubble_force.wrench.force.x * curr_bubble_force.wrench.force.x) +
01260       (new_bubble_force.wrench.force.y * curr_bubble_force.wrench.force.y) +
01261       (new_bubble_force.wrench.torque.z * curr_bubble_force.wrench.torque.z);
01262 
01263     if(checksum_zero < 0.0)
01264     {
01265 #ifdef DEBUG_EBAND_
01266       ROS_DEBUG("Detected zero-crossings in force on bubble %d - Recursion %d. Checking total change in force.", bubble_num, curr_recursion_depth);
01267 #endif
01268 
01269       // check the absolute values of the two vectors
01270       abs_new_force = sqrt( (new_bubble_force.wrench.force.x * new_bubble_force.wrench.force.x) +
01271           (new_bubble_force.wrench.force.y * new_bubble_force.wrench.force.y) +
01272           (new_bubble_force.wrench.torque.z * new_bubble_force.wrench.torque.z) );
01273       abs_old_force = sqrt( (curr_bubble_force.wrench.force.x * curr_bubble_force.wrench.force.x) +
01274           (curr_bubble_force.wrench.force.x * curr_bubble_force.wrench.force.x) +
01275           (curr_bubble_force.wrench.torque.z * curr_bubble_force.wrench.torque.z) );
01276 
01277       if( (abs_new_force > equilibrium_relative_overshoot_ * abs_old_force) && (abs_new_force > significant_force_) )
01278       {
01279 #ifdef DEBUG_EBAND_
01280         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);
01281 #endif
01282 
01283         // o.k. now we really have to take a closer look -> start recursive approximation to equilibrium-point
01284         new_recursion_depth = curr_recursion_depth + 1;
01285         // half step size - backward direction
01286         new_step_width.linear.x = -0.5*curr_step_width.linear.x;
01287         new_step_width.linear.y = -0.5*curr_step_width.linear.y;
01288         new_step_width.linear.z = -0.5*curr_step_width.linear.z;
01289         new_step_width.angular.x = -0.5*curr_step_width.angular.x;
01290         new_step_width.angular.y = -0.5*curr_step_width.angular.y;
01291         new_step_width.angular.z = -0.5*curr_step_width.angular.z;
01292 
01293         // one step deeper into the recursion
01294         if(moveApproximateEquilibrium(bubble_num, band, new_bubble, new_bubble_force, new_step_width, new_recursion_depth))
01295           // done with recursion - change bubble and hand it back
01296           curr_bubble = new_bubble;
01297 
01298         // otherwise - could not get a better value - return without change (curr_bubble as asigned above)
01299       }
01300 
01301       // otherwise - this is good enough for us - return with this value (curr_bubble as asigned above)
01302     }
01303     else
01304     {
01305 #ifdef DEBUG_EBAND_
01306       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);
01307 #endif
01308 
01309       // continue walk in same direction
01310       new_recursion_depth = curr_recursion_depth + 1;
01311       // half step size - backward direction
01312       new_step_width.linear.x = 0.5*curr_step_width.linear.x;
01313       new_step_width.linear.y = 0.5*curr_step_width.linear.y;
01314       new_step_width.linear.z = 0.5*curr_step_width.linear.z;
01315       new_step_width.angular.x = 0.5*curr_step_width.angular.x;
01316       new_step_width.angular.y = 0.5*curr_step_width.angular.y;
01317       new_step_width.angular.z = 0.5*curr_step_width.angular.z;
01318 
01319       // one step deeper into the recursion
01320       if(moveApproximateEquilibrium(bubble_num, band, new_bubble, new_bubble_force, new_step_width, new_recursion_depth))
01321         // done with recursion - change bubble and hand it back
01322         curr_bubble = new_bubble;
01323 
01324       // otherwise - could not get a better value - return without change (curr_bubble as asigned above)
01325     }
01326 
01327     // done
01328     return true;
01329   }
01330 
01331 
01332   bool EBandPlanner::getForcesAt(int bubble_num, std::vector<Bubble> band, Bubble curr_bubble, geometry_msgs::WrenchStamped& forces)
01333   {
01334     geometry_msgs::WrenchStamped internal_force, external_force;
01335 
01336     if(!calcInternalForces(bubble_num, band, curr_bubble, internal_force))
01337     {
01338       // calculation of internal forces failed - stopping optimization
01339       ROS_DEBUG("Calculation of internal forces failed");
01340       return false;
01341     }
01342 
01343     if(!calcExternalForces(bubble_num, curr_bubble, external_force))
01344     {
01345       // calculation of External Forces failed - stopping optimization
01346       ROS_DEBUG("Calculation of external forces failed");
01347       return false;
01348     }
01349 
01350     // sum up external and internal forces over all bubbles
01351     forces.wrench.force.x = internal_force.wrench.force.x + external_force.wrench.force.x;
01352     forces.wrench.force.y = internal_force.wrench.force.y + external_force.wrench.force.y;
01353     forces.wrench.force.z = internal_force.wrench.force.z + external_force.wrench.force.z;
01354 
01355     forces.wrench.torque.x = internal_force.wrench.torque.x + external_force.wrench.torque.x;
01356     forces.wrench.torque.y = internal_force.wrench.torque.y + external_force.wrench.torque.y;
01357     forces.wrench.torque.z = internal_force.wrench.torque.z + external_force.wrench.torque.z;
01358 
01359     if(!suppressTangentialForces(bubble_num, band, forces))
01360     {
01361       // suppression of tangential forces failed
01362       ROS_DEBUG("Supression of tangential forces failed");
01363       return false;
01364     }
01365 
01366     return true;
01367   }
01368 
01369 
01370   bool EBandPlanner::calcInternalForces(int bubble_num, std::vector<Bubble> band, Bubble curr_bubble, geometry_msgs::WrenchStamped& forces)
01371   {
01372     // check if plugin initialized
01373     if(!initialized_)
01374     {
01375       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
01376       return false;
01377     }
01378 
01379     //cycle over all bubbles except first and last (these are fixed)
01380     if(band.size() <= 2)
01381     {
01382       // nothing to do here -> we can stop right away - no forces calculated
01383       return true;
01384     }
01385 
01386     // init tmp variables
01387     double distance1, distance2;
01388     geometry_msgs::Twist difference1, difference2;
01389     geometry_msgs::Wrench wrench;
01390 
01391     // make sure this method was called for a valid element in the forces or bubbles vector
01392     ROS_ASSERT( bubble_num > 0 );
01393     ROS_ASSERT( bubble_num < ((int) band.size() - 1) );
01394 
01395 
01396     // get distance between bubbles
01397     if(!calcBubbleDistance(curr_bubble.center.pose, band[bubble_num-1].center.pose, distance1))
01398     {
01399       ROS_ERROR("Failed to calculate Distance between two bubbles. Aborting calculation of internal forces!");
01400       return false;
01401     }
01402 
01403     if(!calcBubbleDistance(curr_bubble.center.pose, band[bubble_num+1].center.pose, distance2))
01404     {
01405       ROS_ERROR("Failed to calculate Distance between two bubbles. Aborting calculation of internal forces!");
01406       return false;
01407     }
01408 
01409     // get (elementwise) difference bewtween bubbles
01410     if(!calcBubbleDifference(curr_bubble.center.pose, band[bubble_num-1].center.pose, difference1))
01411     {
01412       ROS_ERROR("Failed to calculate Difference between two bubbles. Aborting calculation of internal forces!");
01413       return false;
01414     }
01415 
01416     if(!calcBubbleDifference(curr_bubble.center.pose, band[bubble_num+1].center.pose, difference2))
01417     {
01418       ROS_ERROR("Failed to calculate Difference between two bubbles. Aborting calculation of internal forces!");
01419       return false;
01420     }
01421 
01422     // make sure to avoid division by  (almost) zero during force calculation (avoid numerical problems)
01423     // -> if difference/distance is (close to) zero then the force in this direction should be zero as well
01424     if(distance1 <= tiny_bubble_distance_)
01425       distance1 = 1000000.0;
01426     if(distance2 <= tiny_bubble_distance_)
01427       distance2 = 1000000.0;
01428 
01429     // now calculate wrench - forces model an elastic band and are normed (distance) to render forces for small and large bubbles the same
01430     wrench.force.x = internal_force_gain_*(difference1.linear.x/distance1 + difference2.linear.x/distance2);
01431     wrench.force.y = internal_force_gain_*(difference1.linear.y/distance1 + difference2.linear.y/distance2);
01432     wrench.force.z = internal_force_gain_*(difference1.linear.z/distance1 + difference2.linear.z/distance2);
01433     wrench.torque.x = internal_force_gain_*(difference1.angular.x/distance1 + difference2.angular.x/distance2);
01434     wrench.torque.y = internal_force_gain_*(difference1.angular.y/distance1 + difference2.angular.y/distance2);
01435     wrench.torque.z = internal_force_gain_*(difference1.angular.z/distance1 + difference2.angular.z/distance2);
01436 
01437 #ifdef DEBUG_EBAND_
01438     ROS_DEBUG("Calculating internal forces: (x, y, theta) = (%f, %f, %f)", wrench.force.x, wrench.force.y, wrench.torque.z);
01439 #endif
01440 
01441     // store wrench in vector
01442     forces.wrench = wrench;
01443 
01444     return true;
01445   }
01446 
01447 
01448   bool EBandPlanner::calcExternalForces(int bubble_num, Bubble curr_bubble, geometry_msgs::WrenchStamped& forces)
01449   {
01450     // check if plugin initialized
01451     if(!initialized_)
01452     {
01453       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
01454       return false;
01455     }
01456 
01457     // init tmp variables
01458     double distance1, distance2;
01459     geometry_msgs::Pose edge;
01460     geometry_msgs::Pose2D edge_pose2D;
01461     geometry_msgs::Wrench wrench;
01462 
01463 
01464     // calculate delta-poses (on upper edge of bubble) for x-direction
01465     edge = curr_bubble.center.pose;
01466     edge.position.x = edge.position.x + curr_bubble.expansion;
01467     // get expansion on bubble at this point
01468     if(!calcObstacleKinematicDistance(edge, distance1))
01469     {
01470       ROS_DEBUG("Bubble %d probably at edge of map - cannot retrieve distance information to calculate external forces", bubble_num);
01471       // we cannot calculate external forces for this bubble - but still continue for the other bubbles
01472       return true;
01473     }
01474     // calculate delta-poses (on lower edge of bubble) for x-direction
01475     edge.position.x = edge.position.x - 2.0*curr_bubble.expansion;
01476     // get expansion on bubble at this point
01477     if(!calcObstacleKinematicDistance(edge, distance2))
01478     {
01479       ROS_DEBUG("Bubble %d probably at edge of map - cannot retrieve distance information to calculate external forces", bubble_num);
01480       // we cannot calculate external forces for this bubble - but still continue for the other bubbles
01481       return true;
01482     }
01483 
01484     // calculate difference-quotient (approx. of derivative) in x-direction
01485     if(curr_bubble.expansion <= tiny_bubble_expansion_)
01486     {
01487       // avoid division by (almost) zero to avoid numerical problems
01488       wrench.force.x = -external_force_gain_*(distance2 - distance1)/(2.0*tiny_bubble_expansion_);
01489       // actually we should never end up here - band should have been considered as broken
01490       ROS_DEBUG("Calculating external forces on broken band. Bubble should have been removed. Local Planner probably ill configured");
01491     }
01492     else
01493       wrench.force.x = -external_force_gain_*(distance2 - distance1)/(2.0*curr_bubble.expansion);
01494     // TODO above equations skip term to make forces continuous at end of influence region - test to add corresponding term
01495 
01496 
01497     // calculate delta-poses (on upper edge of bubble) for y-direction
01498     edge = curr_bubble.center.pose;
01499     edge.position.y = edge.position.y + curr_bubble.expansion;
01500     // get expansion on bubble at this point
01501     if(!calcObstacleKinematicDistance(edge, distance1))
01502     {
01503       ROS_DEBUG("Bubble %d probably at edge of map - cannot retrieve distance information to calculate external forces", bubble_num);
01504       // we cannot calculate external forces for this bubble - but still continue for the other bubbles
01505       return true;
01506     }
01507     // calculate delta-poses (on lower edge of bubble) for x-direction
01508     edge.position.y = edge.position.y - 2.0*curr_bubble.expansion;
01509     // get expansion on bubble at this point
01510     if(!calcObstacleKinematicDistance(edge, distance2))
01511     {
01512       ROS_DEBUG("Bubble %d probably at edge of map - cannot retrieve distance information to calculate external forces", bubble_num);
01513       // we cannot calculate external forces for this bubble - but still continue for the other bubbles
01514       return true;
01515     }
01516 
01517     // calculate difference-quotient (approx. of derivative) in x-direction
01518     if(curr_bubble.expansion <= tiny_bubble_expansion_)
01519     {
01520       // avoid division by (almost) zero to avoid numerical problems
01521       wrench.force.y = -external_force_gain_*(distance2 - distance1)/(2.0*tiny_bubble_expansion_);
01522       // actually we should never end up here - band should have been considered as broken
01523       ROS_DEBUG("Calculating external forces on broken band. Bubble should have been removed. Local Planner probably ill configured");
01524     }
01525     else
01526       wrench.force.y = -external_force_gain_*(distance2 - distance1)/(2.0*curr_bubble.expansion);
01527     // TODO above equations skip term to make forces continuous at end of influence region - test to add corresponsing term
01528 
01529 
01530     // no force in z-direction
01531     wrench.force.z = 0.0;
01532 
01533 
01534     // no torque around x and y axis
01535     wrench.torque.x = 0.0;
01536     wrench.torque.y = 0.0;
01537 
01538 
01539     // calculate delta-poses (on upper edge of bubble) for x-direction
01540     PoseToPose2D(curr_bubble.center.pose, edge_pose2D);
01541     edge_pose2D.theta = edge_pose2D.theta + (curr_bubble.expansion/getCircumscribedRadius(*costmap_ros_));
01542     edge_pose2D.theta = angles::normalize_angle(edge_pose2D.theta);
01543     PoseToPose2D(edge, edge_pose2D);
01544     // get expansion on bubble at this point
01545     if(!calcObstacleKinematicDistance(edge, distance1))
01546     {
01547       ROS_DEBUG("Bubble %d probably at edge of map - cannot retrieve distance information to calculate external forces", bubble_num);
01548       // we cannot calculate external forces for this bubble - but still continue for the other bubbles
01549       return true;
01550     }
01551     // calculate delta-poses (on lower edge of bubble) for x-direction
01552     edge_pose2D.theta = edge_pose2D.theta - 2.0*(curr_bubble.expansion/getCircumscribedRadius(*costmap_ros_));
01553     edge_pose2D.theta = angles::normalize_angle(edge_pose2D.theta);
01554     PoseToPose2D(edge, edge_pose2D);
01555     // get expansion on bubble at this point
01556     if(!calcObstacleKinematicDistance(edge, distance2))
01557     {
01558       ROS_DEBUG("Bubble %d probably at edge of map - cannot retrieve distance information to calculate external forces", bubble_num);
01559       // we cannot calculate external forces for this bubble - but still continue for the other bubbles
01560       return true;
01561     }
01562 
01563     // calculate difference-quotient (approx. of derivative) in x-direction
01564     if(curr_bubble.expansion <= tiny_bubble_expansion_)
01565     {
01566       // avoid division by (almost) zero to avoid numerical problems
01567       wrench.torque.z = -external_force_gain_*(distance2 - distance1)/(2.0*tiny_bubble_expansion_);
01568       // actually we should never end up here - band should have been considered as broken
01569       ROS_DEBUG("Calculating external forces on broken band. Bubble should have been removed. Local Planner probably ill configured");
01570     }
01571     else
01572       wrench.torque.z = -external_force_gain_*(distance2 - distance1)/(2.0*curr_bubble.expansion);
01573     // TODO above equations skip term to make forces continuous at end of influence region - test to add corresponsing term
01574 
01575 
01576 #ifdef DEBUG_EBAND_
01577     ROS_DEBUG("Calculating external forces: (x, y, theta) = (%f, %f, %f)", wrench.force.x, wrench.force.y, wrench.torque.z);
01578 #endif
01579 
01580     // assign wrench to forces vector
01581     forces.wrench = wrench;
01582 
01583     return true;
01584   }
01585 
01586 
01587   bool EBandPlanner::suppressTangentialForces(int bubble_num, std::vector<Bubble> band, geometry_msgs::WrenchStamped& forces)
01588   {
01589     //cycle over all bubbles except first and last (these are fixed)
01590     if(band.size() <= 2)
01591     {
01592       // nothing to do here -> we can stop right away - no forces calculated
01593       return true;
01594     }
01595 
01596     double scalar_fd, scalar_dd;
01597     geometry_msgs::Twist difference;
01598 
01599     // make sure this method was called for a valid element in the forces or bubbles vector
01600     ROS_ASSERT( bubble_num > 0 );
01601     ROS_ASSERT( bubble_num < ((int) band.size() - 1) );
01602 
01603 
01604     // get pose-difference from following to preceding bubble -> "direction of the band in this bubble"
01605     if(!calcBubbleDifference(band[bubble_num+1].center.pose, band[bubble_num-1].center.pose, difference))
01606       return false;
01607 
01608     // "project wrench" in middle bubble onto connecting vector
01609     // scalar wrench*difference
01610     scalar_fd = forces.wrench.force.x*difference.linear.x + forces.wrench.force.y*difference.linear.y +
01611       forces.wrench.force.z*difference.linear.z + forces.wrench.torque.x*difference.angular.x +
01612       forces.wrench.torque.y*difference.angular.y + forces.wrench.torque.z*difference.angular.z;
01613 
01614     // abs of difference-vector: scalar difference*difference
01615     scalar_dd = difference.linear.x*difference.linear.x + difference.linear.y*difference.linear.y + difference.linear.z*difference.linear.z +
01616       difference.angular.x*difference.angular.x + difference.angular.y*difference.angular.y + difference.angular.z*difference.angular.z;
01617 
01618     // avoid division by (almost) zero -> check if bubbles have (almost) same center-pose
01619     if(scalar_dd <= tiny_bubble_distance_)
01620     {
01621       // there are redundant bubbles, this should normally not hapen -> probably error in band refinement
01622       ROS_DEBUG("Calculating tangential forces for redundant bubbles. Bubble should have been removed. Local Planner probably ill configured");
01623     }
01624 
01625     // calculate orthogonal components
01626     forces.wrench.force.x = forces.wrench.force.x - scalar_fd/scalar_dd * difference.linear.x;
01627     forces.wrench.force.y = forces.wrench.force.y - scalar_fd/scalar_dd * difference.linear.y;
01628     forces.wrench.force.z = forces.wrench.force.z - scalar_fd/scalar_dd * difference.linear.z;
01629     forces.wrench.torque.x = forces.wrench.torque.x - scalar_fd/scalar_dd * difference.angular.x;
01630     forces.wrench.torque.y = forces.wrench.torque.y - scalar_fd/scalar_dd * difference.angular.y;
01631     forces.wrench.torque.z = forces.wrench.torque.z - scalar_fd/scalar_dd * difference.angular.z;
01632 
01633 #ifdef DEBUG_EBAND_
01634     ROS_DEBUG("Supressing tangential forces: (x, y, theta) = (%f, %f, %f)",
01635         forces.wrench.force.x, forces.wrench.force.y, forces.wrench.torque.z);
01636 #endif
01637 
01638     return true;
01639   }
01640 
01641 
01642   // problem (geometry) dependant functions
01643 
01644   bool EBandPlanner::interpolateBubbles(geometry_msgs::PoseStamped start_center, geometry_msgs::PoseStamped end_center, geometry_msgs::PoseStamped& interpolated_center)
01645   {
01646     // check if plugin initialized
01647     if(!initialized_)
01648     {
01649       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
01650       return false;
01651     }
01652 
01653     // instantiate local variables
01654     geometry_msgs::Pose2D start_pose2D, end_pose2D, interpolated_pose2D;
01655     double delta_theta;
01656 
01657     // copy header
01658     interpolated_center.header = start_center.header;
01659 
01660     // interpolate angles
01661     // TODO make this in a better way
01662     // - for instance use "slerp" to interpolate directly between quaternions
01663     // - or work with pose2D right from the beginnning
01664     // convert quaternions to euler angles - at this point this no longer works in 3D !!
01665     PoseToPose2D(start_center.pose, start_pose2D);
01666     PoseToPose2D(end_center.pose, end_pose2D);
01667     // calc mean of theta angle
01668     delta_theta = end_pose2D.theta - start_pose2D.theta;
01669     delta_theta = angles::normalize_angle(delta_theta) / 2.0;
01670     interpolated_pose2D.theta = start_pose2D.theta + delta_theta;
01671     interpolated_pose2D.theta = angles::normalize_angle(interpolated_pose2D.theta);
01672     // convert back to quaternion
01673     interpolated_pose2D.x = 0.0;
01674     interpolated_pose2D.y = 0.0;
01675     Pose2DToPose(interpolated_center.pose, interpolated_pose2D);
01676 
01677     // interpolate positions
01678     interpolated_center.pose.position.x = (end_center.pose.position.x + start_center.pose.position.x)/2.0;
01679     interpolated_center.pose.position.y = (end_center.pose.position.y + start_center.pose.position.y)/2.0;
01680     interpolated_center.pose.position.z = (end_center.pose.position.z + start_center.pose.position.z)/2.0;
01681 
01682     // TODO ideally this would take into account kinematics of the robot and for instance use splines
01683 
01684     return true;
01685   }
01686 
01687 
01688   bool EBandPlanner::checkOverlap(Bubble bubble1, Bubble bubble2)
01689   {
01690     // check if plugin initialized
01691     if(!initialized_)
01692     {
01693       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
01694       return false;
01695     }
01696 
01697     // calc (kinematic) Distance between bubbles
01698     double distance = 0.0;
01699     if(!calcBubbleDistance(bubble1.center.pose, bubble2.center.pose, distance))
01700     {
01701       ROS_ERROR("failed to calculate Distance between two bubbles. Aborting check for overlap!");
01702       return false;
01703     }
01704 
01705     // compare with size of the two bubbles
01706     if(distance >= min_bubble_overlap_ * (bubble1.expansion + bubble2.expansion))
01707       return false;
01708 
01709     // TODO this does not account for kinematic properties -> improve
01710 
01711     // everything fine - bubbles overlap
01712     return true;
01713   }
01714 
01715 
01716   bool EBandPlanner::calcBubbleDistance(geometry_msgs::Pose start_center_pose, geometry_msgs::Pose end_center_pose, double& distance)
01717   {
01718     // check if plugin initialized
01719     if(!initialized_)
01720     {
01721       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
01722       return false;
01723     }
01724 
01725     geometry_msgs::Pose2D start_pose2D, end_pose2D, diff_pose2D;
01726 
01727     // TODO make this in a better way
01728     // - or work with pose2D right from the beginnning
01729     // convert quaternions to euler angles - at this point this no longer works in 3D !!
01730     PoseToPose2D(start_center_pose, start_pose2D);
01731     PoseToPose2D(end_center_pose, end_pose2D);
01732 
01733     // get rotational difference
01734     diff_pose2D.theta = end_pose2D.theta - start_pose2D.theta;
01735     diff_pose2D.theta = angles::normalize_angle(diff_pose2D.theta);
01736     // get translational difference
01737     diff_pose2D.x = end_pose2D.x - start_pose2D.x;
01738     diff_pose2D.y = end_pose2D.y - start_pose2D.y;
01739 
01740     // calc distance
01741     double angle_to_pseudo_vel = diff_pose2D.theta * getCircumscribedRadius(*costmap_ros_);
01742     //distance = sqrt( (diff_pose2D.x * diff_pose2D.x) + (diff_pose2D.y * diff_pose2D.y) + (angle_to_pseudo_vel * angle_to_pseudo_vel) );
01743     distance = sqrt( (diff_pose2D.x * diff_pose2D.x) + (diff_pose2D.y * diff_pose2D.y));
01744 
01745     // TODO take into account kinematic properties of body
01746 
01747     return true;
01748   }
01749 
01750 
01751   bool EBandPlanner::calcBubbleDifference(geometry_msgs::Pose start_center_pose, geometry_msgs::Pose end_center_pose, geometry_msgs::Twist& difference)
01752   {
01753     // check if plugin initialized
01754     if(!initialized_)
01755     {
01756       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
01757       return false;
01758     }
01759 
01760     geometry_msgs::Pose2D start_pose2D, end_pose2D, diff_pose2D;
01761 
01762     // TODO make this in a better way
01763     // - or work with pose2D right from the beginnning
01764     // convert quaternions to euler angles - at this point this no longer works in 3D !!
01765     PoseToPose2D(start_center_pose, start_pose2D);
01766     PoseToPose2D(end_center_pose, end_pose2D);
01767 
01768     // get rotational difference
01769     diff_pose2D.theta = end_pose2D.theta - start_pose2D.theta;
01770     diff_pose2D.theta = angles::normalize_angle(diff_pose2D.theta);
01771     // get translational difference
01772     diff_pose2D.x = end_pose2D.x - start_pose2D.x;
01773     diff_pose2D.y = end_pose2D.y - start_pose2D.y;
01774 
01775     difference.linear.x = diff_pose2D.x;
01776     difference.linear.y = diff_pose2D.y;
01777     difference.linear.z = 0.0;
01778     // multiply by inscribed radius to math calculation of distance
01779     difference.angular.x = 0.0;
01780     difference.angular.y = 0.0;
01781     difference.angular.z = diff_pose2D.theta*getCircumscribedRadius(*costmap_ros_);
01782 
01783     // TODO take into account kinematic properties of body
01784 
01785     return true;
01786   }
01787 
01788 
01789   bool EBandPlanner::calcObstacleKinematicDistance(geometry_msgs::Pose center_pose, double& distance)
01790   {
01791     // calculate distance to nearest obstacle [depends kinematic, shape, environment]
01792 
01793     // check if plugin initialized
01794     if(!initialized_)
01795     {
01796       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
01797       return false;
01798     }
01799 
01800     unsigned int cell_x, cell_y;
01801     unsigned char disc_cost;
01802     double weight = costmap_weight_;
01803 
01804     // read distance to nearest obstacle directly from costmap
01805     // (does not take into account shape and kinematic properties)
01806     // get cell for coordinates of bubble center
01807     if(!costmap_->worldToMap(center_pose.position.x, center_pose.position.y, cell_x, cell_y)) {
01808       // probably at the edge of the costmap - this value should be recovered soon
01809       disc_cost = 1;
01810     } else {
01811       // get cost for this cell
01812       disc_cost = costmap_->getCost(cell_x, cell_y);
01813     }
01814 
01815     // calculate distance to nearest obstacel from this cost (see costmap_2d in wiki for details)
01816 
01817     // For reference: here comes an excerpt of the cost calculation within the costmap function
01818     /*if(distance == 0)
01819       cost = LETHAL_OBSTACLE;
01820       else if(distance <= cell_inscribed_radius_)
01821       cost = INSCRIBED_INFLATED_OBSTACLE;
01822       else {
01823     //make sure cost falls off by Euclidean distance
01824     double euclidean_distance = distance * resolution_;
01825     double factor = exp(-1.0 * weight_ * (euclidean_distance - inscribed_radius_));
01826     cost = (unsigned char) ((INSCRIBED_INFLATED_OBSTACLE - 1) * factor);
01827     }*/
01828 
01829     if (disc_cost == costmap_2d::LETHAL_OBSTACLE) {
01830       // pose is inside an obstacle - very bad
01831       distance = 0.0;
01832     }   else if (disc_cost == costmap_2d::INSCRIBED_INFLATED_OBSTACLE) {
01833       // footprint is definitely inside an obstacle - still bad
01834       distance = 0.0;
01835     } else {
01836       if (disc_cost == 0) { // freespace, no estimate of distance
01837         disc_cost = 1; // lowest non freespace cost
01838       } else if (disc_cost == 255) { // unknown space, we should never be here
01839         disc_cost = 1;
01840       }
01841       double factor = ((double) disc_cost) / (costmap_2d::INSCRIBED_INFLATED_OBSTACLE - 1);
01842       distance = -log(factor) / weight;
01843     }
01844 
01845     return true;
01846   }
01847 
01848 
01849   // type conversions
01850 
01851   bool EBandPlanner::convertPlanToBand(std::vector<geometry_msgs::PoseStamped> plan, std::vector<Bubble>& band)
01852   {
01853     // check if plugin initialized
01854     if(!initialized_)
01855     {
01856       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
01857       return false;
01858     }
01859 
01860     // create local variables
01861     double distance = 0.0;
01862     std::vector<Bubble> tmp_band;
01863 
01864     ROS_DEBUG("Copying plan to band - Conversion started: %d frames to convert.", ((int) plan.size()) );
01865 
01866     // get local copy of referenced variable
01867     tmp_band = band;
01868 
01869     // adapt band to plan
01870     tmp_band.resize(plan.size());
01871     for(int i = 0; i < ((int) plan.size()); i++)
01872     {
01873 #ifdef DEBUG_EBAND_
01874       ROS_DEBUG("Checking Frame %d of %d", i, ((int) plan.size()) );
01875 #endif
01876 
01877       // set poses in plan as centers of bubbles
01878       tmp_band[i].center = plan[i];
01879 
01880       // calc Size of Bubbles by calculating Dist to nearest Obstacle [depends kinematic, environment]
01881       if(!calcObstacleKinematicDistance(tmp_band[i].center.pose, distance))
01882       {
01883         // frame must not be immediately in collision -> otherwise calculation of gradient will later be invalid
01884         ROS_WARN("Calculation of Distance between bubble and nearest obstacle failed. Frame %d of %d outside map", i, ((int) plan.size()) );
01885         return false;
01886       }
01887 
01888       if(distance <= 0.0)
01889       {
01890         // frame must not be immediately in collision -> otherwise calculation of gradient will later be invalid
01891         ROS_WARN("Calculation of Distance between bubble and nearest obstacle failed. Frame %d of %d in collision. Plan invalid", i, ((int) plan.size()) );
01892         // TODO if frame in collision try to repair band instaed of aborting averything
01893         return false;
01894       }
01895 
01896 
01897       // assign to expansion of bubble
01898       tmp_band[i].expansion = distance;
01899     }
01900 
01901     // write to referenced variable
01902     band = tmp_band;
01903 
01904     ROS_DEBUG("Successfully converted plan to band");
01905     return true;
01906   }
01907 
01908 
01909   bool EBandPlanner::convertBandToPlan(std::vector<geometry_msgs::PoseStamped>& plan, std::vector<Bubble> band)
01910   {
01911     // check if plugin initialized
01912     if(!initialized_)
01913     {
01914       ROS_ERROR("This planner has not been initialized, please call initialize() before using this planner");
01915       return false;
01916     }
01917 
01918     // create local variables
01919     std::vector<geometry_msgs::PoseStamped> tmp_plan;
01920 
01921     // adapt plan to band
01922     tmp_plan.resize(band.size());
01923     for(int i = 0; i < ((int) band.size()); i++)
01924     {
01925       // set centers of bubbles to StampedPose in plan
01926       tmp_plan[i] = band[i].center;
01927     }
01928 
01929     //write to referenced variable and done
01930     plan = tmp_plan;
01931 
01932     return true;
01933   }
01934 
01935 
01936 }


eband_local_planner
Author(s): Christian Connette, Bhaskara Marthi, Piyush Khandelwal
autogenerated on Thu Jun 6 2019 18:50:52