homotopy_class_planner.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2016,
00006  *  TU Dortmund - Institute of Control Theory and Systems Engineering.
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of the institute nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * Author: Christoph Rösmann
00037  *********************************************************************/
00038 
00039 #include <teb_local_planner/homotopy_class_planner.h>
00040 
00041 namespace teb_local_planner
00042 {
00043   
00045 inline std::complex<long double> getCplxFromVertexPosePtr(const VertexPose* pose)
00046 {
00047   return std::complex<long double>(pose->x(), pose->y());
00048 };
00049 
00051 inline std::complex<long double> getCplxFromHcGraph(HcGraphVertexType vert_descriptor, const HcGraph& graph)
00052 {
00053   return std::complex<long double>(graph[vert_descriptor].pos.x(), graph[vert_descriptor].pos.y());
00054 };
00055   
00057 inline const Eigen::Vector2d& getVector2dFromHcGraph(HcGraphVertexType vert_descriptor, const HcGraph& graph)
00058 {
00059   return graph[vert_descriptor].pos;
00060 };
00061   
00063 inline std::complex<long double> getCplxFromMsgPoseStamped(const geometry_msgs::PoseStamped& pose)
00064 {
00065   return std::complex<long double>(pose.pose.position.x, pose.pose.position.y);
00066 };
00067 
00068 
00069 HomotopyClassPlanner::HomotopyClassPlanner() : obstacles_(NULL), via_points_(NULL),  cfg_(NULL), robot_model_(new PointRobotFootprint()),
00070                                                initial_plan_(NULL), initialized_(false)
00071 {
00072 }
00073   
00074 HomotopyClassPlanner::HomotopyClassPlanner(const TebConfig& cfg, ObstContainer* obstacles, RobotFootprintModelPtr robot_model,
00075                                            TebVisualizationPtr visual, const ViaPointContainer* via_points) : initial_plan_(NULL)
00076 {
00077   initialize(cfg, obstacles, robot_model, visual, via_points);
00078 }
00079 
00080 HomotopyClassPlanner::~HomotopyClassPlanner()
00081 {
00082 }
00083 
00084 void HomotopyClassPlanner::initialize(const TebConfig& cfg, ObstContainer* obstacles, RobotFootprintModelPtr robot_model,
00085                                       TebVisualizationPtr visual, const ViaPointContainer* via_points)
00086 {
00087   cfg_ = &cfg;
00088   obstacles_ = obstacles;
00089   via_points_ = via_points;
00090   robot_model_ = robot_model;
00091   initialized_ = true;
00092   
00093   setVisualization(visual);
00094 }
00095 
00096 
00097 void HomotopyClassPlanner::setVisualization(TebVisualizationPtr visualization)
00098 {
00099   visualization_ = visualization;
00100 }
00101 
00102 
00103  
00104 bool HomotopyClassPlanner::plan(const std::vector<geometry_msgs::PoseStamped>& initial_plan, const geometry_msgs::Twist* start_vel, bool free_goal_vel)
00105 {    
00106   ROS_ASSERT_MSG(initialized_, "Call initialize() first.");
00107   
00108   // store initial plan for further initializations (must be valid for the lifetime of this object or clearPlanner() is called!)
00109   initial_plan_ = &initial_plan;
00110   // store the h signature of the initial plan to enable searching a matching teb later.
00111   initial_plan_h_sig_ = calculateHSignature(initial_plan.begin(), initial_plan.end(), getCplxFromMsgPoseStamped, obstacles_, cfg_->hcp.h_signature_prescaler);
00112     
00113   PoseSE2 start(initial_plan.front().pose);
00114   PoseSE2 goal(initial_plan.back().pose);
00115   Eigen::Vector2d vel = start_vel ?  Eigen::Vector2d( start_vel->linear.x, start_vel->angular.z ) : Eigen::Vector2d::Zero();
00116   return plan(start, goal, vel, free_goal_vel);
00117 }
00118 
00119 
00120 bool HomotopyClassPlanner::plan(const tf::Pose& start, const tf::Pose& goal, const geometry_msgs::Twist* start_vel, bool free_goal_vel)
00121 {
00122   ROS_ASSERT_MSG(initialized_, "Call initialize() first.");
00123   PoseSE2 start_pose(start);
00124   PoseSE2 goal_pose(goal);
00125   Eigen::Vector2d vel = start_vel ?  Eigen::Vector2d( start_vel->linear.x, start_vel->angular.z ) : Eigen::Vector2d::Zero();
00126   return plan(start_pose, goal_pose, vel, free_goal_vel);
00127 }
00128 
00129 bool HomotopyClassPlanner::plan(const PoseSE2& start, const PoseSE2& goal, const Eigen::Vector2d& start_vel, bool free_goal_vel)
00130 {       
00131   ROS_ASSERT_MSG(initialized_, "Call initialize() first.");
00132   
00133   // Update old TEBs with new start, goal and velocity
00134   updateAllTEBs(start, goal, start_vel);
00135     
00136   // Init new TEBs based on newly explored homotopy classes
00137   exploreHomotopyClassesAndInitTebs(start, goal, cfg_->obstacles.min_obstacle_dist, start_vel);
00138   // update via-points if activated
00139   updateReferenceTrajectoryViaPoints(cfg_->hcp.viapoints_all_candidates);
00140   // Optimize all trajectories in alternative homotopy classes
00141   optimizeAllTEBs(cfg_->optim.no_inner_iterations, cfg_->optim.no_outer_iterations);
00142   // Delete any detours
00143   deleteTebDetours(-0.1); 
00144   // Select which candidate (based on alternative homotopy classes) should be used
00145   selectBestTeb();
00146 
00147   initial_plan_ = NULL; // clear pointer to any previous initial plan (any previous plan is useless regarding the h-signature);
00148   return true;
00149 } 
00150  
00151 bool HomotopyClassPlanner::getVelocityCommand(double& v, double& omega) const
00152 {
00153   TebOptimalPlannerConstPtr best_teb = bestTeb();
00154   if (!best_teb)
00155   {
00156     v = 0;
00157     omega = 0;
00158     return false;
00159   }
00160  
00161   return best_teb->getVelocityCommand(v, omega); 
00162 }
00163 
00164 
00165 
00166 
00167 void HomotopyClassPlanner::visualize()
00168 {
00169   if (visualization_)
00170   {
00171     // Visualize graph
00172     if (cfg_->hcp.visualize_hc_graph)
00173       visualization_->publishGraph(graph_);
00174         
00175     // Visualize active tebs as marker
00176     visualization_->publishTebContainer(tebs_);
00177     
00178     // Visualize best teb and feedback message if desired
00179     TebOptimalPlannerConstPtr best_teb = bestTeb();
00180     if (best_teb)
00181     {
00182       visualization_->publishLocalPlanAndPoses(best_teb->teb());
00183       
00184       if (best_teb->teb().sizePoses() > 0) //TODO maybe store current pose (start) within plan method as class field.
00185         visualization_->publishRobotFootprintModel(best_teb->teb().Pose(0), *robot_model_);
00186     
00187       // feedback message
00188       if (cfg_->trajectory.publish_feedback)
00189       {
00190         int best_idx = bestTebIdx();
00191         if (best_idx>=0)
00192           visualization_->publishFeedbackMessage(tebs_, (unsigned int) best_idx, *obstacles_);
00193       }
00194     }
00195   }
00196   else ROS_DEBUG("Ignoring HomotopyClassPlanner::visualize() call, since no visualization class was instantiated before.");
00197 }
00198 
00199 
00200 
00201 
00202 void HomotopyClassPlanner::createGraph(const PoseSE2& start, const PoseSE2& goal, double dist_to_obst, double obstacle_heading_threshold, boost::optional<const Eigen::Vector2d&> start_velocity)
00203 {
00204   // Clear existing graph and paths
00205   clearGraph();
00206   
00207   // Direction-vector between start and goal and normal-vector:
00208   Eigen::Vector2d diff = goal.position()-start.position();
00209   
00210   if (diff.norm()<cfg_->goal_tolerance.xy_goal_tolerance) 
00211   {
00212     ROS_DEBUG("HomotopyClassPlanner::createProbRoadmapGraph(): xy-goal-tolerance already reached.");
00213     if (tebs_.empty())
00214     {
00215       ROS_INFO("HomotopyClassPlanner::createProbRoadmapGraph(): Initializing a small straight line to just correct orientation errors.");
00216       addAndInitNewTeb(start, goal, start_velocity);
00217     }
00218     return;
00219   }
00220   
00221   Eigen::Vector2d normal(-diff[1],diff[0]); // normal-vector
00222   normal.normalize();
00223   normal = normal*dist_to_obst; // scale with obstacle_distance;
00224   
00225   // Insert Vertices
00226   HcGraphVertexType start_vtx = boost::add_vertex(graph_); // start vertex
00227   graph_[start_vtx].pos = start.position();
00228   diff.normalize();
00229   
00230   // store nearest obstacle keypoints -> only used if limit_obstacle_heading is enabled
00231   std::pair<HcGraphVertexType,HcGraphVertexType> nearest_obstacle; // both vertices are stored
00232   double min_dist = DBL_MAX;
00233   
00234   if (obstacles_!=NULL)
00235   {
00236     for (ObstContainer::const_iterator it_obst = obstacles_->begin(); it_obst != obstacles_->end(); ++it_obst)
00237     {
00238       // check if obstacle is placed in front of start point
00239       Eigen::Vector2d start2obst = (*it_obst)->getCentroid() - start.position();
00240       double dist = start2obst.norm();
00241       if (start2obst.dot(diff)/dist<0.1)
00242         continue;
00243       
00244       // Add Keypoints  
00245       HcGraphVertexType u = boost::add_vertex(graph_);
00246       graph_[u].pos = (*it_obst)->getCentroid() + normal;
00247       HcGraphVertexType v = boost::add_vertex(graph_);
00248       graph_[v].pos = (*it_obst)->getCentroid() - normal;
00249       
00250       // store nearest obstacle
00251       if (obstacle_heading_threshold && dist<min_dist)
00252       {
00253         min_dist = dist;
00254         nearest_obstacle.first = u;
00255         nearest_obstacle.second = v;
00256       }
00257     }   
00258   }
00259   
00260   HcGraphVertexType goal_vtx = boost::add_vertex(graph_); // goal vertex
00261   graph_[goal_vtx].pos = goal.position();
00262   
00263   // Insert Edges
00264   HcGraphVertexIterator it_i, end_i, it_j, end_j;
00265   for (boost::tie(it_i,end_i) = boost::vertices(graph_); it_i!=end_i-1; ++it_i) // ignore goal in this loop
00266   {
00267     for (boost::tie(it_j,end_j) = boost::vertices(graph_); it_j!=end_j; ++it_j) // check all forward connections
00268     {
00269       if (it_i==it_j) 
00270         continue;
00271       // TODO: make use of knowing in which order obstacles are inserted and that for each obstacle 2 vertices are added,
00272       // therefore we must only check one of them.
00273       Eigen::Vector2d distij = graph_[*it_j].pos-graph_[*it_i].pos;
00274       distij.normalize();
00275       // Check if the direction is backwards:
00276       if (distij.dot(diff)<=obstacle_heading_threshold)
00277         continue;
00278 
00279     
00280       // Check start angle to nearest obstacle 
00281       if (obstacle_heading_threshold && *it_i==start_vtx && min_dist!=DBL_MAX)
00282       {
00283         if (*it_j == nearest_obstacle.first || *it_j == nearest_obstacle.second)
00284         {
00285           Eigen::Vector2d keypoint_dist = graph_[*it_j].pos-start.position();
00286           keypoint_dist.normalize();
00287           Eigen::Vector2d start_orient_vec( cos(start.theta()), sin(start.theta()) ); // already normalized
00288           // check angle
00289           if (start_orient_vec.dot(keypoint_dist) <= obstacle_heading_threshold) 
00290           {
00291             ROS_DEBUG("createGraph() - deleted edge: limit_obstacle_heading");
00292             continue;
00293           }
00294         }
00295       }
00296 
00297       // Collision Check
00298       
00299       if (obstacles_!=NULL)
00300       {
00301         bool collision = false;
00302         for (ObstContainer::const_iterator it_obst = obstacles_->begin(); it_obst != obstacles_->end(); ++it_obst)
00303         {
00304           if ( (*it_obst)->checkLineIntersection(graph_[*it_i].pos,graph_[*it_j].pos, 0.5*dist_to_obst) ) 
00305           {
00306             collision = true;
00307             break;
00308           }
00309         }
00310         if (collision) 
00311           continue;
00312       }
00313       
00314       // Create Edge
00315       boost::add_edge(*it_i,*it_j,graph_);                      
00316     }
00317   }
00318   
00319    
00320   // Find all paths between start and goal!
00321   std::vector<HcGraphVertexType> visited;
00322   visited.push_back(start_vtx);
00323   DepthFirst(graph_,visited,goal_vtx, start.theta(), goal.theta(), start_velocity);
00324 }
00325 
00326 
00327 void HomotopyClassPlanner::createProbRoadmapGraph(const PoseSE2& start, const PoseSE2& goal, double dist_to_obst, int no_samples,
00328                                                   double obstacle_heading_threshold, boost::optional<const Eigen::Vector2d&> start_velocity)
00329 {
00330   // Clear existing graph and paths
00331   clearGraph();
00332   
00333   // Direction-vector between start and goal and normal-vector:
00334   Eigen::Vector2d diff = goal.position()-start.position();
00335   double start_goal_dist = diff.norm();
00336   
00337   if (start_goal_dist<cfg_->goal_tolerance.xy_goal_tolerance) 
00338   {
00339     ROS_DEBUG("HomotopyClassPlanner::createProbRoadmapGraph(): xy-goal-tolerance already reached.");
00340     if (tebs_.empty())
00341     {
00342       ROS_INFO("HomotopyClassPlanner::createProbRoadmapGraph(): Initializing a small straight line to just correct orientation errors.");
00343       addAndInitNewTeb(start, goal, start_velocity);
00344     }
00345     return;
00346   }
00347   Eigen::Vector2d normal(-diff.coeffRef(1),diff.coeffRef(0)); // normal-vector
00348   normal.normalize();
00349 
00350   // Now sample vertices between start, goal and a specified width between both sides
00351   // Let's start with a square area between start and goal (maybe change it later to something like a circle or whatever)
00352   
00353   double area_width = cfg_->hcp.roadmap_graph_area_width;
00354     
00355   boost::random::uniform_real_distribution<double> distribution_x(0, start_goal_dist);  
00356   boost::random::uniform_real_distribution<double> distribution_y(0, area_width); 
00357   
00358   double phi = atan2(diff.coeffRef(1),diff.coeffRef(0)); // rotate area by this angle
00359   Eigen::Rotation2D<double> rot_phi(phi);
00360   
00361   Eigen::Vector2d area_origin = start.position() - 0.5*area_width*normal; // bottom left corner of the origin
00362   
00363   // Insert Vertices
00364   HcGraphVertexType start_vtx = boost::add_vertex(graph_); // start vertex
00365   graph_[start_vtx].pos = start.position();
00366   diff.normalize(); // normalize in place
00367   
00368   
00369   // Start sampling
00370   for (int i=0; i < no_samples; ++i)
00371   {
00372     Eigen::Vector2d sample;
00373 //     bool coll_free;
00374 //     do // sample as long as a collision free sample is found
00375 //     {
00376       // Sample coordinates
00377       sample = area_origin + rot_phi*Eigen::Vector2d(distribution_x(rnd_generator_), distribution_y(rnd_generator_));
00378       
00379       // Test for collision
00380       // we do not care for collision checking here to improve efficiency, since we perform resampling repeatedly.
00381       // occupied vertices are ignored in the edge insertion state since they always violate the edge-obstacle collision check.
00382 //       coll_free = true;
00383 //       for (ObstContainer::const_iterator it_obst = obstacles_->begin(); it_obst != obstacles_->end(); ++it_obst)
00384 //       {
00385 //         if ( (*it_obst)->checkCollision(sample, dist_to_obst)) // TODO really keep dist_to_obst here?
00386 //         {
00387 //           coll_free = false;
00388 //           break;
00389 //         }
00390 //       }
00391 // 
00392 //     } while (!coll_free && ros::ok());
00393     
00394     // Add new vertex
00395     HcGraphVertexType v = boost::add_vertex(graph_);
00396     graph_[v].pos = sample;
00397   }
00398   
00399   // Now add goal vertex
00400   HcGraphVertexType goal_vtx = boost::add_vertex(graph_); // goal vertex
00401   graph_[goal_vtx].pos = goal.position();
00402   
00403   
00404   // Insert Edges
00405   HcGraphVertexIterator it_i, end_i, it_j, end_j;
00406   for (boost::tie(it_i,end_i) = boost::vertices(graph_); it_i!=boost::prior(end_i); ++it_i) // ignore goal in this loop
00407   {
00408     for (boost::tie(it_j,end_j) = boost::vertices(graph_); it_j!=end_j; ++it_j) // check all forward connections
00409     {
00410       if (it_i==it_j) // same vertex found
00411         continue;
00412 
00413       Eigen::Vector2d distij = graph_[*it_j].pos-graph_[*it_i].pos;
00414       distij.normalize(); // normalize in place
00415 
00416       // Check if the direction is backwards:
00417       if (distij.dot(diff)<=obstacle_heading_threshold) 
00418           continue; // diff is already normalized
00419       
00420 
00421       // Collision Check        
00422       bool collision = false;
00423       for (ObstContainer::const_iterator it_obst = obstacles_->begin(); it_obst != obstacles_->end(); ++it_obst)
00424       {
00425         if ( (*it_obst)->checkLineIntersection(graph_[*it_i].pos,graph_[*it_j].pos, dist_to_obst) )
00426         {
00427           collision = true;
00428           break;
00429         }
00430       }
00431       if (collision)
00432         continue;
00433       
00434       // Create Edge
00435       boost::add_edge(*it_i,*it_j,graph_);                      
00436     }
00437   }
00438   
00440   std::vector<HcGraphVertexType> visited;
00441   visited.push_back(start_vtx);
00442   DepthFirst(graph_,visited,goal_vtx, start.theta(), goal.theta(), start_velocity);
00443 }
00444 
00445 
00446 void HomotopyClassPlanner::DepthFirst(HcGraph& g, std::vector<HcGraphVertexType>& visited, const HcGraphVertexType& goal,
00447                                       double start_orientation, double goal_orientation, boost::optional<const Eigen::Vector2d&> start_velocity)
00448 {
00449   // see http://www.technical-recipes.com/2011/a-recursive-algorithm-to-find-all-paths-between-two-given-nodes/ for details on finding all simple paths
00450   
00451   if ((int)tebs_.size() >= cfg_->hcp.max_number_classes)
00452     return; // We do not need to search for further possible alternative homotopy classes.
00453   
00454   HcGraphVertexType back = visited.back();
00455 
00457   HcGraphAdjecencyIterator it, end;
00458   for ( boost::tie(it,end) = boost::adjacent_vertices(back,g); it!=end; ++it)
00459   {
00460     if ( std::find(visited.begin(), visited.end(), *it)!=visited.end() )
00461       continue; // already visited
00462 
00463     if ( *it == goal ) // goal reached
00464     {
00465       visited.push_back(*it);
00466       
00467       
00468       // check H-Signature
00469       std::complex<long double> H = calculateHSignature(visited.begin(), visited.end(), boost::bind(getCplxFromHcGraph, _1, boost::cref(graph_)), obstacles_, cfg_->hcp.h_signature_prescaler);
00470       
00471       // check if H-Signature is already known
00472       // and init new TEB if no duplicate was found
00473       if ( addHSignatureIfNew(H) )
00474       {
00475         addAndInitNewTeb(visited.begin(), visited.end(), boost::bind(getVector2dFromHcGraph, _1, boost::cref(graph_)), start_orientation, goal_orientation, start_velocity);
00476       }
00477       
00478       visited.pop_back();
00479       break;
00480     }
00481 }
00482 
00484 for ( boost::tie(it,end) = boost::adjacent_vertices(back,g); it!=end; ++it)
00485 {
00486   if ( std::find(visited.begin(), visited.end(), *it)!=visited.end() || *it == goal)
00487     continue; // already visited || goal reached
00488   
00489   
00490   visited.push_back(*it);
00491   
00492   // recursion step
00493   DepthFirst(g, visited, goal, start_orientation, goal_orientation, start_velocity);
00494   
00495   visited.pop_back();
00496 }
00497 }
00498  
00499  
00500 bool HomotopyClassPlanner::hasHSignature(const std::complex<long double>& H) const
00501 {
00502   // iterate existing h-signatures and check if there is an existing H-Signature similar the candidate
00503   for (std::vector< std::pair<std::complex<long double>, bool> >::const_iterator it = h_signatures_.begin(); it != h_signatures_.end(); ++it)
00504   {
00505     if (isHSignatureSimilar(it->first, H, cfg_->hcp.h_signature_threshold))
00506       return true; // Found! Homotopy class already exists, therefore nothing added  
00507   }
00508   return false;
00509 }
00510 
00511 bool HomotopyClassPlanner::addHSignatureIfNew(const std::complex<long double>& H, bool lock)
00512 {         
00513   if (!std::isfinite(H.real()) || !std::isfinite(H.imag()))
00514   {
00515     ROS_WARN("HomotopyClassPlanner: Ignoring nan/inf H-signature");
00516     return false;
00517   }
00518   
00519   if (hasHSignature(H))
00520     return false;
00521 
00522   // Homotopy class not found -> Add to class-list, return that the h-signature is new
00523   h_signatures_.push_back(std::make_pair(H,lock));       
00524   return true;
00525 }
00526  
00527  
00528 
00529   
00531 inline bool compareH( std::pair<TebOptPlannerContainer::iterator, std::complex<long double> > i, std::complex<long double> j ) {return std::abs(i.second.real()-j.real())<0.1 && std::abs(i.second.imag()-j.imag())<0.1;};
00532  
00533 
00534 void HomotopyClassPlanner::renewAndAnalyzeOldTebs(bool delete_detours)
00535 {
00536   // clear old h-signatures (since they could be changed due to new obstacle positions.
00537   h_signatures_.clear();
00538 
00539   // Collect h-signatures for all existing TEBs and store them together with the corresponding iterator / pointer:
00540 //   typedef std::list< std::pair<TebOptPlannerContainer::iterator, std::complex<long double> > > TebCandidateType;
00541 //   TebCandidateType teb_candidates;
00542 
00543   // get new homotopy classes and delete multiple TEBs per homotopy class
00544   TebOptPlannerContainer::iterator it_teb = tebs_.begin();
00545   while(it_teb != tebs_.end())
00546   {
00547     // delete Detours if there is at least one other TEB candidate left in the container
00548     if (delete_detours && tebs_.size()>1 && it_teb->get()->teb().detectDetoursBackwards(-0.1)) 
00549     {
00550       it_teb = tebs_.erase(it_teb); // delete candidate and set iterator to the next valid candidate
00551       continue;
00552     }
00553 
00554     // calculate H Signature for the current candidate
00555     std::complex<long double> H = calculateHSignature(it_teb->get()->teb().poses().begin(), it_teb->get()->teb().poses().end(), getCplxFromVertexPosePtr ,obstacles_, cfg_->hcp.h_signature_prescaler);
00556     
00557 //     teb_candidates.push_back(std::make_pair(it_teb,H));
00558     
00559     // WORKAROUND until the commented code below works
00560     // Here we do not compare cost values. Just first come first serve...
00561     bool new_flag = addHSignatureIfNew(H);
00562     if (!new_flag)
00563     {
00564       it_teb = tebs_.erase(it_teb);
00565       continue;
00566     }
00567     
00568     ++it_teb;
00569   }
00570 
00571   // Find multiple candidates and delete the one with higher cost 
00572   // TODO: this code needs to be adpated. Erasing tebs from the teb container_ could make iteratores stored in the candidate list invalid!
00573 //   TebCandidateType::reverse_iterator cand_i = teb_candidates.rbegin();
00574 //   int test_idx = 0;
00575 //   while (cand_i != teb_candidates.rend())
00576 //   {
00577 //          
00578 //     TebCandidateType::reverse_iterator cand_j = std::find_if(boost::next(cand_i),teb_candidates.rend(), boost::bind(compareH,_1,cand_i->second));
00579 //     if (cand_j != teb_candidates.rend() && cand_j != cand_i)
00580 //     {
00581 //         TebOptimalPlannerPtr pt1 = *(cand_j->first);
00582 //         TebOptimalPlannerPtr pt2 = *(cand_i->first);
00583 //         assert(pt1);
00584 //         assert(pt2);
00585 //       if ( cand_j->first->get()->getCurrentCost().sum() > cand_i->first->get()->getCurrentCost().sum() )
00586 //       {
00587 //      // found one that has higher cost, therefore erase cand_j
00588 //      tebs_.erase(cand_j->first);
00589 //      teb_candidates.erase(cand_j);         
00590 //       }
00591 //       else   // otherwise erase cand_i
00592 //       {
00593 //      tebs_.erase(cand_i->first);
00594 //      cand_i = teb_candidates.erase(cand_i);
00595 //       }
00596 //     }
00597 //     else 
00598 //     {
00599 //         ROS_WARN_STREAM("increase cand_i");
00600 //         ++cand_i;    
00601 //     }
00602 //   }
00603   
00604   // now add the h-signatures to the internal lookup-table (but only if there is no existing duplicate)
00605 //   for (TebCandidateType::iterator cand=teb_candidates.begin(); cand!=teb_candidates.end(); ++cand)
00606 //   {
00607 //     bool new_flag = addNewHSignatureIfNew(cand->second, cfg_->hcp.h_signature_threshold);
00608 //     if (!new_flag)
00609 //     {
00610 // //       ROS_ERROR_STREAM("getAndFilterHomotopyClassesTEB() - This schould not be happen.");
00611 //       tebs_.erase(cand->first);
00612 //     }
00613 //   }
00614         
00615 }
00616  
00617 void HomotopyClassPlanner::updateReferenceTrajectoryViaPoints(bool all_trajectories)
00618 {
00619   if ( (!all_trajectories && !initial_plan_) || !via_points_ || via_points_->empty() || cfg_->optim.weight_viapoint <= 0)
00620     return;
00621   
00622   if(h_signatures_.size() < tebs_.size())
00623   {
00624     ROS_ERROR("HomotopyClassPlanner::updateReferenceTrajectoryWithViaPoints(): Number of h-signatures does not match number of trajectories.");
00625     return;
00626   }
00627   
00628   if (all_trajectories)
00629   {
00630     // enable via-points for all tebs
00631     for (std::size_t i=0; i < h_signatures_.size(); ++i)
00632     {
00633         tebs_[i]->setViaPoints(via_points_);
00634     }
00635   }
00636   else
00637   {
00638     // enable via-points for teb in the same hommotopy class as the initial_plan and deactivate it for all other ones
00639     for (std::size_t i=0; i < h_signatures_.size(); ++i)
00640     {
00641       if (isHSignatureSimilar(h_signatures_[i].first, initial_plan_h_sig_, cfg_->hcp.h_signature_threshold))
00642         tebs_[i]->setViaPoints(via_points_);
00643       else
00644         tebs_[i]->setViaPoints(NULL);
00645     }
00646   }
00647 }
00648  
00649  
00650 void HomotopyClassPlanner::exploreHomotopyClassesAndInitTebs(const PoseSE2& start, const PoseSE2& goal, double dist_to_obst, boost::optional<const Eigen::Vector2d&> start_vel)
00651 {
00652   // first process old trajectories
00653   renewAndAnalyzeOldTebs(false);
00654 
00655   // inject initial plan if available and not yet captured
00656   if (initial_plan_ && addHSignatureIfNew(initial_plan_h_sig_, true)) // also prevent candidate from deletion
00657     addAndInitNewTeb(*initial_plan_, start_vel);
00658     
00659   // now explore new homotopy classes and initialize tebs if new ones are found.
00660   if (cfg_->hcp.simple_exploration)
00661     createGraph(start,goal,dist_to_obst,cfg_->hcp.obstacle_heading_threshold, start_vel);
00662   else
00663     createProbRoadmapGraph(start,goal,dist_to_obst,cfg_->hcp.roadmap_graph_no_samples,cfg_->hcp.obstacle_heading_threshold, start_vel);
00664 } 
00665 
00666 
00667 void HomotopyClassPlanner::addAndInitNewTeb(const PoseSE2& start, const PoseSE2& goal, boost::optional<const Eigen::Vector2d&> start_velocity)
00668 {
00669   tebs_.push_back( TebOptimalPlannerPtr( new TebOptimalPlanner(*cfg_, obstacles_, robot_model_) ) );
00670   tebs_.back()->teb().initTEBtoGoal(start, goal, 0, cfg_->trajectory.dt_ref, cfg_->trajectory.min_samples);
00671   
00672   if (start_velocity)
00673     tebs_.back()->setVelocityStart(*start_velocity);
00674 }
00675 
00676 void HomotopyClassPlanner::addAndInitNewTeb(const std::vector<geometry_msgs::PoseStamped>& initial_plan, boost::optional<const Eigen::Vector2d&> start_velocity)
00677 {
00678   tebs_.push_back( TebOptimalPlannerPtr( new TebOptimalPlanner(*cfg_, obstacles_, robot_model_) ) );
00679   tebs_.back()->teb().initTEBtoGoal(*initial_plan_, cfg_->trajectory.dt_ref, true, cfg_->trajectory.min_samples); 
00680   
00681   if (start_velocity)
00682     tebs_.back()->setVelocityStart(*start_velocity);
00683 }
00684 
00685 void HomotopyClassPlanner::updateAllTEBs(boost::optional<const PoseSE2&> start, boost::optional<const PoseSE2&> goal,  boost::optional<const Eigen::Vector2d&> start_velocity)
00686 {
00687   // If new goal is too far away, clear all existing trajectories to let them reinitialize later.
00688   // Since all Tebs are sharing the same fixed goal pose, just take the first candidate:
00689   if (!tebs_.empty() && (goal->position() - tebs_.front()->teb().BackPose().position()).norm() >= cfg_->trajectory.force_reinit_new_goal_dist)
00690   {
00691       ROS_DEBUG("New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories.");
00692       tebs_.clear();
00693       h_signatures_.clear();
00694   }  
00695   
00696   // hot-start from previous solutions
00697   for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb)
00698   {
00699     it_teb->get()->teb().updateAndPruneTEB(start, goal);
00700     if (start_velocity)
00701       it_teb->get()->setVelocityStart(*start_velocity);
00702   }
00703 }
00704 
00705  
00706 void HomotopyClassPlanner::optimizeAllTEBs(unsigned int iter_innerloop, unsigned int iter_outerloop)
00707 {
00708   // optimize TEBs in parallel since they are independend of each other
00709   if (cfg_->hcp.enable_multithreading)
00710   {
00711     boost::thread_group teb_threads;
00712     for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb)
00713     {
00714       teb_threads.create_thread( boost::bind(&TebOptimalPlanner::optimizeTEB, it_teb->get(), iter_innerloop, iter_outerloop,
00715                                              true, cfg_->hcp.selection_obst_cost_scale, cfg_->hcp.selection_viapoint_cost_scale,
00716                                              cfg_->hcp.selection_alternative_time_cost) );
00717     }
00718     teb_threads.join_all();
00719   }
00720   else
00721   {
00722     for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb)
00723     {
00724       it_teb->get()->optimizeTEB(iter_innerloop,iter_outerloop, true, cfg_->hcp.selection_obst_cost_scale, 
00725                                  cfg_->hcp.selection_viapoint_cost_scale, cfg_->hcp.selection_alternative_time_cost); // compute cost as well inside optimizeTEB (last argument = true)
00726     }
00727   }
00728 } 
00729  
00730 void HomotopyClassPlanner::deleteTebDetours(double threshold)
00731 {
00732   TebOptPlannerContainer::iterator it_teb = tebs_.begin();
00733   bool modified;
00734   int h_idx = 0; // keep track about the current h-signature idx
00735   while(it_teb != tebs_.end())
00736   { 
00737     modified = false;
00738     
00739     if (!h_signatures_[h_idx].second) // check if h-signature is locked
00740     {
00741       // delete Detours if other TEBs will remain!
00742       if (tebs_.size()>1 && it_teb->get()->teb().detectDetoursBackwards(threshold))
00743       {
00744         it_teb = tebs_.erase(it_teb); // 0.05
00745         modified = true;
00746       }
00747     }
00748     
00749     // Also delete tebs that cannot be optimized (last optim call failed)
00750     // here, we ignore the lock-state, since we cannot keep trajectories that are not optimizable
00751     if (!it_teb->get()->isOptimized())
00752     {
00753         it_teb = tebs_.erase(it_teb);
00754         modified = true;      
00755     }  
00756     
00757     if (!modified)
00758        ++it_teb;
00759     
00760     ++h_idx;
00761   }
00762 } 
00763  
00764  
00765 TebOptimalPlannerPtr HomotopyClassPlanner::selectBestTeb()
00766 {
00767   double min_cost = std::numeric_limits<double>::max(); // maximum cost
00768   
00769   // check if last best_teb is still a valid candidate
00770   if (std::find(tebs_.begin(), tebs_.end(), best_teb_) != tebs_.end())
00771   {
00772     // get cost of this candidate
00773     min_cost = best_teb_->getCurrentCost() * cfg_->hcp.selection_cost_hysteresis; // small hysteresis
00774   }
00775   else // the last candidate is not valid anymore
00776     best_teb_.reset(); // reset pointer
00777 
00778   for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb)
00779   {
00780     if (*it_teb == best_teb_)
00781       continue; // skip already known cost value of the last best_teb
00782     
00783     double teb_cost = it_teb->get()->getCurrentCost();
00784 
00785     if (teb_cost < min_cost)
00786     {
00787       // check if this candidate is currently not selected
00788       best_teb_ = *it_teb;
00789       min_cost = teb_cost;
00790     }
00791   }     
00792   return best_teb_;
00793 } 
00794 
00795 int HomotopyClassPlanner::bestTebIdx() const
00796 {
00797   if (tebs_.size() == 1)
00798     return 0;
00799     
00800   if (!best_teb_)
00801     return -1;
00802   
00803   int idx = 0;
00804   for (TebOptPlannerContainer::const_iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb, ++idx)
00805   {
00806     if (*it_teb == best_teb_)
00807       return idx;
00808   }
00809   return -1;  
00810 }
00811 
00812 bool HomotopyClassPlanner::isTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector<geometry_msgs::Point>& footprint_spec,
00813                                                 double inscribed_radius, double circumscribed_radius, int look_ahead_idx)
00814 {
00815   TebOptimalPlannerPtr best = bestTeb();
00816   if (!best)
00817     return false;
00818   
00819   return best->isTrajectoryFeasible(costmap_model,footprint_spec, inscribed_radius, circumscribed_radius, look_ahead_idx);
00820 }
00821 
00822 bool HomotopyClassPlanner::isHorizonReductionAppropriate(const std::vector<geometry_msgs::PoseStamped>& initial_plan) const
00823 {
00824   TebOptimalPlannerPtr best = bestTeb();
00825   if (!best)
00826     return false;
00827   
00828   return best->isHorizonReductionAppropriate(initial_plan);
00829 }
00830 
00831 void HomotopyClassPlanner::computeCurrentCost(std::vector<double>& cost, double obst_cost_scale, double viapoint_cost_scale, bool alternative_time_cost)
00832 {
00833   for (TebOptPlannerContainer::iterator it_teb = tebs_.begin(); it_teb != tebs_.end(); ++it_teb)
00834   {
00835     it_teb->get()->computeCurrentCost(cost, obst_cost_scale, viapoint_cost_scale, alternative_time_cost);
00836   } 
00837 }
00838  
00839  
00840 } // end namespace


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Mon Oct 24 2016 05:31:15