optimal_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/optimal_planner.h>
00040 
00041 
00042 namespace teb_local_planner
00043 {
00044 
00045 // ============== Implementation ===================
00046 
00047 TebOptimalPlanner::TebOptimalPlanner() : cfg_(NULL), obstacles_(NULL), via_points_(NULL), cost_(HUGE_VAL), robot_model_(new PointRobotFootprint()), initialized_(false), optimized_(false)
00048 {    
00049 }
00050   
00051 TebOptimalPlanner::TebOptimalPlanner(const TebConfig& cfg, ObstContainer* obstacles, RobotFootprintModelPtr robot_model, TebVisualizationPtr visual, const ViaPointContainer* via_points)
00052 {    
00053   initialize(cfg, obstacles, robot_model, visual, via_points);
00054 }
00055 
00056 TebOptimalPlanner::~TebOptimalPlanner()
00057 {
00058   clearGraph();
00059   // free dynamically allocated memory
00060   //if (optimizer_) 
00061   //  g2o::Factory::destroy();
00062   //g2o::OptimizationAlgorithmFactory::destroy();
00063   //g2o::HyperGraphActionLibrary::destroy();
00064 }
00065 
00066 void TebOptimalPlanner::initialize(const TebConfig& cfg, ObstContainer* obstacles, RobotFootprintModelPtr robot_model, TebVisualizationPtr visual, const ViaPointContainer* via_points)
00067 {    
00068   // init optimizer (set solver and block ordering settings)
00069   optimizer_ = initOptimizer();
00070   
00071   cfg_ = &cfg;
00072   obstacles_ = obstacles;
00073   robot_model_ = robot_model;
00074   via_points_ = via_points;
00075   cost_ = HUGE_VAL;
00076   setVisualization(visual);
00077   
00078   vel_start_.first = true;
00079   vel_start_.second.setZero();
00080 
00081   vel_goal_.first = true;
00082   vel_goal_.second.setZero();
00083   initialized_ = true;
00084 }
00085 
00086 
00087 void TebOptimalPlanner::setVisualization(TebVisualizationPtr visualization)
00088 {
00089   visualization_ = visualization;
00090 }
00091 
00092 void TebOptimalPlanner::visualize()
00093 {
00094   if (!visualization_)
00095     return;
00096  
00097   visualization_->publishLocalPlanAndPoses(teb_);
00098   
00099   if (teb_.sizePoses() > 0)
00100     visualization_->publishRobotFootprintModel(teb_.Pose(0), *robot_model_);
00101   
00102   if (cfg_->trajectory.publish_feedback)
00103     visualization_->publishFeedbackMessage(*this, *obstacles_);
00104  
00105 }
00106 
00107 
00108 /*
00109  * registers custom vertices and edges in g2o framework
00110  */
00111 void TebOptimalPlanner::registerG2OTypes()
00112 {
00113   g2o::Factory* factory = g2o::Factory::instance();
00114   factory->registerType("VERTEX_POSE", new g2o::HyperGraphElementCreator<VertexPose>);
00115   factory->registerType("VERTEX_TIMEDIFF", new g2o::HyperGraphElementCreator<VertexTimeDiff>);
00116 
00117   factory->registerType("EDGE_TIME_OPTIMAL", new g2o::HyperGraphElementCreator<EdgeTimeOptimal>);
00118   factory->registerType("EDGE_VELOCITY", new g2o::HyperGraphElementCreator<EdgeVelocity>);
00119   factory->registerType("EDGE_ACCELERATION", new g2o::HyperGraphElementCreator<EdgeAcceleration>);
00120   factory->registerType("EDGE_ACCELERATION_START", new g2o::HyperGraphElementCreator<EdgeAccelerationStart>);
00121   factory->registerType("EDGE_ACCELERATION_GOAL", new g2o::HyperGraphElementCreator<EdgeAccelerationGoal>);
00122   factory->registerType("EDGE_KINEMATICS_DIFF_DRIVE", new g2o::HyperGraphElementCreator<EdgeKinematicsDiffDrive>);
00123   factory->registerType("EDGE_KINEMATICS_CARLIKE", new g2o::HyperGraphElementCreator<EdgeKinematicsCarlike>);
00124   factory->registerType("EDGE_OBSTACLE", new g2o::HyperGraphElementCreator<EdgeObstacle>);
00125   factory->registerType("EDGE_INFLATED_OBSTACLE", new g2o::HyperGraphElementCreator<EdgeInflatedObstacle>);
00126   factory->registerType("EDGE_DYNAMIC_OBSTACLE", new g2o::HyperGraphElementCreator<EdgeDynamicObstacle>);
00127   factory->registerType("EDGE_VIA_POINT", new g2o::HyperGraphElementCreator<EdgeViaPoint>);
00128   return;
00129 }
00130 
00131 /*
00132  * initialize g2o optimizer. Set solver settings here.
00133  * Return: pointer to new SparseOptimizer Object.
00134  */
00135 boost::shared_ptr<g2o::SparseOptimizer> TebOptimalPlanner::initOptimizer()
00136 {
00137   // Call register_g2o_types once, even for multiple TebOptimalPlanner instances (thread-safe)
00138   static boost::once_flag flag = BOOST_ONCE_INIT;
00139   boost::call_once(&registerG2OTypes, flag);  
00140 
00141   // allocating the optimizer
00142   boost::shared_ptr<g2o::SparseOptimizer> optimizer = boost::make_shared<g2o::SparseOptimizer>();
00143   TEBLinearSolver* linearSolver = new TEBLinearSolver(); // see typedef in optimization.h
00144   linearSolver->setBlockOrdering(true);
00145   TEBBlockSolver* blockSolver = new TEBBlockSolver(linearSolver);
00146   g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(blockSolver);
00147 
00148   optimizer->setAlgorithm(solver);
00149   
00150   optimizer->initMultiThreading(); // required for >Eigen 3.1
00151   
00152   return optimizer;
00153 }
00154 
00155 
00156 bool TebOptimalPlanner::optimizeTEB(unsigned int iterations_innerloop, unsigned int iterations_outerloop, bool compute_cost_afterwards,
00157                                     double obst_cost_scale, double viapoint_cost_scale, bool alternative_time_cost)
00158 {
00159   if (cfg_->optim.optimization_activate==false) 
00160     return false;
00161   bool success = false;
00162   optimized_ = false;
00163   for(unsigned int i=0; i<iterations_outerloop; ++i)
00164   {
00165     if (cfg_->trajectory.teb_autosize)
00166       teb_.autoResize(cfg_->trajectory.dt_ref, cfg_->trajectory.dt_hysteresis, cfg_->trajectory.min_samples);
00167 
00168     success = buildGraph();
00169     if (!success) 
00170     {
00171         clearGraph();
00172         return false;
00173     }
00174     success = optimizeGraph(iterations_innerloop, false);
00175     if (!success) 
00176     {
00177         clearGraph();
00178         return false;
00179     }
00180     optimized_ = true;
00181     
00182     if (compute_cost_afterwards && i==iterations_outerloop-1) // compute cost vec only in the last iteration
00183       computeCurrentCost(obst_cost_scale, viapoint_cost_scale, alternative_time_cost);
00184       
00185     clearGraph();
00186   }
00187 
00188   return true;
00189 }
00190 
00191 void TebOptimalPlanner::setVelocityStart(const Eigen::Ref<const Eigen::Vector2d>& vel_start)
00192 {
00193   vel_start_.first = true;
00194   vel_start_.second = vel_start;
00195 }
00196 
00197 void TebOptimalPlanner::setVelocityStart(const geometry_msgs::Twist& vel_start)
00198 {
00199   vel_start_.first = true;
00200   vel_start_.second.coeffRef(0) = vel_start.linear.x;
00201   vel_start_.second.coeffRef(1) = vel_start.angular.z;
00202 }
00203 
00204 void TebOptimalPlanner::setVelocityGoal(const Eigen::Ref<const Eigen::Vector2d>& vel_goal)
00205 {
00206   vel_goal_.first = true;
00207   vel_goal_.second = vel_goal;
00208 }
00209 
00210 bool TebOptimalPlanner::plan(const std::vector<geometry_msgs::PoseStamped>& initial_plan, const geometry_msgs::Twist* start_vel, bool free_goal_vel)
00211 {    
00212   ROS_ASSERT_MSG(initialized_, "Call initialize() first.");
00213   if (!teb_.isInit())
00214   {
00215     // init trajectory
00216     teb_.initTEBtoGoal(initial_plan, cfg_->trajectory.dt_ref, true, cfg_->trajectory.min_samples);
00217   } 
00218   else // warm start
00219   {
00220     PoseSE2 start_(initial_plan.front().pose);
00221     PoseSE2 goal_(initial_plan.back().pose);
00222     if (teb_.sizePoses()>0 && (goal_.position() - teb_.BackPose().position()).norm() < cfg_->trajectory.force_reinit_new_goal_dist) // actual warm start!
00223       teb_.updateAndPruneTEB(start_, goal_, cfg_->trajectory.min_samples); // update TEB
00224     else // goal too far away -> reinit
00225     {
00226       ROS_DEBUG("New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories.");
00227       teb_.clearTimedElasticBand();
00228       teb_.initTEBtoGoal(initial_plan, cfg_->trajectory.dt_ref, true, cfg_->trajectory.min_samples);
00229     }
00230   }
00231   if (start_vel)
00232     setVelocityStart(*start_vel);
00233   if (free_goal_vel)
00234     setVelocityGoalFree();
00235   else
00236     vel_goal_.first = true; // we just reactivate and use the previously set velocity (should be zero if nothing was modified)
00237   
00238   // now optimize
00239   return optimizeTEB(cfg_->optim.no_inner_iterations, cfg_->optim.no_outer_iterations);
00240 }
00241 
00242 
00243 bool TebOptimalPlanner::plan(const tf::Pose& start, const tf::Pose& goal, const geometry_msgs::Twist* start_vel, bool free_goal_vel)
00244 {
00245   PoseSE2 start_(start);
00246   PoseSE2 goal_(goal);
00247   Eigen::Vector2d vel = start_vel ? Eigen::Vector2d(start_vel->linear.x, start_vel->angular.z) : Eigen::Vector2d::Zero();
00248   return plan(start_, goal_, vel);
00249 }
00250 
00251 bool TebOptimalPlanner::plan(const PoseSE2& start, const PoseSE2& goal, const Eigen::Vector2d& start_vel, bool free_goal_vel)
00252 {       
00253   ROS_ASSERT_MSG(initialized_, "Call initialize() first.");
00254   if (!teb_.isInit())
00255   {
00256     // init trajectory
00257     teb_.initTEBtoGoal(start, goal, 0, 1, cfg_->trajectory.min_samples); // 0 intermediate samples, but dt=1 -> autoResize will add more samples before calling first optimization
00258   }
00259   else // warm start
00260   {
00261     if (teb_.sizePoses()>0 && (goal.position() - teb_.BackPose().position()).norm() < cfg_->trajectory.force_reinit_new_goal_dist) // actual warm start!
00262       teb_.updateAndPruneTEB(start, goal, cfg_->trajectory.min_samples);
00263     else // goal too far away -> reinit
00264     {
00265       ROS_DEBUG("New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories.");
00266       teb_.clearTimedElasticBand();
00267       teb_.initTEBtoGoal(start, goal, 0, 1, cfg_->trajectory.min_samples);
00268     }
00269   }
00270   setVelocityStart(start_vel);
00271   if (free_goal_vel)
00272     setVelocityGoalFree();
00273   else
00274     vel_goal_.first = true; // we just reactivate and use the previously set velocity (should be zero if nothing was modified)
00275       
00276   // now optimize
00277   return optimizeTEB(cfg_->optim.no_inner_iterations, cfg_->optim.no_outer_iterations);
00278 }
00279 
00280 
00281 bool TebOptimalPlanner::buildGraph()
00282 {
00283   if (!optimizer_->edges().empty() || !optimizer_->vertices().empty())
00284   {
00285     ROS_WARN("Cannot build graph, because it is not empty. Call graphClear()!");
00286     return false;
00287   }
00288   
00289   // add TEB vertices
00290   AddTEBVertices();
00291   
00292   // add Edges (local cost functions)
00293   if (cfg_->obstacles.inflation_dist > cfg_->obstacles.min_obstacle_dist)
00294     AddEdgesInflatedObstacles();
00295   else
00296     AddEdgesObstacles();
00297   
00298   //AddEdgesDynamicObstacles();
00299   
00300   AddEdgesViaPoints();
00301   
00302   AddEdgesVelocity();
00303   
00304   AddEdgesAcceleration();
00305 
00306   AddEdgesTimeOptimal();        
00307   
00308   if (cfg_->robot.min_turning_radius == 0 || cfg_->optim.weight_kinematics_turning_radius == 0)
00309     AddEdgesKinematicsDiffDrive(); // we have a differential drive robot
00310   else
00311     AddEdgesKinematicsCarlike(); // we have a carlike robot since the turning radius is bounded from below.
00312 
00313   return true;  
00314 }
00315 
00316 bool TebOptimalPlanner::optimizeGraph(int no_iterations,bool clear_after)
00317 {
00318   if (cfg_->robot.max_vel_x<0.01)
00319   {
00320     ROS_WARN("optimizeGraph(): Robot Max Velocity is smaller than 0.01m/s. Optimizing aborted...");
00321     if (clear_after) clearGraph();
00322     return false;       
00323   }
00324   
00325   if (!teb_.isInit() || (int)teb_.sizePoses()<cfg_->trajectory.min_samples)
00326   {
00327     ROS_WARN("optimizeGraph(): TEB is empty or has too less elements. Skipping optimization.");
00328     if (clear_after) clearGraph();
00329     return false;       
00330   }
00331   
00332   optimizer_->setVerbose(cfg_->optim.optimization_verbose);
00333   optimizer_->initializeOptimization();
00334 
00335   int iter = optimizer_->optimize(no_iterations);
00336   
00337   if(!iter)
00338   {
00339         ROS_ERROR("optimizeGraph(): Optimization failed! iter=%i", iter);
00340         return false;
00341   }
00342 
00343   if (clear_after) clearGraph();        
00344     
00345   return true;
00346 }
00347 
00348 void TebOptimalPlanner::clearGraph()
00349 {
00350   // clear optimizer states
00351   //optimizer.edges().clear(); // optimizer.clear deletes edges!!! Therefore do not run optimizer.edges().clear()
00352   optimizer_->vertices().clear();  // neccessary, because optimizer->clear deletes pointer-targets (therefore it deletes TEB states!)
00353   optimizer_->clear();  
00354 }
00355 
00356 
00357 
00358 void TebOptimalPlanner::AddTEBVertices()
00359 {
00360   // add vertices to graph
00361   ROS_DEBUG_COND(cfg_->optim.optimization_verbose, "Adding TEB vertices ...");
00362   unsigned int id_counter = 0; // used for vertices ids
00363   for (unsigned int i=0; i<teb_.sizePoses(); ++i)
00364   {
00365     teb_.PoseVertex(i)->setId(id_counter++);
00366     optimizer_->addVertex(teb_.PoseVertex(i));
00367     if (teb_.sizeTimeDiffs()!=0 && i<teb_.sizeTimeDiffs())
00368     {
00369       teb_.TimeDiffVertex(i)->setId(id_counter++);
00370       optimizer_->addVertex(teb_.TimeDiffVertex(i));
00371     }
00372   } 
00373 }
00374 
00375 
00376 
00377 void TebOptimalPlanner::AddEdgesObstacles()
00378 {
00379   if (cfg_->optim.weight_obstacle==0 || obstacles_==NULL )
00380     return; // if weight equals zero skip adding edges!
00381 
00382   Eigen::Matrix<double,1,1> information;
00383   information.fill(cfg_->optim.weight_obstacle);
00384     
00385   for (ObstContainer::const_iterator obst = obstacles_->begin(); obst != obstacles_->end(); ++obst)
00386   {
00387     if ((*obst)->isDynamic()) // we handle dynamic obstacles differently below
00388       continue; 
00389     
00390     unsigned int index;
00391     
00392     if (cfg_->obstacles.obstacle_poses_affected >= (int)teb_.sizePoses())
00393       index =  teb_.sizePoses() / 2;
00394     else
00395       index = teb_.findClosestTrajectoryPose(*(obst->get()));
00396      
00397     
00398     // check if obstacle is outside index-range between start and goal
00399     if ( (index <= 1) || (index > teb_.sizePoses()-2) ) // start and goal are fixed and findNearestBandpoint finds first or last conf if intersection point is outside the range
00400             continue; 
00401         
00402     EdgeObstacle* dist_bandpt_obst = new EdgeObstacle;
00403     dist_bandpt_obst->setVertex(0,teb_.PoseVertex(index));
00404     dist_bandpt_obst->setInformation(information);
00405     dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), obst->get());
00406     optimizer_->addEdge(dist_bandpt_obst);
00407 
00408     for (unsigned int neighbourIdx=0; neighbourIdx < floor(cfg_->obstacles.obstacle_poses_affected/2); neighbourIdx++)
00409     {
00410       if (index+neighbourIdx < teb_.sizePoses())
00411       {
00412         EdgeObstacle* dist_bandpt_obst_n_r = new EdgeObstacle;
00413         dist_bandpt_obst_n_r->setVertex(0,teb_.PoseVertex(index+neighbourIdx));
00414         dist_bandpt_obst_n_r->setInformation(information);
00415         dist_bandpt_obst_n_r->setParameters(*cfg_, robot_model_.get(), obst->get());
00416         optimizer_->addEdge(dist_bandpt_obst_n_r);
00417       }
00418       if ( (int) index - (int) neighbourIdx >= 0) // needs to be casted to int to allow negative values
00419       {
00420         EdgeObstacle* dist_bandpt_obst_n_l = new EdgeObstacle;
00421         dist_bandpt_obst_n_l->setVertex(0,teb_.PoseVertex(index-neighbourIdx));
00422         dist_bandpt_obst_n_l->setInformation(information);
00423         dist_bandpt_obst_n_l->setParameters(*cfg_, robot_model_.get(), obst->get());
00424         optimizer_->addEdge(dist_bandpt_obst_n_l);
00425       }
00426     } 
00427           
00428   }
00429 }
00430 
00431 void TebOptimalPlanner::AddEdgesInflatedObstacles()
00432 {
00433   if (cfg_->optim.weight_obstacle==0 || obstacles_==NULL )
00434     return; // if weight equals zero skip adding edges!
00435 
00436   Eigen::Matrix<double,2,2> information;
00437   information(0,0) = cfg_->optim.weight_obstacle;
00438   information(1,1) = cfg_->optim.weight_inflation;
00439   information(0,1) = information(1,0) = 0;
00440     
00441   for (ObstContainer::const_iterator obst = obstacles_->begin(); obst != obstacles_->end(); ++obst)
00442   {
00443     if ((*obst)->isDynamic()) // we handle dynamic obstacles differently below
00444       continue; 
00445     
00446     int index;
00447     
00448     if (cfg_->obstacles.obstacle_poses_affected >= teb_.sizePoses())
00449       index =  teb_.sizePoses() / 2;
00450     else
00451       index = teb_.findClosestTrajectoryPose(*(obst->get()));
00452      
00453     
00454     // check if obstacle is outside index-range between start and goal
00455     if ( (index <= 1) || (index > teb_.sizePoses()-2) ) // start and goal are fixed and findNearestBandpoint finds first or last conf if intersection point is outside the range
00456             continue; 
00457         
00458     EdgeInflatedObstacle* dist_bandpt_obst = new EdgeInflatedObstacle;
00459     dist_bandpt_obst->setVertex(0,teb_.PoseVertex(index));
00460     dist_bandpt_obst->setInformation(information);
00461     dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), obst->get());
00462     optimizer_->addEdge(dist_bandpt_obst);
00463 
00464     for (int neighbourIdx=0; neighbourIdx < floor(cfg_->obstacles.obstacle_poses_affected/2); neighbourIdx++)
00465     {
00466       if (index+neighbourIdx < teb_.sizePoses())
00467       {
00468         EdgeInflatedObstacle* dist_bandpt_obst_n_r = new EdgeInflatedObstacle;
00469         dist_bandpt_obst_n_r->setVertex(0,teb_.PoseVertex(index+neighbourIdx));
00470         dist_bandpt_obst_n_r->setInformation(information);
00471         dist_bandpt_obst_n_r->setParameters(*cfg_, robot_model_.get(), obst->get());
00472         optimizer_->addEdge(dist_bandpt_obst_n_r);
00473       }
00474       if ( index - neighbourIdx >= 0) // needs to be casted to int to allow negative values
00475       {
00476         EdgeInflatedObstacle* dist_bandpt_obst_n_l = new EdgeInflatedObstacle;
00477         dist_bandpt_obst_n_l->setVertex(0,teb_.PoseVertex(index-neighbourIdx));
00478         dist_bandpt_obst_n_l->setInformation(information);
00479         dist_bandpt_obst_n_l->setParameters(*cfg_, robot_model_.get(), obst->get());
00480         optimizer_->addEdge(dist_bandpt_obst_n_l);
00481       }
00482     } 
00483           
00484   }
00485 }
00486 
00487 
00488 void TebOptimalPlanner::AddEdgesDynamicObstacles()
00489 {
00490   if (cfg_->optim.weight_obstacle==0 || obstacles_==NULL )
00491     return; // if weight equals zero skip adding edges!
00492   
00493   Eigen::Matrix<double,1,1> information;
00494   information.fill(cfg_->optim.weight_dynamic_obstacle);
00495   
00496   for (ObstContainer::const_iterator obst = obstacles_->begin(); obst != obstacles_->end(); ++obst)
00497   {
00498     if (!(*obst)->isDynamic())
00499       continue;
00500 
00501     for (std::size_t i=1; i < teb_.sizePoses() - 1; ++i)
00502     {
00503       EdgeDynamicObstacle* dynobst_edge = new EdgeDynamicObstacle(i);
00504       dynobst_edge->setVertex(0,teb_.PoseVertex(i));
00505       //dynobst_edge->setVertex(1,teb.PointVertex(i+1));
00506       dynobst_edge->setVertex(1,teb_.TimeDiffVertex(i));
00507       dynobst_edge->setInformation(information);
00508       dynobst_edge->setMeasurement(obst->get());
00509       dynobst_edge->setTebConfig(*cfg_);
00510       optimizer_->addEdge(dynobst_edge);
00511     }
00512   }
00513 }
00514 
00515 void TebOptimalPlanner::AddEdgesViaPoints()
00516 {
00517   if (cfg_->optim.weight_viapoint==0 || via_points_==NULL || via_points_->empty() )
00518     return; // if weight equals zero skip adding edges!
00519 
00520   int start_pose_idx = 0;
00521   
00522   int n = (int)teb_.sizePoses();
00523   if (n<3) // we do not have any degrees of freedom for reaching via-points
00524     return;
00525   
00526   for (ViaPointContainer::const_iterator vp_it = via_points_->begin(); vp_it != via_points_->end(); ++vp_it)
00527   {
00528     
00529     int index = teb_.findClosestTrajectoryPose(*vp_it, NULL, start_pose_idx);
00530     if (cfg_->trajectory.via_points_ordered)
00531       start_pose_idx = index+2; // skip a point to have a DOF inbetween for further via-points
00532      
00533     // check if point conicides with goal or is located behind it
00534     if ( index > n-2 ) 
00535       index = n-2; // set to a pose before the goal, since we can move it away!
00536     // check if point coincides with start or is located before it
00537     if ( index < 1)
00538       index = 1;
00539     
00540     Eigen::Matrix<double,1,1> information;
00541     information.fill(cfg_->optim.weight_viapoint);
00542     
00543     EdgeViaPoint* edge_viapoint = new EdgeViaPoint;
00544     edge_viapoint->setVertex(0,teb_.PoseVertex(index));
00545     edge_viapoint->setInformation(information);
00546     edge_viapoint->setParameters(*cfg_, &(*vp_it));
00547     optimizer_->addEdge(edge_viapoint);   
00548   }
00549 }
00550 
00551 void TebOptimalPlanner::AddEdgesVelocity()
00552 {
00553   if (cfg_->optim.weight_max_vel_x==0 && cfg_->optim.weight_max_vel_theta==0)
00554     return; // if weight equals zero skip adding edges!
00555 
00556   std::size_t NoBandpts(teb_.sizePoses());
00557   Eigen::Matrix<double,2,2> information;
00558   information.fill(0);
00559   information(0,0) = cfg_->optim.weight_max_vel_x;
00560   information(1,1) = cfg_->optim.weight_max_vel_theta;
00561 
00562   for (std::size_t i=0; i < NoBandpts - 1; ++i)
00563   {
00564     EdgeVelocity* velocity_edge = new EdgeVelocity;
00565     velocity_edge->setVertex(0,teb_.PoseVertex(i));
00566     velocity_edge->setVertex(1,teb_.PoseVertex(i+1));
00567     velocity_edge->setVertex(2,teb_.TimeDiffVertex(i));
00568     velocity_edge->setInformation(information);
00569     velocity_edge->setTebConfig(*cfg_);
00570     optimizer_->addEdge(velocity_edge);
00571   }
00572 }
00573 
00574 void TebOptimalPlanner::AddEdgesAcceleration()
00575 {
00576   if (cfg_->optim.weight_acc_lim_x==0 && cfg_->optim.weight_acc_lim_theta==0) 
00577     return; // if weight equals zero skip adding edges!
00578 
00579   std::size_t NoBandpts(teb_.sizePoses());
00580   Eigen::Matrix<double,2,2> information;
00581   information.fill(0);
00582   information(0,0) = cfg_->optim.weight_acc_lim_x;
00583   information(1,1) = cfg_->optim.weight_acc_lim_theta;
00584   
00585   // check if an initial velocity should be taken into accound
00586   if (vel_start_.first)
00587   {
00588     EdgeAccelerationStart* acceleration_edge = new EdgeAccelerationStart;
00589     acceleration_edge->setVertex(0,teb_.PoseVertex(0));
00590     acceleration_edge->setVertex(1,teb_.PoseVertex(1));
00591     acceleration_edge->setVertex(2,teb_.TimeDiffVertex(0));
00592     acceleration_edge->setInitialVelocity(vel_start_.second);
00593     acceleration_edge->setInformation(information);
00594     acceleration_edge->setTebConfig(*cfg_);
00595     optimizer_->addEdge(acceleration_edge);
00596   }
00597 
00598   // now add the usual acceleration edge for each tuple of three teb poses
00599   for (std::size_t i=0; i < NoBandpts - 2; ++i)
00600   {
00601     EdgeAcceleration* acceleration_edge = new EdgeAcceleration;
00602     acceleration_edge->setVertex(0,teb_.PoseVertex(i));
00603     acceleration_edge->setVertex(1,teb_.PoseVertex(i+1));
00604     acceleration_edge->setVertex(2,teb_.PoseVertex(i+2));
00605     acceleration_edge->setVertex(3,teb_.TimeDiffVertex(i));
00606     acceleration_edge->setVertex(4,teb_.TimeDiffVertex(i+1));
00607     acceleration_edge->setInformation(information);
00608     acceleration_edge->setTebConfig(*cfg_);
00609     optimizer_->addEdge(acceleration_edge);
00610   }
00611   
00612   // check if a goal velocity should be taken into accound
00613   if (vel_goal_.first)
00614   {
00615     EdgeAccelerationGoal* acceleration_edge = new EdgeAccelerationGoal;
00616     acceleration_edge->setVertex(0,teb_.PoseVertex(NoBandpts-2));
00617     acceleration_edge->setVertex(1,teb_.PoseVertex(NoBandpts-1));
00618     acceleration_edge->setVertex(2,teb_.TimeDiffVertex( teb_.sizeTimeDiffs()-1 ));
00619     acceleration_edge->setGoalVelocity(vel_goal_.second);
00620     acceleration_edge->setInformation(information);
00621     acceleration_edge->setTebConfig(*cfg_);
00622     optimizer_->addEdge(acceleration_edge);
00623   }  
00624 }
00625 
00626 
00627 
00628 void TebOptimalPlanner::AddEdgesTimeOptimal()
00629 {
00630   if (cfg_->optim.weight_optimaltime==0) 
00631     return; // if weight equals zero skip adding edges!
00632 
00633   Eigen::Matrix<double,1,1> information;
00634   information.fill(cfg_->optim.weight_optimaltime);
00635 
00636   for (std::size_t i=0; i < teb_.sizeTimeDiffs(); ++i)
00637   {
00638     EdgeTimeOptimal* timeoptimal_edge = new EdgeTimeOptimal;
00639     timeoptimal_edge->setVertex(0,teb_.TimeDiffVertex(i));
00640     timeoptimal_edge->setInformation(information);
00641     timeoptimal_edge->setTebConfig(*cfg_);
00642     optimizer_->addEdge(timeoptimal_edge);
00643   }
00644 }
00645 
00646 
00647 
00648 void TebOptimalPlanner::AddEdgesKinematicsDiffDrive()
00649 {
00650   if (cfg_->optim.weight_kinematics_nh==0 && cfg_->optim.weight_kinematics_forward_drive==0)
00651     return; // if weight equals zero skip adding edges!
00652   
00653   // create edge for satisfiying kinematic constraints
00654   Eigen::Matrix<double,2,2> information_kinematics;
00655   information_kinematics.fill(0.0);
00656   information_kinematics(0, 0) = cfg_->optim.weight_kinematics_nh;
00657   information_kinematics(1, 1) = cfg_->optim.weight_kinematics_forward_drive;
00658   
00659   for (unsigned int i=0; i < teb_.sizePoses()-1; i++) // ignore twiced start only
00660   {
00661     EdgeKinematicsDiffDrive* kinematics_edge = new EdgeKinematicsDiffDrive;
00662     kinematics_edge->setVertex(0,teb_.PoseVertex(i));
00663     kinematics_edge->setVertex(1,teb_.PoseVertex(i+1));      
00664     kinematics_edge->setInformation(information_kinematics);
00665     kinematics_edge->setTebConfig(*cfg_);
00666     optimizer_->addEdge(kinematics_edge);
00667   }      
00668 }
00669 
00670 void TebOptimalPlanner::AddEdgesKinematicsCarlike()
00671 {
00672   if (cfg_->optim.weight_kinematics_nh==0 && cfg_->optim.weight_kinematics_turning_radius)
00673     return; // if weight equals zero skip adding edges!
00674   
00675   // create edge for satisfiying kinematic constraints
00676   Eigen::Matrix<double,2,2> information_kinematics;
00677   information_kinematics.fill(0.0);
00678   information_kinematics(0, 0) = cfg_->optim.weight_kinematics_nh;
00679   information_kinematics(1, 1) = cfg_->optim.weight_kinematics_turning_radius;
00680   
00681   for (unsigned int i=0; i < teb_.sizePoses()-1; i++) // ignore twiced start only
00682   {
00683     EdgeKinematicsCarlike* kinematics_edge = new EdgeKinematicsCarlike;
00684     kinematics_edge->setVertex(0,teb_.PoseVertex(i));
00685     kinematics_edge->setVertex(1,teb_.PoseVertex(i+1));      
00686     kinematics_edge->setInformation(information_kinematics);
00687     kinematics_edge->setTebConfig(*cfg_);
00688     optimizer_->addEdge(kinematics_edge);
00689   }  
00690 }
00691 
00692 
00693 void TebOptimalPlanner::computeCurrentCost(double obst_cost_scale, double viapoint_cost_scale, bool alternative_time_cost)
00694 { 
00695   // check if graph is empty/exist  -> important if function is called between buildGraph and optimizeGraph/clearGraph
00696   bool graph_exist_flag(false);
00697   if (optimizer_->edges().empty() && optimizer_->vertices().empty())
00698   {
00699     // here the graph is build again, for time efficiency make sure to call this function 
00700     // between buildGraph and Optimize (deleted), but it depends on the application
00701     buildGraph();       
00702     optimizer_->initializeOptimization();
00703   }
00704   else
00705   {
00706     graph_exist_flag = true;
00707   }
00708   
00709   optimizer_->computeInitialGuess();
00710   
00711   cost_ = 0;
00712 
00713   if (alternative_time_cost)
00714   {
00715     cost_ += teb_.getSumOfAllTimeDiffs();
00716     // TEST we use SumOfAllTimeDiffs() here, because edge cost depends on number of samples, which is not always the same for similar TEBs,
00717     // since we are using an AutoResize Function with hysteresis.
00718   }
00719   
00720   // now we need pointers to all edges -> calculate error for each edge-type
00721   // since we aren't storing edge pointers, we need to check every edge
00722   for (std::vector<g2o::OptimizableGraph::Edge*>::const_iterator it = optimizer_->activeEdges().begin(); it!= optimizer_->activeEdges().end(); it++)
00723   {
00724     EdgeTimeOptimal* edge_time_optimal = dynamic_cast<EdgeTimeOptimal*>(*it);
00725     if (edge_time_optimal!=NULL && !alternative_time_cost)
00726     {
00727       cost_ += edge_time_optimal->getError().squaredNorm();
00728       continue;
00729     }
00730 
00731     EdgeKinematicsDiffDrive* edge_kinematics_dd = dynamic_cast<EdgeKinematicsDiffDrive*>(*it);
00732     if (edge_kinematics_dd!=NULL)
00733     {
00734       cost_ += edge_kinematics_dd->getError().squaredNorm();
00735       continue;
00736     }
00737     
00738     EdgeKinematicsCarlike* edge_kinematics_cl = dynamic_cast<EdgeKinematicsCarlike*>(*it);
00739     if (edge_kinematics_cl!=NULL)
00740     {
00741       cost_ += edge_kinematics_cl->getError().squaredNorm();
00742       continue;
00743     }
00744     
00745     EdgeVelocity* edge_velocity = dynamic_cast<EdgeVelocity*>(*it);
00746     if (edge_velocity!=NULL)
00747     {
00748       cost_ += edge_velocity->getError().squaredNorm();
00749       continue;
00750     }
00751     
00752     EdgeAcceleration* edge_acceleration = dynamic_cast<EdgeAcceleration*>(*it);
00753     if (edge_acceleration!=NULL)
00754     {
00755       cost_ += edge_acceleration->getError().squaredNorm();
00756       continue;
00757     }
00758     
00759     EdgeObstacle* edge_obstacle = dynamic_cast<EdgeObstacle*>(*it);
00760     if (edge_obstacle!=NULL)
00761     {
00762       cost_ += edge_obstacle->getError().squaredNorm() * obst_cost_scale;
00763       continue;
00764     }
00765     
00766     EdgeInflatedObstacle* edge_inflated_obstacle = dynamic_cast<EdgeInflatedObstacle*>(*it);
00767     if (edge_inflated_obstacle!=NULL)
00768     {
00769       cost_ += std::sqrt(std::pow(edge_inflated_obstacle->getError()[0],2) * obst_cost_scale 
00770                + std::pow(edge_inflated_obstacle->getError()[1],2));
00771       continue;
00772     }
00773     
00774     EdgeDynamicObstacle* edge_dyn_obstacle = dynamic_cast<EdgeDynamicObstacle*>(*it);
00775     if (edge_dyn_obstacle!=NULL)
00776     {
00777       cost_ += edge_dyn_obstacle->getError().squaredNorm() * obst_cost_scale;
00778       continue;
00779     }
00780     
00781     EdgeViaPoint* edge_viapoint = dynamic_cast<EdgeViaPoint*>(*it);
00782     if (edge_viapoint!=NULL)
00783     {
00784       cost_ += edge_viapoint->getError().squaredNorm() * viapoint_cost_scale;
00785       continue;
00786     }
00787   }
00788 
00789   // delete temporary created graph
00790   if (!graph_exist_flag) 
00791     clearGraph();
00792 }
00793 
00794 
00795 void TebOptimalPlanner::extractVelocity(const PoseSE2& pose1, const PoseSE2& pose2, double dt, double& v, double& omega) const
00796 {
00797   Eigen::Vector2d deltaS = pose2.position() - pose1.position();
00798   Eigen::Vector2d conf1dir( cos(pose1.theta()), sin(pose1.theta()) );
00799   // translational velocity
00800   double dir = deltaS.dot(conf1dir);
00801   v = (double) g2o::sign(dir) * deltaS.norm()/dt;
00802   
00803   // rotational velocity
00804   double orientdiff = g2o::normalize_theta(pose2.theta() - pose1.theta());
00805   omega = orientdiff/dt;
00806 }
00807 
00808 bool TebOptimalPlanner::getVelocityCommand(double& v, double& omega) const
00809 {
00810   if (teb_.sizePoses()<2)
00811   {
00812     ROS_ERROR("TebOptimalPlanner::getVelocityCommand(): The trajectory contains less than 2 poses. Make sure to init and optimize/plan the trajectory fist.");
00813     v = 0;
00814     omega = 0;
00815     return false;
00816   }
00817   
00818   double dt = teb_.TimeDiff(0);
00819   if (dt<=0)
00820   {     
00821     ROS_ERROR("TebOptimalPlanner::getVelocityCommand() - timediff<=0 is invalid!");
00822     v = 0;
00823     omega = 0;
00824     return false;
00825   }
00826           
00827   // Get velocity from the first two configurations
00828   extractVelocity(teb_.Pose(0), teb_.Pose(1), dt, v, omega);
00829   return true;
00830 }
00831 
00832 void TebOptimalPlanner::getVelocityProfile(std::vector<geometry_msgs::Twist>& velocity_profile) const
00833 {
00834   int n = (int) teb_.sizePoses();
00835   velocity_profile.resize( n+1 );
00836 
00837   // start velocity
00838   velocity_profile.front().linear.y = velocity_profile.front().linear.z = 0;
00839   velocity_profile.front().angular.x = velocity_profile.front().angular.y = 0;  
00840   velocity_profile.front().linear.x = vel_start_.second.x();
00841   velocity_profile.front().angular.z = vel_start_.second.y();
00842   
00843   for (int i=1; i<n; ++i)
00844   {
00845     velocity_profile[i].linear.y = velocity_profile[i].linear.z = 0;
00846     velocity_profile[i].angular.x = velocity_profile[i].angular.y = 0;
00847     extractVelocity(teb_.Pose(i-1), teb_.Pose(i), teb_.TimeDiff(i-1), velocity_profile[i].linear.x, velocity_profile[i].angular.z);
00848   }
00849   
00850   // goal velocity
00851   velocity_profile.back().linear.y = velocity_profile.back().linear.z = 0;
00852   velocity_profile.back().angular.x = velocity_profile.back().angular.y = 0;  
00853   velocity_profile.back().linear.x = vel_goal_.second.x();
00854   velocity_profile.back().angular.z = vel_goal_.second.y();
00855 }
00856 
00857 void TebOptimalPlanner::getFullTrajectory(std::vector<TrajectoryPointMsg>& trajectory) const
00858 {
00859   int n = (int) teb_.sizePoses();
00860   
00861   trajectory.resize(n);
00862   
00863   if (n == 0)
00864     return;
00865      
00866   double curr_time = 0;
00867   
00868   // start
00869   TrajectoryPointMsg& start = trajectory.front();
00870   teb_.Pose(0).toPoseMsg(start.pose);
00871   start.velocity.linear.y = start.velocity.linear.z = 0;
00872   start.velocity.angular.x = start.velocity.angular.y = 0;
00873   start.velocity.linear.x = vel_start_.second.x();
00874   start.velocity.angular.z = vel_start_.second.y();
00875   start.time_from_start.fromSec(curr_time);
00876   
00877   curr_time += teb_.TimeDiff(0);
00878   
00879   // intermediate points
00880   for (int i=1; i < n-1; ++i)
00881   {
00882     TrajectoryPointMsg& point = trajectory[i];
00883     teb_.Pose(i).toPoseMsg(point.pose);
00884     point.velocity.linear.y = point.velocity.linear.z = 0;
00885     point.velocity.angular.x = point.velocity.angular.y = 0;
00886     double vel1, vel2, omega1, omega2;
00887     extractVelocity(teb_.Pose(i-1), teb_.Pose(i), teb_.TimeDiff(i-1), vel1, omega1);
00888     extractVelocity(teb_.Pose(i), teb_.Pose(i+1), teb_.TimeDiff(i), vel2, omega2);
00889     point.velocity.linear.x = 0.5*(vel1+vel2);
00890     point.velocity.angular.z = 0.5*(omega1+omega2);    
00891     point.time_from_start.fromSec(curr_time);
00892     
00893     curr_time += teb_.TimeDiff(i);
00894   }
00895   
00896   // goal
00897   TrajectoryPointMsg& goal = trajectory.back();
00898   teb_.BackPose().toPoseMsg(goal.pose);
00899   goal.velocity.linear.y = goal.velocity.linear.z = 0;
00900   goal.velocity.angular.x = goal.velocity.angular.y = 0;
00901   goal.velocity.linear.x = vel_goal_.second.x();
00902   goal.velocity.angular.z = vel_goal_.second.y();
00903   goal.time_from_start.fromSec(curr_time);
00904 }
00905 
00906 
00907 bool TebOptimalPlanner::isTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector<geometry_msgs::Point>& footprint_spec,
00908                                              double inscribed_radius, double circumscribed_radius, int look_ahead_idx)
00909 {
00910   if (look_ahead_idx < 0 || look_ahead_idx >= (int) teb().sizePoses())
00911     look_ahead_idx = (int) teb().sizePoses()-1;
00912   
00913   for (int i=0; i <= look_ahead_idx; ++i)
00914   {           
00915     if ( costmap_model->footprintCost(teb().Pose(i).x(), teb().Pose(i).y(), teb().Pose(i).theta(), footprint_spec, inscribed_radius, circumscribed_radius) < 0 )
00916       return false;
00917     
00918     // check if distance between two poses is higher than the robot radius and interpolate in that case
00919     // (if obstacles are pushing two consecutive poses away, the center between two consecutive poses might coincide with the obstacle ;-)!
00920     if (i<look_ahead_idx)
00921     {
00922       if ( (teb().Pose(i+1).position()-teb().Pose(i).position()).norm() > inscribed_radius)
00923       {
00924         // check one more time
00925         PoseSE2 center = PoseSE2::average(teb().Pose(i), teb().Pose(i+1));
00926         if ( costmap_model->footprintCost(center.x(), center.y(), center.theta(), footprint_spec, inscribed_radius, circumscribed_radius) < 0 )
00927           return false;
00928       }
00929       
00930     }
00931   }
00932   return true;
00933 }
00934 
00935 
00936 bool TebOptimalPlanner::isHorizonReductionAppropriate(const std::vector<geometry_msgs::PoseStamped>& initial_plan) const
00937 {
00938   if (teb_.sizePoses() < std::size_t( 1.5*double(cfg_->trajectory.min_samples) ) ) // trajectory is short already
00939     return false;
00940   
00941   // check if distance is at least 2m long // hardcoded for now
00942   double dist = 0;
00943   for (std::size_t i=1; i < teb_.sizePoses(); ++i)
00944   {
00945     dist += ( teb_.Pose(i).position() - teb_.Pose(i-1).position() ).norm();
00946     if (dist > 2)
00947       break;
00948   }
00949   if (dist <= 2)
00950     return false;
00951   
00952   // check if goal orientation is differing with more than 90° and the horizon is still long enough to exclude parking maneuvers.
00953   // use case: Sometimes the robot accomplish the following navigation task:
00954   // 1. wall following 2. 180° curve 3. following along the other side of the wall.
00955   // If the trajectory is too long, the trajectory might intersect with the obstace and the optimizer does 
00956   // push the trajectory to the correct side.
00957   if ( std::abs( g2o::normalize_theta( teb_.Pose(0).theta() - teb_.BackPose().theta() ) ) > M_PI/2)
00958   {
00959     ROS_DEBUG("TebOptimalPlanner::isHorizonReductionAppropriate(): Goal orientation - start orientation > 90° ");
00960     return true;
00961   }
00962   
00963   // check if goal heading deviates more than 90° w.r.t. start orienation
00964   if (teb_.Pose(0).orientationUnitVec().dot(teb_.BackPose().position() - teb_.Pose(0).position()) < 0)
00965   {
00966     ROS_DEBUG("TebOptimalPlanner::isHorizonReductionAppropriate(): Goal heading - start orientation > 90° ");
00967     return true;
00968   }
00969     
00970   // check ratio: distance along the inital plan and distance of the trajectory (maybe too much is cut off)
00971   int idx=0; // first get point close to the robot (should be fast if the global path is already pruned!)
00972   for (; idx < (int)initial_plan.size(); ++idx)
00973   {
00974     if ( std::sqrt(std::pow(initial_plan[idx].pose.position.x-teb_.Pose(0).x(), 2) + std::pow(initial_plan[idx].pose.position.y-teb_.Pose(0).y(), 2)) )
00975       break;
00976   } 
00977   // now calculate length
00978   double ref_path_length = 0;
00979   for (; idx < int(initial_plan.size())-1; ++idx)
00980   {
00981     ref_path_length += std::sqrt(std::pow(initial_plan[idx+1].pose.position.x-initial_plan[idx].pose.position.x, 2) 
00982                      + std::pow(initial_plan[idx+1].pose.position.y-initial_plan[idx].pose.position.y, 2) );
00983   } 
00984   
00985   // check distances along the teb trajectory (by the way, we also check if the distance between two poses is > obst_dist)
00986   double teb_length = 0;
00987   for (int i = 1; i < (int)teb_.sizePoses(); ++i )
00988   {
00989     double dist = (teb_.Pose(i).position() - teb_.Pose(i-1).position()).norm();
00990     if (dist > 0.95*cfg_->obstacles.min_obstacle_dist)
00991     {
00992       ROS_DEBUG("TebOptimalPlanner::isHorizonReductionAppropriate(): Distance between consecutive poses > 0.9*min_obstacle_dist");
00993       return true;
00994     }
00995     ref_path_length += dist;
00996   }
00997   if (ref_path_length>0 && teb_length/ref_path_length < 0.7) // now check ratio
00998   {
00999     ROS_DEBUG("TebOptimalPlanner::isHorizonReductionAppropriate(): Planned trajectory is at least 30° shorter than the initial plan");
01000     return true;
01001   }
01002   
01003   
01004   // otherwise we do not suggest shrinking the horizon:
01005   return false;
01006 }
01007 
01008 } // namespace teb_local_planner


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