00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #include <teb_local_planner/optimal_planner.h>
00040 #include <map>
00041 #include <limits>
00042
00043
00044 namespace teb_local_planner
00045 {
00046
00047
00048
00049 TebOptimalPlanner::TebOptimalPlanner() : cfg_(NULL), obstacles_(NULL), via_points_(NULL), cost_(HUGE_VAL), robot_model_(new PointRobotFootprint()), initialized_(false), optimized_(false)
00050 {
00051 }
00052
00053 TebOptimalPlanner::TebOptimalPlanner(const TebConfig& cfg, ObstContainer* obstacles, RobotFootprintModelPtr robot_model, TebVisualizationPtr visual, const ViaPointContainer* via_points)
00054 {
00055 initialize(cfg, obstacles, robot_model, visual, via_points);
00056 }
00057
00058 TebOptimalPlanner::~TebOptimalPlanner()
00059 {
00060 clearGraph();
00061
00062
00063
00064
00065
00066 }
00067
00068 void TebOptimalPlanner::initialize(const TebConfig& cfg, ObstContainer* obstacles, RobotFootprintModelPtr robot_model, TebVisualizationPtr visual, const ViaPointContainer* via_points)
00069 {
00070
00071 optimizer_ = initOptimizer();
00072
00073 cfg_ = &cfg;
00074 obstacles_ = obstacles;
00075 robot_model_ = robot_model;
00076 via_points_ = via_points;
00077 cost_ = HUGE_VAL;
00078 setVisualization(visual);
00079
00080 vel_start_.first = true;
00081 vel_start_.second.linear.x = 0;
00082 vel_start_.second.linear.y = 0;
00083 vel_start_.second.angular.z = 0;
00084
00085 vel_goal_.first = true;
00086 vel_goal_.second.linear.x = 0;
00087 vel_goal_.second.linear.y = 0;
00088 vel_goal_.second.angular.z = 0;
00089 initialized_ = true;
00090 }
00091
00092
00093 void TebOptimalPlanner::setVisualization(TebVisualizationPtr visualization)
00094 {
00095 visualization_ = visualization;
00096 }
00097
00098 void TebOptimalPlanner::visualize()
00099 {
00100 if (!visualization_)
00101 return;
00102
00103 visualization_->publishLocalPlanAndPoses(teb_);
00104
00105 if (teb_.sizePoses() > 0)
00106 visualization_->publishRobotFootprintModel(teb_.Pose(0), *robot_model_);
00107
00108 if (cfg_->trajectory.publish_feedback)
00109 visualization_->publishFeedbackMessage(*this, *obstacles_);
00110
00111 }
00112
00113
00114
00115
00116
00117 void TebOptimalPlanner::registerG2OTypes()
00118 {
00119 g2o::Factory* factory = g2o::Factory::instance();
00120 factory->registerType("VERTEX_POSE", new g2o::HyperGraphElementCreator<VertexPose>);
00121 factory->registerType("VERTEX_TIMEDIFF", new g2o::HyperGraphElementCreator<VertexTimeDiff>);
00122
00123 factory->registerType("EDGE_TIME_OPTIMAL", new g2o::HyperGraphElementCreator<EdgeTimeOptimal>);
00124 factory->registerType("EDGE_VELOCITY", new g2o::HyperGraphElementCreator<EdgeVelocity>);
00125 factory->registerType("EDGE_VELOCITY_HOLONOMIC", new g2o::HyperGraphElementCreator<EdgeVelocityHolonomic>);
00126 factory->registerType("EDGE_ACCELERATION", new g2o::HyperGraphElementCreator<EdgeAcceleration>);
00127 factory->registerType("EDGE_ACCELERATION_START", new g2o::HyperGraphElementCreator<EdgeAccelerationStart>);
00128 factory->registerType("EDGE_ACCELERATION_GOAL", new g2o::HyperGraphElementCreator<EdgeAccelerationGoal>);
00129 factory->registerType("EDGE_ACCELERATION_HOLONOMIC", new g2o::HyperGraphElementCreator<EdgeAccelerationHolonomic>);
00130 factory->registerType("EDGE_ACCELERATION_HOLONOMIC_START", new g2o::HyperGraphElementCreator<EdgeAccelerationHolonomicStart>);
00131 factory->registerType("EDGE_ACCELERATION_HOLONOMIC_GOAL", new g2o::HyperGraphElementCreator<EdgeAccelerationHolonomicGoal>);
00132 factory->registerType("EDGE_KINEMATICS_DIFF_DRIVE", new g2o::HyperGraphElementCreator<EdgeKinematicsDiffDrive>);
00133 factory->registerType("EDGE_KINEMATICS_CARLIKE", new g2o::HyperGraphElementCreator<EdgeKinematicsCarlike>);
00134 factory->registerType("EDGE_OBSTACLE", new g2o::HyperGraphElementCreator<EdgeObstacle>);
00135 factory->registerType("EDGE_INFLATED_OBSTACLE", new g2o::HyperGraphElementCreator<EdgeInflatedObstacle>);
00136 factory->registerType("EDGE_DYNAMIC_OBSTACLE", new g2o::HyperGraphElementCreator<EdgeDynamicObstacle>);
00137 factory->registerType("EDGE_VIA_POINT", new g2o::HyperGraphElementCreator<EdgeViaPoint>);
00138 return;
00139 }
00140
00141
00142
00143
00144
00145 boost::shared_ptr<g2o::SparseOptimizer> TebOptimalPlanner::initOptimizer()
00146 {
00147
00148 static boost::once_flag flag = BOOST_ONCE_INIT;
00149 boost::call_once(®isterG2OTypes, flag);
00150
00151
00152 boost::shared_ptr<g2o::SparseOptimizer> optimizer = boost::make_shared<g2o::SparseOptimizer>();
00153 TEBLinearSolver* linearSolver = new TEBLinearSolver();
00154 linearSolver->setBlockOrdering(true);
00155 TEBBlockSolver* blockSolver = new TEBBlockSolver(linearSolver);
00156 g2o::OptimizationAlgorithmLevenberg* solver = new g2o::OptimizationAlgorithmLevenberg(blockSolver);
00157
00158 optimizer->setAlgorithm(solver);
00159
00160 optimizer->initMultiThreading();
00161
00162 return optimizer;
00163 }
00164
00165
00166 bool TebOptimalPlanner::optimizeTEB(int iterations_innerloop, int iterations_outerloop, bool compute_cost_afterwards,
00167 double obst_cost_scale, double viapoint_cost_scale, bool alternative_time_cost)
00168 {
00169 if (cfg_->optim.optimization_activate==false)
00170 return false;
00171
00172 bool success = false;
00173 optimized_ = false;
00174
00175 double weight_multiplier = 1.0;
00176
00177 for(int i=0; i<iterations_outerloop; ++i)
00178 {
00179 if (cfg_->trajectory.teb_autosize)
00180 teb_.autoResize(cfg_->trajectory.dt_ref, cfg_->trajectory.dt_hysteresis, cfg_->trajectory.min_samples, cfg_->trajectory.max_samples);
00181
00182 success = buildGraph(weight_multiplier);
00183 if (!success)
00184 {
00185 clearGraph();
00186 return false;
00187 }
00188 success = optimizeGraph(iterations_innerloop, false);
00189 if (!success)
00190 {
00191 clearGraph();
00192 return false;
00193 }
00194 optimized_ = true;
00195
00196 if (compute_cost_afterwards && i==iterations_outerloop-1)
00197 computeCurrentCost(obst_cost_scale, viapoint_cost_scale, alternative_time_cost);
00198
00199 clearGraph();
00200
00201 weight_multiplier *= cfg_->optim.weight_adapt_factor;
00202 }
00203
00204 return true;
00205 }
00206
00207
00208 void TebOptimalPlanner::setVelocityStart(const geometry_msgs::Twist& vel_start)
00209 {
00210 vel_start_.first = true;
00211 vel_start_.second.linear.x = vel_start.linear.x;
00212 vel_start_.second.linear.y = vel_start.linear.y;
00213 vel_start_.second.angular.z = vel_start.angular.z;
00214 }
00215
00216 void TebOptimalPlanner::setVelocityGoal(const geometry_msgs::Twist& vel_goal)
00217 {
00218 vel_goal_.first = true;
00219 vel_goal_.second = vel_goal;
00220 }
00221
00222 bool TebOptimalPlanner::plan(const std::vector<geometry_msgs::PoseStamped>& initial_plan, const geometry_msgs::Twist* start_vel, bool free_goal_vel)
00223 {
00224 ROS_ASSERT_MSG(initialized_, "Call initialize() first.");
00225 if (!teb_.isInit())
00226 {
00227
00228 teb_.initTEBtoGoal(initial_plan, cfg_->trajectory.dt_ref, cfg_->trajectory.global_plan_overwrite_orientation, cfg_->trajectory.min_samples, cfg_->trajectory.allow_init_with_backwards_motion);
00229 }
00230 else
00231 {
00232 PoseSE2 start_(initial_plan.front().pose);
00233 PoseSE2 goal_(initial_plan.back().pose);
00234 if (teb_.sizePoses()>0 && (goal_.position() - teb_.BackPose().position()).norm() < cfg_->trajectory.force_reinit_new_goal_dist)
00235 teb_.updateAndPruneTEB(start_, goal_, cfg_->trajectory.min_samples);
00236 else
00237 {
00238 ROS_DEBUG("New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories.");
00239 teb_.clearTimedElasticBand();
00240 teb_.initTEBtoGoal(initial_plan, cfg_->trajectory.dt_ref, true, cfg_->trajectory.min_samples, cfg_->trajectory.allow_init_with_backwards_motion);
00241 }
00242 }
00243 if (start_vel)
00244 setVelocityStart(*start_vel);
00245 if (free_goal_vel)
00246 setVelocityGoalFree();
00247 else
00248 vel_goal_.first = true;
00249
00250
00251 return optimizeTEB(cfg_->optim.no_inner_iterations, cfg_->optim.no_outer_iterations);
00252 }
00253
00254
00255 bool TebOptimalPlanner::plan(const tf::Pose& start, const tf::Pose& goal, const geometry_msgs::Twist* start_vel, bool free_goal_vel)
00256 {
00257 PoseSE2 start_(start);
00258 PoseSE2 goal_(goal);
00259 return plan(start_, goal_, start_vel);
00260 }
00261
00262 bool TebOptimalPlanner::plan(const PoseSE2& start, const PoseSE2& goal, const geometry_msgs::Twist* start_vel, bool free_goal_vel)
00263 {
00264 ROS_ASSERT_MSG(initialized_, "Call initialize() first.");
00265 if (!teb_.isInit())
00266 {
00267
00268 teb_.initTEBtoGoal(start, goal, 0, 1, cfg_->trajectory.min_samples, cfg_->trajectory.allow_init_with_backwards_motion);
00269 }
00270 else
00271 {
00272 if (teb_.sizePoses()>0 && (goal.position() - teb_.BackPose().position()).norm() < cfg_->trajectory.force_reinit_new_goal_dist)
00273 teb_.updateAndPruneTEB(start, goal, cfg_->trajectory.min_samples);
00274 else
00275 {
00276 ROS_DEBUG("New goal: distance to existing goal is higher than the specified threshold. Reinitalizing trajectories.");
00277 teb_.clearTimedElasticBand();
00278 teb_.initTEBtoGoal(start, goal, 0, 1, cfg_->trajectory.min_samples, cfg_->trajectory.allow_init_with_backwards_motion);
00279 }
00280 }
00281 if (start_vel)
00282 setVelocityStart(*start_vel);
00283 if (free_goal_vel)
00284 setVelocityGoalFree();
00285 else
00286 vel_goal_.first = true;
00287
00288
00289 return optimizeTEB(cfg_->optim.no_inner_iterations, cfg_->optim.no_outer_iterations);
00290 }
00291
00292
00293 bool TebOptimalPlanner::buildGraph(double weight_multiplier)
00294 {
00295 if (!optimizer_->edges().empty() || !optimizer_->vertices().empty())
00296 {
00297 ROS_WARN("Cannot build graph, because it is not empty. Call graphClear()!");
00298 return false;
00299 }
00300
00301
00302 AddTEBVertices();
00303
00304
00305 if (cfg_->obstacles.legacy_obstacle_association)
00306 AddEdgesObstaclesLegacy(weight_multiplier);
00307 else
00308 AddEdgesObstacles(weight_multiplier);
00309
00310
00311
00312 AddEdgesViaPoints();
00313
00314 AddEdgesVelocity();
00315
00316 AddEdgesAcceleration();
00317
00318 AddEdgesTimeOptimal();
00319
00320 if (cfg_->robot.min_turning_radius == 0 || cfg_->optim.weight_kinematics_turning_radius == 0)
00321 AddEdgesKinematicsDiffDrive();
00322 else
00323 AddEdgesKinematicsCarlike();
00324
00325 return true;
00326 }
00327
00328 bool TebOptimalPlanner::optimizeGraph(int no_iterations,bool clear_after)
00329 {
00330 if (cfg_->robot.max_vel_x<0.01)
00331 {
00332 ROS_WARN("optimizeGraph(): Robot Max Velocity is smaller than 0.01m/s. Optimizing aborted...");
00333 if (clear_after) clearGraph();
00334 return false;
00335 }
00336
00337 if (!teb_.isInit() || teb_.sizePoses() < cfg_->trajectory.min_samples)
00338 {
00339 ROS_WARN("optimizeGraph(): TEB is empty or has too less elements. Skipping optimization.");
00340 if (clear_after) clearGraph();
00341 return false;
00342 }
00343
00344 optimizer_->setVerbose(cfg_->optim.optimization_verbose);
00345 optimizer_->initializeOptimization();
00346
00347 int iter = optimizer_->optimize(no_iterations);
00348
00349 if(!iter)
00350 {
00351 ROS_ERROR("optimizeGraph(): Optimization failed! iter=%i", iter);
00352 return false;
00353 }
00354
00355 if (clear_after) clearGraph();
00356
00357 return true;
00358 }
00359
00360 void TebOptimalPlanner::clearGraph()
00361 {
00362
00363
00364 optimizer_->vertices().clear();
00365 optimizer_->clear();
00366 }
00367
00368
00369
00370 void TebOptimalPlanner::AddTEBVertices()
00371 {
00372
00373 ROS_DEBUG_COND(cfg_->optim.optimization_verbose, "Adding TEB vertices ...");
00374 unsigned int id_counter = 0;
00375 for (int i=0; i<teb_.sizePoses(); ++i)
00376 {
00377 teb_.PoseVertex(i)->setId(id_counter++);
00378 optimizer_->addVertex(teb_.PoseVertex(i));
00379 if (teb_.sizeTimeDiffs()!=0 && i<teb_.sizeTimeDiffs())
00380 {
00381 teb_.TimeDiffVertex(i)->setId(id_counter++);
00382 optimizer_->addVertex(teb_.TimeDiffVertex(i));
00383 }
00384 }
00385 }
00386
00387
00388 void TebOptimalPlanner::AddEdgesObstacles(double weight_multiplier)
00389 {
00390 if (cfg_->optim.weight_obstacle==0 || weight_multiplier==0 || obstacles_==nullptr )
00391 return;
00392
00393
00394 bool inflated = cfg_->obstacles.inflation_dist > cfg_->obstacles.min_obstacle_dist;
00395
00396 Eigen::Matrix<double,1,1> information;
00397 information.fill(cfg_->optim.weight_obstacle * weight_multiplier);
00398
00399 Eigen::Matrix<double,2,2> information_inflated;
00400 information_inflated(0,0) = cfg_->optim.weight_obstacle * weight_multiplier;
00401 information_inflated(1,1) = cfg_->optim.weight_inflation;
00402 information_inflated(0,1) = information_inflated(1,0) = 0;
00403
00404
00405 for (int i=1; i < teb_.sizePoses()-1; ++i)
00406 {
00407 double left_min_dist = std::numeric_limits<double>::max();
00408 double right_min_dist = std::numeric_limits<double>::max();
00409 Obstacle* left_obstacle = nullptr;
00410 Obstacle* right_obstacle = nullptr;
00411
00412 std::vector<Obstacle*> relevant_obstacles;
00413
00414 const Eigen::Vector2d pose_orient = teb_.Pose(i).orientationUnitVec();
00415
00416
00417 for (const ObstaclePtr& obst : *obstacles_)
00418 {
00419
00420
00421 double dist = obst->getMinimumDistance(teb_.Pose(i).position());
00422
00423
00424 if (dist < cfg_->obstacles.min_obstacle_dist*cfg_->obstacles.obstacle_association_force_inclusion_factor)
00425 {
00426 relevant_obstacles.push_back(obst.get());
00427 continue;
00428 }
00429
00430 if (dist > cfg_->obstacles.min_obstacle_dist*cfg_->obstacles.obstacle_association_cutoff_factor)
00431 continue;
00432
00433
00434 if (cross2d(pose_orient, obst->getCentroid()) > 0)
00435 {
00436 if (dist < left_min_dist)
00437 {
00438 left_min_dist = dist;
00439 left_obstacle = obst.get();
00440 }
00441 }
00442 else
00443 {
00444 if (dist < right_min_dist)
00445 {
00446 right_min_dist = dist;
00447 right_obstacle = obst.get();
00448 }
00449 }
00450 }
00451
00452
00453 if (left_obstacle)
00454 {
00455 if (inflated)
00456 {
00457 EdgeInflatedObstacle* dist_bandpt_obst = new EdgeInflatedObstacle;
00458 dist_bandpt_obst->setVertex(0,teb_.PoseVertex(i));
00459 dist_bandpt_obst->setInformation(information_inflated);
00460 dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), left_obstacle);
00461 optimizer_->addEdge(dist_bandpt_obst);
00462 }
00463 else
00464 {
00465 EdgeObstacle* dist_bandpt_obst = new EdgeObstacle;
00466 dist_bandpt_obst->setVertex(0,teb_.PoseVertex(i));
00467 dist_bandpt_obst->setInformation(information);
00468 dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), left_obstacle);
00469 optimizer_->addEdge(dist_bandpt_obst);
00470 }
00471 }
00472
00473 if (right_obstacle)
00474 {
00475 if (inflated)
00476 {
00477 EdgeInflatedObstacle* dist_bandpt_obst = new EdgeInflatedObstacle;
00478 dist_bandpt_obst->setVertex(0,teb_.PoseVertex(i));
00479 dist_bandpt_obst->setInformation(information_inflated);
00480 dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), right_obstacle);
00481 optimizer_->addEdge(dist_bandpt_obst);
00482 }
00483 else
00484 {
00485 EdgeObstacle* dist_bandpt_obst = new EdgeObstacle;
00486 dist_bandpt_obst->setVertex(0,teb_.PoseVertex(i));
00487 dist_bandpt_obst->setInformation(information);
00488 dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), right_obstacle);
00489 optimizer_->addEdge(dist_bandpt_obst);
00490 }
00491 }
00492
00493 for (const Obstacle* obst : relevant_obstacles)
00494 {
00495 if (inflated)
00496 {
00497 EdgeInflatedObstacle* dist_bandpt_obst = new EdgeInflatedObstacle;
00498 dist_bandpt_obst->setVertex(0,teb_.PoseVertex(i));
00499 dist_bandpt_obst->setInformation(information_inflated);
00500 dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), obst);
00501 optimizer_->addEdge(dist_bandpt_obst);
00502 }
00503 else
00504 {
00505 EdgeObstacle* dist_bandpt_obst = new EdgeObstacle;
00506 dist_bandpt_obst->setVertex(0,teb_.PoseVertex(i));
00507 dist_bandpt_obst->setInformation(information);
00508 dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), obst);
00509 optimizer_->addEdge(dist_bandpt_obst);
00510 }
00511 }
00512 }
00513
00514 }
00515
00516
00517 void TebOptimalPlanner::AddEdgesObstaclesLegacy(double weight_multiplier)
00518 {
00519 if (cfg_->optim.weight_obstacle==0 || weight_multiplier==0 || obstacles_==nullptr)
00520 return;
00521
00522 Eigen::Matrix<double,1,1> information;
00523 information.fill(cfg_->optim.weight_obstacle * weight_multiplier);
00524
00525 Eigen::Matrix<double,2,2> information_inflated;
00526 information_inflated(0,0) = cfg_->optim.weight_obstacle * weight_multiplier;
00527 information_inflated(1,1) = cfg_->optim.weight_inflation;
00528 information_inflated(0,1) = information_inflated(1,0) = 0;
00529
00530 bool inflated = cfg_->obstacles.inflation_dist > cfg_->obstacles.min_obstacle_dist;
00531
00532 for (ObstContainer::const_iterator obst = obstacles_->begin(); obst != obstacles_->end(); ++obst)
00533 {
00534 if ((*obst)->isDynamic())
00535 continue;
00536
00537 int index;
00538
00539 if (cfg_->obstacles.obstacle_poses_affected >= (int)teb_.sizePoses())
00540 index = teb_.sizePoses() / 2;
00541 else
00542 index = teb_.findClosestTrajectoryPose(*(obst->get()));
00543
00544
00545
00546 if ( (index <= 1) || (index > teb_.sizePoses()-2) )
00547 continue;
00548
00549 if (inflated)
00550 {
00551 EdgeInflatedObstacle* dist_bandpt_obst = new EdgeInflatedObstacle;
00552 dist_bandpt_obst->setVertex(0,teb_.PoseVertex(index));
00553 dist_bandpt_obst->setInformation(information_inflated);
00554 dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), obst->get());
00555 optimizer_->addEdge(dist_bandpt_obst);
00556 }
00557 else
00558 {
00559 EdgeObstacle* dist_bandpt_obst = new EdgeObstacle;
00560 dist_bandpt_obst->setVertex(0,teb_.PoseVertex(index));
00561 dist_bandpt_obst->setInformation(information);
00562 dist_bandpt_obst->setParameters(*cfg_, robot_model_.get(), obst->get());
00563 optimizer_->addEdge(dist_bandpt_obst);
00564 }
00565
00566 for (int neighbourIdx=0; neighbourIdx < floor(cfg_->obstacles.obstacle_poses_affected/2); neighbourIdx++)
00567 {
00568 if (index+neighbourIdx < teb_.sizePoses())
00569 {
00570 if (inflated)
00571 {
00572 EdgeInflatedObstacle* dist_bandpt_obst_n_r = new EdgeInflatedObstacle;
00573 dist_bandpt_obst_n_r->setVertex(0,teb_.PoseVertex(index+neighbourIdx));
00574 dist_bandpt_obst_n_r->setInformation(information_inflated);
00575 dist_bandpt_obst_n_r->setParameters(*cfg_, robot_model_.get(), obst->get());
00576 optimizer_->addEdge(dist_bandpt_obst_n_r);
00577 }
00578 else
00579 {
00580 EdgeObstacle* dist_bandpt_obst_n_r = new EdgeObstacle;
00581 dist_bandpt_obst_n_r->setVertex(0,teb_.PoseVertex(index+neighbourIdx));
00582 dist_bandpt_obst_n_r->setInformation(information);
00583 dist_bandpt_obst_n_r->setParameters(*cfg_, robot_model_.get(), obst->get());
00584 optimizer_->addEdge(dist_bandpt_obst_n_r);
00585 }
00586 }
00587 if ( index - neighbourIdx >= 0)
00588 {
00589 if (inflated)
00590 {
00591 EdgeInflatedObstacle* dist_bandpt_obst_n_l = new EdgeInflatedObstacle;
00592 dist_bandpt_obst_n_l->setVertex(0,teb_.PoseVertex(index-neighbourIdx));
00593 dist_bandpt_obst_n_l->setInformation(information_inflated);
00594 dist_bandpt_obst_n_l->setParameters(*cfg_, robot_model_.get(), obst->get());
00595 optimizer_->addEdge(dist_bandpt_obst_n_l);
00596 }
00597 else
00598 {
00599 EdgeObstacle* dist_bandpt_obst_n_l = new EdgeObstacle;
00600 dist_bandpt_obst_n_l->setVertex(0,teb_.PoseVertex(index-neighbourIdx));
00601 dist_bandpt_obst_n_l->setInformation(information);
00602 dist_bandpt_obst_n_l->setParameters(*cfg_, robot_model_.get(), obst->get());
00603 optimizer_->addEdge(dist_bandpt_obst_n_l);
00604 }
00605 }
00606 }
00607
00608 }
00609 }
00610
00611
00612 void TebOptimalPlanner::AddEdgesDynamicObstacles()
00613 {
00614 if (cfg_->optim.weight_obstacle==0 || obstacles_==NULL )
00615 return;
00616
00617 Eigen::Matrix<double,1,1> information;
00618 information.fill(cfg_->optim.weight_dynamic_obstacle);
00619
00620 for (ObstContainer::const_iterator obst = obstacles_->begin(); obst != obstacles_->end(); ++obst)
00621 {
00622 if (!(*obst)->isDynamic())
00623 continue;
00624
00625 for (int i=1; i < teb_.sizePoses() - 1; ++i)
00626 {
00627 EdgeDynamicObstacle* dynobst_edge = new EdgeDynamicObstacle(i);
00628 dynobst_edge->setVertex(0,teb_.PoseVertex(i));
00629
00630 dynobst_edge->setVertex(1,teb_.TimeDiffVertex(i));
00631 dynobst_edge->setInformation(information);
00632 dynobst_edge->setMeasurement(obst->get());
00633 dynobst_edge->setTebConfig(*cfg_);
00634 optimizer_->addEdge(dynobst_edge);
00635 }
00636 }
00637 }
00638
00639 void TebOptimalPlanner::AddEdgesViaPoints()
00640 {
00641 if (cfg_->optim.weight_viapoint==0 || via_points_==NULL || via_points_->empty() )
00642 return;
00643
00644 int start_pose_idx = 0;
00645
00646 int n = teb_.sizePoses();
00647 if (n<3)
00648 return;
00649
00650 for (ViaPointContainer::const_iterator vp_it = via_points_->begin(); vp_it != via_points_->end(); ++vp_it)
00651 {
00652
00653 int index = teb_.findClosestTrajectoryPose(*vp_it, NULL, start_pose_idx);
00654 if (cfg_->trajectory.via_points_ordered)
00655 start_pose_idx = index+2;
00656
00657
00658 if ( index > n-2 )
00659 index = n-2;
00660
00661 if ( index < 1)
00662 index = 1;
00663
00664 Eigen::Matrix<double,1,1> information;
00665 information.fill(cfg_->optim.weight_viapoint);
00666
00667 EdgeViaPoint* edge_viapoint = new EdgeViaPoint;
00668 edge_viapoint->setVertex(0,teb_.PoseVertex(index));
00669 edge_viapoint->setInformation(information);
00670 edge_viapoint->setParameters(*cfg_, &(*vp_it));
00671 optimizer_->addEdge(edge_viapoint);
00672 }
00673 }
00674
00675 void TebOptimalPlanner::AddEdgesVelocity()
00676 {
00677 if (cfg_->robot.max_vel_y == 0)
00678 {
00679 if ( cfg_->optim.weight_max_vel_x==0 && cfg_->optim.weight_max_vel_theta==0)
00680 return;
00681
00682 int n = teb_.sizePoses();
00683 Eigen::Matrix<double,2,2> information;
00684 information(0,0) = cfg_->optim.weight_max_vel_x;
00685 information(1,1) = cfg_->optim.weight_max_vel_theta;
00686 information(0,1) = 0.0;
00687 information(1,0) = 0.0;
00688
00689 for (int i=0; i < n - 1; ++i)
00690 {
00691 EdgeVelocity* velocity_edge = new EdgeVelocity;
00692 velocity_edge->setVertex(0,teb_.PoseVertex(i));
00693 velocity_edge->setVertex(1,teb_.PoseVertex(i+1));
00694 velocity_edge->setVertex(2,teb_.TimeDiffVertex(i));
00695 velocity_edge->setInformation(information);
00696 velocity_edge->setTebConfig(*cfg_);
00697 optimizer_->addEdge(velocity_edge);
00698 }
00699 }
00700 else
00701 {
00702 if ( cfg_->optim.weight_max_vel_x==0 && cfg_->optim.weight_max_vel_y==0 && cfg_->optim.weight_max_vel_theta==0)
00703 return;
00704
00705 int n = teb_.sizePoses();
00706 Eigen::Matrix<double,3,3> information;
00707 information.fill(0);
00708 information(0,0) = cfg_->optim.weight_max_vel_x;
00709 information(1,1) = cfg_->optim.weight_max_vel_y;
00710 information(2,2) = cfg_->optim.weight_max_vel_theta;
00711
00712 for (int i=0; i < n - 1; ++i)
00713 {
00714 EdgeVelocityHolonomic* velocity_edge = new EdgeVelocityHolonomic;
00715 velocity_edge->setVertex(0,teb_.PoseVertex(i));
00716 velocity_edge->setVertex(1,teb_.PoseVertex(i+1));
00717 velocity_edge->setVertex(2,teb_.TimeDiffVertex(i));
00718 velocity_edge->setInformation(information);
00719 velocity_edge->setTebConfig(*cfg_);
00720 optimizer_->addEdge(velocity_edge);
00721 }
00722
00723 }
00724 }
00725
00726 void TebOptimalPlanner::AddEdgesAcceleration()
00727 {
00728 if (cfg_->optim.weight_acc_lim_x==0 && cfg_->optim.weight_acc_lim_theta==0)
00729 return;
00730
00731 int n = teb_.sizePoses();
00732
00733 if (cfg_->robot.max_vel_y == 0 || cfg_->robot.acc_lim_y == 0)
00734 {
00735 Eigen::Matrix<double,2,2> information;
00736 information.fill(0);
00737 information(0,0) = cfg_->optim.weight_acc_lim_x;
00738 information(1,1) = cfg_->optim.weight_acc_lim_theta;
00739
00740
00741 if (vel_start_.first)
00742 {
00743 EdgeAccelerationStart* acceleration_edge = new EdgeAccelerationStart;
00744 acceleration_edge->setVertex(0,teb_.PoseVertex(0));
00745 acceleration_edge->setVertex(1,teb_.PoseVertex(1));
00746 acceleration_edge->setVertex(2,teb_.TimeDiffVertex(0));
00747 acceleration_edge->setInitialVelocity(vel_start_.second);
00748 acceleration_edge->setInformation(information);
00749 acceleration_edge->setTebConfig(*cfg_);
00750 optimizer_->addEdge(acceleration_edge);
00751 }
00752
00753
00754 for (int i=0; i < n - 2; ++i)
00755 {
00756 EdgeAcceleration* acceleration_edge = new EdgeAcceleration;
00757 acceleration_edge->setVertex(0,teb_.PoseVertex(i));
00758 acceleration_edge->setVertex(1,teb_.PoseVertex(i+1));
00759 acceleration_edge->setVertex(2,teb_.PoseVertex(i+2));
00760 acceleration_edge->setVertex(3,teb_.TimeDiffVertex(i));
00761 acceleration_edge->setVertex(4,teb_.TimeDiffVertex(i+1));
00762 acceleration_edge->setInformation(information);
00763 acceleration_edge->setTebConfig(*cfg_);
00764 optimizer_->addEdge(acceleration_edge);
00765 }
00766
00767
00768 if (vel_goal_.first)
00769 {
00770 EdgeAccelerationGoal* acceleration_edge = new EdgeAccelerationGoal;
00771 acceleration_edge->setVertex(0,teb_.PoseVertex(n-2));
00772 acceleration_edge->setVertex(1,teb_.PoseVertex(n-1));
00773 acceleration_edge->setVertex(2,teb_.TimeDiffVertex( teb_.sizeTimeDiffs()-1 ));
00774 acceleration_edge->setGoalVelocity(vel_goal_.second);
00775 acceleration_edge->setInformation(information);
00776 acceleration_edge->setTebConfig(*cfg_);
00777 optimizer_->addEdge(acceleration_edge);
00778 }
00779 }
00780 else
00781 {
00782 Eigen::Matrix<double,3,3> information;
00783 information.fill(0);
00784 information(0,0) = cfg_->optim.weight_acc_lim_x;
00785 information(1,1) = cfg_->optim.weight_acc_lim_y;
00786 information(2,2) = cfg_->optim.weight_acc_lim_theta;
00787
00788
00789 if (vel_start_.first)
00790 {
00791 EdgeAccelerationHolonomicStart* acceleration_edge = new EdgeAccelerationHolonomicStart;
00792 acceleration_edge->setVertex(0,teb_.PoseVertex(0));
00793 acceleration_edge->setVertex(1,teb_.PoseVertex(1));
00794 acceleration_edge->setVertex(2,teb_.TimeDiffVertex(0));
00795 acceleration_edge->setInitialVelocity(vel_start_.second);
00796 acceleration_edge->setInformation(information);
00797 acceleration_edge->setTebConfig(*cfg_);
00798 optimizer_->addEdge(acceleration_edge);
00799 }
00800
00801
00802 for (int i=0; i < n - 2; ++i)
00803 {
00804 EdgeAccelerationHolonomic* acceleration_edge = new EdgeAccelerationHolonomic;
00805 acceleration_edge->setVertex(0,teb_.PoseVertex(i));
00806 acceleration_edge->setVertex(1,teb_.PoseVertex(i+1));
00807 acceleration_edge->setVertex(2,teb_.PoseVertex(i+2));
00808 acceleration_edge->setVertex(3,teb_.TimeDiffVertex(i));
00809 acceleration_edge->setVertex(4,teb_.TimeDiffVertex(i+1));
00810 acceleration_edge->setInformation(information);
00811 acceleration_edge->setTebConfig(*cfg_);
00812 optimizer_->addEdge(acceleration_edge);
00813 }
00814
00815
00816 if (vel_goal_.first)
00817 {
00818 EdgeAccelerationHolonomicGoal* acceleration_edge = new EdgeAccelerationHolonomicGoal;
00819 acceleration_edge->setVertex(0,teb_.PoseVertex(n-2));
00820 acceleration_edge->setVertex(1,teb_.PoseVertex(n-1));
00821 acceleration_edge->setVertex(2,teb_.TimeDiffVertex( teb_.sizeTimeDiffs()-1 ));
00822 acceleration_edge->setGoalVelocity(vel_goal_.second);
00823 acceleration_edge->setInformation(information);
00824 acceleration_edge->setTebConfig(*cfg_);
00825 optimizer_->addEdge(acceleration_edge);
00826 }
00827 }
00828 }
00829
00830
00831
00832 void TebOptimalPlanner::AddEdgesTimeOptimal()
00833 {
00834 if (cfg_->optim.weight_optimaltime==0)
00835 return;
00836
00837 Eigen::Matrix<double,1,1> information;
00838 information.fill(cfg_->optim.weight_optimaltime);
00839
00840 for (int i=0; i < teb_.sizeTimeDiffs(); ++i)
00841 {
00842 EdgeTimeOptimal* timeoptimal_edge = new EdgeTimeOptimal;
00843 timeoptimal_edge->setVertex(0,teb_.TimeDiffVertex(i));
00844 timeoptimal_edge->setInformation(information);
00845 timeoptimal_edge->setTebConfig(*cfg_);
00846 optimizer_->addEdge(timeoptimal_edge);
00847 }
00848 }
00849
00850
00851
00852 void TebOptimalPlanner::AddEdgesKinematicsDiffDrive()
00853 {
00854 if (cfg_->optim.weight_kinematics_nh==0 && cfg_->optim.weight_kinematics_forward_drive==0)
00855 return;
00856
00857
00858 Eigen::Matrix<double,2,2> information_kinematics;
00859 information_kinematics.fill(0.0);
00860 information_kinematics(0, 0) = cfg_->optim.weight_kinematics_nh;
00861 information_kinematics(1, 1) = cfg_->optim.weight_kinematics_forward_drive;
00862
00863 for (int i=0; i < teb_.sizePoses()-1; i++)
00864 {
00865 EdgeKinematicsDiffDrive* kinematics_edge = new EdgeKinematicsDiffDrive;
00866 kinematics_edge->setVertex(0,teb_.PoseVertex(i));
00867 kinematics_edge->setVertex(1,teb_.PoseVertex(i+1));
00868 kinematics_edge->setInformation(information_kinematics);
00869 kinematics_edge->setTebConfig(*cfg_);
00870 optimizer_->addEdge(kinematics_edge);
00871 }
00872 }
00873
00874 void TebOptimalPlanner::AddEdgesKinematicsCarlike()
00875 {
00876 if (cfg_->optim.weight_kinematics_nh==0 && cfg_->optim.weight_kinematics_turning_radius)
00877 return;
00878
00879
00880 Eigen::Matrix<double,2,2> information_kinematics;
00881 information_kinematics.fill(0.0);
00882 information_kinematics(0, 0) = cfg_->optim.weight_kinematics_nh;
00883 information_kinematics(1, 1) = cfg_->optim.weight_kinematics_turning_radius;
00884
00885 for (int i=0; i < teb_.sizePoses()-1; i++)
00886 {
00887 EdgeKinematicsCarlike* kinematics_edge = new EdgeKinematicsCarlike;
00888 kinematics_edge->setVertex(0,teb_.PoseVertex(i));
00889 kinematics_edge->setVertex(1,teb_.PoseVertex(i+1));
00890 kinematics_edge->setInformation(information_kinematics);
00891 kinematics_edge->setTebConfig(*cfg_);
00892 optimizer_->addEdge(kinematics_edge);
00893 }
00894 }
00895
00896
00897 void TebOptimalPlanner::computeCurrentCost(double obst_cost_scale, double viapoint_cost_scale, bool alternative_time_cost)
00898 {
00899
00900 bool graph_exist_flag(false);
00901 if (optimizer_->edges().empty() && optimizer_->vertices().empty())
00902 {
00903
00904
00905 buildGraph();
00906 optimizer_->initializeOptimization();
00907 }
00908 else
00909 {
00910 graph_exist_flag = true;
00911 }
00912
00913 optimizer_->computeInitialGuess();
00914
00915 cost_ = 0;
00916
00917 if (alternative_time_cost)
00918 {
00919 cost_ += teb_.getSumOfAllTimeDiffs();
00920
00921
00922 }
00923
00924
00925
00926 for (std::vector<g2o::OptimizableGraph::Edge*>::const_iterator it = optimizer_->activeEdges().begin(); it!= optimizer_->activeEdges().end(); it++)
00927 {
00928 EdgeTimeOptimal* edge_time_optimal = dynamic_cast<EdgeTimeOptimal*>(*it);
00929 if (edge_time_optimal!=NULL && !alternative_time_cost)
00930 {
00931 cost_ += edge_time_optimal->getError().squaredNorm();
00932 continue;
00933 }
00934
00935 EdgeKinematicsDiffDrive* edge_kinematics_dd = dynamic_cast<EdgeKinematicsDiffDrive*>(*it);
00936 if (edge_kinematics_dd!=NULL)
00937 {
00938 cost_ += edge_kinematics_dd->getError().squaredNorm();
00939 continue;
00940 }
00941
00942 EdgeKinematicsCarlike* edge_kinematics_cl = dynamic_cast<EdgeKinematicsCarlike*>(*it);
00943 if (edge_kinematics_cl!=NULL)
00944 {
00945 cost_ += edge_kinematics_cl->getError().squaredNorm();
00946 continue;
00947 }
00948
00949 EdgeVelocity* edge_velocity = dynamic_cast<EdgeVelocity*>(*it);
00950 if (edge_velocity!=NULL)
00951 {
00952 cost_ += edge_velocity->getError().squaredNorm();
00953 continue;
00954 }
00955
00956 EdgeAcceleration* edge_acceleration = dynamic_cast<EdgeAcceleration*>(*it);
00957 if (edge_acceleration!=NULL)
00958 {
00959 cost_ += edge_acceleration->getError().squaredNorm();
00960 continue;
00961 }
00962
00963 EdgeObstacle* edge_obstacle = dynamic_cast<EdgeObstacle*>(*it);
00964 if (edge_obstacle!=NULL)
00965 {
00966 cost_ += edge_obstacle->getError().squaredNorm() * obst_cost_scale;
00967 continue;
00968 }
00969
00970 EdgeInflatedObstacle* edge_inflated_obstacle = dynamic_cast<EdgeInflatedObstacle*>(*it);
00971 if (edge_inflated_obstacle!=NULL)
00972 {
00973 cost_ += std::sqrt(std::pow(edge_inflated_obstacle->getError()[0],2) * obst_cost_scale
00974 + std::pow(edge_inflated_obstacle->getError()[1],2));
00975 continue;
00976 }
00977
00978 EdgeDynamicObstacle* edge_dyn_obstacle = dynamic_cast<EdgeDynamicObstacle*>(*it);
00979 if (edge_dyn_obstacle!=NULL)
00980 {
00981 cost_ += edge_dyn_obstacle->getError().squaredNorm() * obst_cost_scale;
00982 continue;
00983 }
00984
00985 EdgeViaPoint* edge_viapoint = dynamic_cast<EdgeViaPoint*>(*it);
00986 if (edge_viapoint!=NULL)
00987 {
00988 cost_ += edge_viapoint->getError().squaredNorm() * viapoint_cost_scale;
00989 continue;
00990 }
00991 }
00992
00993
00994 if (!graph_exist_flag)
00995 clearGraph();
00996 }
00997
00998
00999 void TebOptimalPlanner::extractVelocity(const PoseSE2& pose1, const PoseSE2& pose2, double dt, double& vx, double& vy, double& omega) const
01000 {
01001 if (dt == 0)
01002 {
01003 vx = 0;
01004 vy = 0;
01005 omega = 0;
01006 return;
01007 }
01008
01009 Eigen::Vector2d deltaS = pose2.position() - pose1.position();
01010
01011 if (cfg_->robot.max_vel_y == 0)
01012 {
01013 Eigen::Vector2d conf1dir( cos(pose1.theta()), sin(pose1.theta()) );
01014
01015 double dir = deltaS.dot(conf1dir);
01016 vx = (double) g2o::sign(dir) * deltaS.norm()/dt;
01017 vy = 0;
01018 }
01019 else
01020 {
01021
01022
01023
01024 double cos_theta1 = std::cos(pose1.theta());
01025 double sin_theta1 = std::sin(pose1.theta());
01026 double p1_dx = cos_theta1*deltaS.x() + sin_theta1*deltaS.y();
01027 double p1_dy = -sin_theta1*deltaS.x() + cos_theta1*deltaS.y();
01028 vx = p1_dx / dt;
01029 vy = p1_dy / dt;
01030 }
01031
01032
01033 double orientdiff = g2o::normalize_theta(pose2.theta() - pose1.theta());
01034 omega = orientdiff/dt;
01035 }
01036
01037 bool TebOptimalPlanner::getVelocityCommand(double& vx, double& vy, double& omega) const
01038 {
01039 if (teb_.sizePoses()<2)
01040 {
01041 ROS_ERROR("TebOptimalPlanner::getVelocityCommand(): The trajectory contains less than 2 poses. Make sure to init and optimize/plan the trajectory fist.");
01042 vx = 0;
01043 vy = 0;
01044 omega = 0;
01045 return false;
01046 }
01047
01048 double dt = teb_.TimeDiff(0);
01049 if (dt<=0)
01050 {
01051 ROS_ERROR("TebOptimalPlanner::getVelocityCommand() - timediff<=0 is invalid!");
01052 vx = 0;
01053 vy = 0;
01054 omega = 0;
01055 return false;
01056 }
01057
01058
01059 extractVelocity(teb_.Pose(0), teb_.Pose(1), dt, vx, vy, omega);
01060 return true;
01061 }
01062
01063 void TebOptimalPlanner::getVelocityProfile(std::vector<geometry_msgs::Twist>& velocity_profile) const
01064 {
01065 int n = teb_.sizePoses();
01066 velocity_profile.resize( n+1 );
01067
01068
01069 velocity_profile.front().linear.z = 0;
01070 velocity_profile.front().angular.x = velocity_profile.front().angular.y = 0;
01071 velocity_profile.front().linear.x = vel_start_.second.linear.x;
01072 velocity_profile.front().linear.y = vel_start_.second.linear.y;
01073 velocity_profile.front().angular.z = vel_start_.second.angular.z;
01074
01075 for (int i=1; i<n; ++i)
01076 {
01077 velocity_profile[i].linear.z = 0;
01078 velocity_profile[i].angular.x = velocity_profile[i].angular.y = 0;
01079 extractVelocity(teb_.Pose(i-1), teb_.Pose(i), teb_.TimeDiff(i-1), velocity_profile[i].linear.x, velocity_profile[i].linear.y, velocity_profile[i].angular.z);
01080 }
01081
01082
01083 velocity_profile.back().linear.z = 0;
01084 velocity_profile.back().angular.x = velocity_profile.back().angular.y = 0;
01085 velocity_profile.back().linear.x = vel_goal_.second.linear.x;
01086 velocity_profile.back().linear.y = vel_goal_.second.linear.y;
01087 velocity_profile.back().angular.z = vel_goal_.second.angular.z;
01088 }
01089
01090 void TebOptimalPlanner::getFullTrajectory(std::vector<TrajectoryPointMsg>& trajectory) const
01091 {
01092 int n = teb_.sizePoses();
01093
01094 trajectory.resize(n);
01095
01096 if (n == 0)
01097 return;
01098
01099 double curr_time = 0;
01100
01101
01102 TrajectoryPointMsg& start = trajectory.front();
01103 teb_.Pose(0).toPoseMsg(start.pose);
01104 start.velocity.linear.z = 0;
01105 start.velocity.angular.x = start.velocity.angular.y = 0;
01106 start.velocity.linear.x = vel_start_.second.linear.x;
01107 start.velocity.linear.y = vel_start_.second.linear.y;
01108 start.velocity.angular.z = vel_start_.second.angular.z;
01109 start.time_from_start.fromSec(curr_time);
01110
01111 curr_time += teb_.TimeDiff(0);
01112
01113
01114 for (int i=1; i < n-1; ++i)
01115 {
01116 TrajectoryPointMsg& point = trajectory[i];
01117 teb_.Pose(i).toPoseMsg(point.pose);
01118 point.velocity.linear.z = 0;
01119 point.velocity.angular.x = point.velocity.angular.y = 0;
01120 double vel1_x, vel1_y, vel2_x, vel2_y, omega1, omega2;
01121 extractVelocity(teb_.Pose(i-1), teb_.Pose(i), teb_.TimeDiff(i-1), vel1_x, vel1_y, omega1);
01122 extractVelocity(teb_.Pose(i), teb_.Pose(i+1), teb_.TimeDiff(i), vel2_x, vel2_y, omega2);
01123 point.velocity.linear.x = 0.5*(vel1_x+vel2_x);
01124 point.velocity.linear.y = 0.5*(vel1_y+vel2_y);
01125 point.velocity.angular.z = 0.5*(omega1+omega2);
01126 point.time_from_start.fromSec(curr_time);
01127
01128 curr_time += teb_.TimeDiff(i);
01129 }
01130
01131
01132 TrajectoryPointMsg& goal = trajectory.back();
01133 teb_.BackPose().toPoseMsg(goal.pose);
01134 goal.velocity.linear.z = 0;
01135 goal.velocity.angular.x = goal.velocity.angular.y = 0;
01136 goal.velocity.linear.x = vel_goal_.second.linear.x;
01137 goal.velocity.linear.y = vel_goal_.second.linear.y;
01138 goal.velocity.angular.z = vel_goal_.second.angular.z;
01139 goal.time_from_start.fromSec(curr_time);
01140 }
01141
01142
01143 bool TebOptimalPlanner::isTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector<geometry_msgs::Point>& footprint_spec,
01144 double inscribed_radius, double circumscribed_radius, int look_ahead_idx)
01145 {
01146 if (look_ahead_idx < 0 || look_ahead_idx >= teb().sizePoses())
01147 look_ahead_idx = teb().sizePoses() - 1;
01148
01149 for (int i=0; i <= look_ahead_idx; ++i)
01150 {
01151 if ( costmap_model->footprintCost(teb().Pose(i).x(), teb().Pose(i).y(), teb().Pose(i).theta(), footprint_spec, inscribed_radius, circumscribed_radius) < 0 )
01152 return false;
01153
01154
01155
01156 if (i<look_ahead_idx)
01157 {
01158 if ( (teb().Pose(i+1).position()-teb().Pose(i).position()).norm() > inscribed_radius)
01159 {
01160
01161 PoseSE2 center = PoseSE2::average(teb().Pose(i), teb().Pose(i+1));
01162 if ( costmap_model->footprintCost(center.x(), center.y(), center.theta(), footprint_spec, inscribed_radius, circumscribed_radius) < 0 )
01163 return false;
01164 }
01165
01166 }
01167 }
01168 return true;
01169 }
01170
01171
01172 bool TebOptimalPlanner::isHorizonReductionAppropriate(const std::vector<geometry_msgs::PoseStamped>& initial_plan) const
01173 {
01174 if (teb_.sizePoses() < int( 1.5*double(cfg_->trajectory.min_samples) ) )
01175 return false;
01176
01177
01178 double dist = 0;
01179 for (int i=1; i < teb_.sizePoses(); ++i)
01180 {
01181 dist += ( teb_.Pose(i).position() - teb_.Pose(i-1).position() ).norm();
01182 if (dist > 2)
01183 break;
01184 }
01185 if (dist <= 2)
01186 return false;
01187
01188
01189
01190
01191
01192
01193 if ( std::abs( g2o::normalize_theta( teb_.Pose(0).theta() - teb_.BackPose().theta() ) ) > M_PI/2)
01194 {
01195 ROS_DEBUG("TebOptimalPlanner::isHorizonReductionAppropriate(): Goal orientation - start orientation > 90° ");
01196 return true;
01197 }
01198
01199
01200 if (teb_.Pose(0).orientationUnitVec().dot(teb_.BackPose().position() - teb_.Pose(0).position()) < 0)
01201 {
01202 ROS_DEBUG("TebOptimalPlanner::isHorizonReductionAppropriate(): Goal heading - start orientation > 90° ");
01203 return true;
01204 }
01205
01206
01207 int idx=0;
01208 for (; idx < (int)initial_plan.size(); ++idx)
01209 {
01210 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)) )
01211 break;
01212 }
01213
01214 double ref_path_length = 0;
01215 for (; idx < int(initial_plan.size())-1; ++idx)
01216 {
01217 ref_path_length += std::sqrt(std::pow(initial_plan[idx+1].pose.position.x-initial_plan[idx].pose.position.x, 2)
01218 + std::pow(initial_plan[idx+1].pose.position.y-initial_plan[idx].pose.position.y, 2) );
01219 }
01220
01221
01222 double teb_length = 0;
01223 for (int i = 1; i < teb_.sizePoses(); ++i )
01224 {
01225 double dist = (teb_.Pose(i).position() - teb_.Pose(i-1).position()).norm();
01226 if (dist > 0.95*cfg_->obstacles.min_obstacle_dist)
01227 {
01228 ROS_DEBUG("TebOptimalPlanner::isHorizonReductionAppropriate(): Distance between consecutive poses > 0.9*min_obstacle_dist");
01229 return true;
01230 }
01231 ref_path_length += dist;
01232 }
01233 if (ref_path_length>0 && teb_length/ref_path_length < 0.7)
01234 {
01235 ROS_DEBUG("TebOptimalPlanner::isHorizonReductionAppropriate(): Planned trajectory is at least 30° shorter than the initial plan");
01236 return true;
01237 }
01238
01239
01240
01241 return false;
01242 }
01243
01244 }