optimal_planner.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the institute nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Author: Christoph Rösmann
37  *********************************************************************/
38 
39 #ifndef OPTIMAL_PLANNER_H_
40 #define OPTIMAL_PLANNER_H_
41 
42 #include <math.h>
43 
44 
45 // teb stuff
47 #include <teb_local_planner/misc.h>
52 
53 // g2o lib stuff
54 #include <g2o/core/sparse_optimizer.h>
55 #include <g2o/core/block_solver.h>
56 #include <g2o/core/factory.h>
57 #include <g2o/core/optimization_algorithm_gauss_newton.h>
58 #include <g2o/core/optimization_algorithm_levenberg.h>
59 #include <g2o/solvers/csparse/linear_solver_csparse.h>
60 #include <g2o/solvers/cholmod/linear_solver_cholmod.h>
61 
62 // messages
63 #include <nav_msgs/Path.h>
64 #include <geometry_msgs/PoseStamped.h>
65 #include <tf/transform_datatypes.h>
66 #include <teb_local_planner/TrajectoryMsg.h>
67 
68 #include <nav_msgs/Odometry.h>
69 #include <limits.h>
70 
71 namespace teb_local_planner
72 {
73 
75 typedef g2o::BlockSolver< g2o::BlockSolverTraits<-1, -1> > TEBBlockSolver;
76 
78 typedef g2o::LinearSolverCSparse<TEBBlockSolver::PoseMatrixType> TEBLinearSolver;
79 //typedef g2o::LinearSolverCholmod<TEBBlockSolver::PoseMatrixType> TEBLinearSolver;
80 
82 typedef std::vector< Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> > ViaPointContainer;
83 
84 
100 class TebOptimalPlanner : public PlannerInterface
101 {
102 public:
103 
108 
116  TebOptimalPlanner(const TebConfig& cfg, ObstContainer* obstacles = NULL,
118 
122  virtual ~TebOptimalPlanner();
123 
131  void initialize(const TebConfig& cfg, ObstContainer* obstacles = NULL,
133 
136 
154  virtual bool plan(const std::vector<geometry_msgs::PoseStamped>& initial_plan, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false);
155 
172  virtual bool plan(const tf::Pose& start, const tf::Pose& goal, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false);
173 
190  virtual bool plan(const PoseSE2& start, const PoseSE2& goal, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false);
191 
192 
202  virtual bool getVelocityCommand(double& vx, double& vy, double& omega, int look_ahead_poses) const;
203 
204 
231  bool optimizeTEB(int iterations_innerloop, int iterations_outerloop, bool compute_cost_afterwards = false,
232  double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false);
233 
235 
236 
239 
240 
247  void setVelocityStart(const geometry_msgs::Twist& vel_start);
248 
254  void setVelocityGoal(const geometry_msgs::Twist& vel_goal);
255 
260  void setVelocityGoalFree() {vel_goal_.first = false;}
261 
263 
264 
267 
268 
275 
280  const ObstContainer& getObstVector() const {return *obstacles_;}
281 
283 
286 
287 
294 
299  const ViaPointContainer& getViaPoints() const {return *via_points_;}
300 
302 
303 
306 
312  void setVisualization(TebVisualizationPtr visualization);
313 
320  virtual void visualize();
321 
323 
324 
327 
331  virtual void clearPlanner()
332  {
333  clearGraph();
335  }
336 
345  virtual void setPreferredTurningDir(RotType dir) {prefer_rotdir_=dir;}
346 
353  static void registerG2OTypes();
354 
360  TimedElasticBand& teb() {return teb_;};
361 
366  const TimedElasticBand& teb() const {return teb_;};
367 
374 
380 
386  bool isOptimized() const {return optimized_;};
387 
391  bool hasDiverged() const override;
392 
414  void computeCurrentCost(double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false);
415 
424  virtual void computeCurrentCost(std::vector<double>& cost, double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false)
425  {
426  computeCurrentCost(obst_cost_scale, viapoint_cost_scale, alternative_time_cost);
427  cost.push_back( getCurrentCost() );
428  }
429 
437  double getCurrentCost() const {return cost_;}
438 
439 
452  inline void extractVelocity(const PoseSE2& pose1, const PoseSE2& pose2, double dt, double& vx, double& vy, double& omega) const;
453 
472  void getVelocityProfile(std::vector<geometry_msgs::Twist>& velocity_profile) const;
473 
485  void getFullTrajectory(std::vector<TrajectoryPointMsg>& trajectory) const;
486 
500  virtual bool isTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector<geometry_msgs::Point>& footprint_spec, double inscribed_radius = 0.0,
501  double circumscribed_radius=0.0, int look_ahead_idx=-1, double feasibility_check_lookahead_distance=-1.0);
502 
504 
505 protected:
506 
509 
522  bool buildGraph(double weight_multiplier=1.0);
523 
536  bool optimizeGraph(int no_iterations, bool clear_after=true);
537 
543  void clearGraph();
544 
557  void AddTEBVertices();
558 
565  void AddEdgesVelocity();
566 
575  void AddEdgesAcceleration();
576 
583  void AddEdgesTimeOptimal();
584 
591  void AddEdgesShortestPath();
592 
601  void AddEdgesObstacles(double weight_multiplier=1.0);
602 
610  void AddEdgesObstaclesLegacy(double weight_multiplier=1.0);
611 
618  void AddEdgesViaPoints();
619 
630  void AddEdgesDynamicObstacles(double weight_multiplier=1.0);
631 
640 
649 
655  void AddEdgesPreferRotDir();
656 
663 
665 
666 
672 
673 
674  // external objects (store weak pointers)
675  const TebConfig* cfg_;
678  std::vector<ObstContainer> obstacles_per_vertex_;
679 
680  double cost_;
682 
683  // internal objects (memory management owned)
687  std::pair<bool, geometry_msgs::Twist> vel_start_;
688  std::pair<bool, geometry_msgs::Twist> vel_goal_;
689 
690  bool initialized_;
691  bool optimized_;
692 
693 public:
694  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
695 };
696 
702 typedef std::vector< TebOptimalPlannerPtr > TebOptPlannerContainer;
703 
704 } // namespace teb_local_planner
705 
706 #endif /* OPTIMAL_PLANNER_H_ */
teb_local_planner::TebOptimalPlanner::optimizer
boost::shared_ptr< g2o::SparseOptimizer > optimizer()
Access the internal g2o optimizer.
Definition: optimal_planner.h:409
teb_local_planner::TebOptimalPlanner::hasDiverged
bool hasDiverged() const override
Returns true if the planner has diverged.
Definition: optimal_planner.cpp:1059
teb_local_planner::TebOptimalPlanner::getVelocityProfile
void getVelocityProfile(std::vector< geometry_msgs::Twist > &velocity_profile) const
Compute the velocity profile of the trajectory.
Definition: optimal_planner.cpp:1206
teb_local_planner::TebOptimalPlanner::AddEdgesVelocity
void AddEdgesVelocity()
Add all edges (local cost functions) for limiting the translational and angular velocity.
Definition: optimal_planner.cpp:756
cmd_vel_to_ackermann_drive.Twist
Twist
Definition: cmd_vel_to_ackermann_drive.py:56
teb_local_planner::TebOptimalPlanner::vel_start_
std::pair< bool, geometry_msgs::Twist > vel_start_
Store the initial velocity at the start pose.
Definition: optimal_planner.h:723
teb_local_planner::TebOptimalPlanner::optimizeTEB
bool optimizeTEB(int iterations_innerloop, int iterations_outerloop, bool compute_cost_afterwards=false, double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false)
Optimize a previously initialized trajectory (actual TEB optimization loop).
Definition: optimal_planner.cpp:218
teb_local_planner::TebOptimalPlanner::cost_
double cost_
Store cost value of the current hyper-graph.
Definition: optimal_planner.h:716
boost::shared_ptr< TebVisualization >
via_points
ViaPointContainer via_points
Definition: test_optim_node.cpp:55
teb_local_planner::TebOptimalPlanner::vel_goal_
std::pair< bool, geometry_msgs::Twist > vel_goal_
Store the final velocity at the goal pose.
Definition: optimal_planner.h:724
teb_local_planner::TebOptimalPlanner::AddEdgesKinematicsDiffDrive
void AddEdgesKinematicsDiffDrive()
Add all edges (local cost functions) for satisfying kinematic constraints of a differential drive rob...
Definition: optimal_planner.cpp:952
teb_local_planner::TimedElasticBand
Class that defines a trajectory modeled as an elastic band with augmented tempoarl information.
Definition: timed_elastic_band.h:122
teb_local_planner::TebOptimalPlanner::computeCurrentCost
void computeCurrentCost(double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false)
Compute the cost vector of a given optimization problen (hyper-graph must exist).
Definition: optimal_planner.cpp:1077
teb_local_planner::TebOptimalPlanner::setVelocityGoal
void setVelocityGoal(const geometry_msgs::Twist &vel_goal)
Set the desired final velocity at the trajectory's goal pose.
Definition: optimal_planner.cpp:277
teb_local_planner::TebOptimalPlanner::initOptimizer
boost::shared_ptr< g2o::SparseOptimizer > initOptimizer()
Initialize and configure the g2o sparse optimizer.
Definition: optimal_planner.cpp:197
teb_local_planner::TebOptimalPlanner::isTrajectoryFeasible
virtual bool isTrajectoryFeasible(base_local_planner::CostmapModel *costmap_model, const std::vector< geometry_msgs::Point > &footprint_spec, double inscribed_radius=0.0, double circumscribed_radius=0.0, int look_ahead_idx=-1, double feasibility_check_lookahead_distance=-1.0)
Check whether the planned trajectory is feasible or not.
Definition: optimal_planner.cpp:1286
teb_local_planner::TebOptimalPlanner::getViaPoints
const ViaPointContainer & getViaPoints() const
Access the internal via-point container.
Definition: optimal_planner.h:335
teb_local_planner::TebOptimalPlanner::AddEdgesTimeOptimal
void AddEdgesTimeOptimal()
Add all edges (local cost functions) for minimizing the transition time (resp. minimize time differen...
Definition: optimal_planner.cpp:913
teb_local_planner::TebOptimalPlanner::setObstVector
void setObstVector(ObstContainer *obst_vector)
Assign a new set of obstacles.
Definition: optimal_planner.h:310
teb_local_planner::TebOptimalPlanner::AddEdgesDynamicObstacles
void AddEdgesDynamicObstacles(double weight_multiplier=1.0)
Add all edges (local cost functions) related to keeping a distance from dynamic (moving) obstacles.
Definition: optimal_planner.cpp:682
teb_local_planner::RotType
RotType
Symbols for left/none/right rotations
Definition: misc.h:89
teb_local_planner::TebOptimalPlannerConstPtr
boost::shared_ptr< const TebOptimalPlanner > TebOptimalPlannerConstPtr
Abbrev. for shared const TebOptimalPlanner pointers.
Definition: optimal_planner.h:736
teb_local_planner::TebOptimalPlanner::AddEdgesVelocityObstacleRatio
void AddEdgesVelocityObstacleRatio()
Add all edges (local cost function) for reducing the velocity of a vertex due to its associated obsta...
Definition: optimal_planner.cpp:1035
teb_local_planner::TebOptimalPlanner::clearGraph
void clearGraph()
Clear an existing internal hyper-graph.
Definition: optimal_planner.cpp:440
teb_local_planner::TebOptimalPlannerPtr
boost::shared_ptr< TebOptimalPlanner > TebOptimalPlannerPtr
Abbrev. for shared instances of the TebOptimalPlanner.
Definition: optimal_planner.h:734
teb_local_planner::TebOptimalPlanner::getCurrentCost
double getCurrentCost() const
Access the cost vector.
Definition: optimal_planner.h:473
teb_local_planner::TebOptimalPlanner::obstacles_
ObstContainer * obstacles_
Store obstacles that are relevant for planning.
Definition: optimal_planner.h:712
teb_local_planner::TebOptimalPlanner::AddEdgesPreferRotDir
void AddEdgesPreferRotDir()
Add all edges (local cost functions) for prefering a specifiy turning direction (by penalizing the ot...
Definition: optimal_planner.cpp:997
teb_local_planner::TebOptimalPlanner::setVisualization
void setVisualization(TebVisualizationPtr visualization)
Register a TebVisualization class to enable visiualization routines (e.g. publish the local plan and ...
Definition: optimal_planner.cpp:143
base_local_planner::CostmapModel
teb_local_planner::TebOptimalPlanner::getVelocityCommand
virtual bool getVelocityCommand(double &vx, double &vy, double &omega, int look_ahead_poses) const
Get the velocity command from a previously optimized plan to control the robot at the current samplin...
Definition: optimal_planner.cpp:1171
misc.h
teb_local_planner::TebOptimalPlanner::AddTEBVertices
void AddTEBVertices()
Add all relevant vertices to the hyper-graph as optimizable variables.
Definition: optimal_planner.cpp:458
teb_local_planner::TebOptimalPlanner::visualization_
TebVisualizationPtr visualization_
Instance of the visualization class.
Definition: optimal_planner.h:720
visual
TebVisualizationPtr visual
Definition: test_optim_node.cpp:53
teb_local_planner::TebOptimalPlanner::initialized_
bool initialized_
Keeps track about the correct initialization of this class.
Definition: optimal_planner.h:726
visualize_velocity_profile.trajectory
list trajectory
Definition: visualize_velocity_profile.py:72
teb_local_planner::TebOptimalPlanner::~TebOptimalPlanner
virtual ~TebOptimalPlanner()
Destruct the optimal planner.
Definition: optimal_planner.cpp:108
teb_local_planner::TebOptimalPlanner::visualize
virtual void visualize()
Publish the local plan and pose sequence via ros topics (e.g. subscribe with rviz).
Definition: optimal_planner.cpp:148
teb_config.h
timed_elastic_band.h
teb_local_planner::ObstContainer
std::vector< ObstaclePtr > ObstContainer
Abbrev. for containers storing multiple obstacles.
Definition: obstacles.h:333
obst_vector
std::vector< ObstaclePtr > obst_vector
Definition: test_optim_node.cpp:54
planner_interface.h
robot_footprint_model.h
teb_local_planner::TebOptimalPlanner::setViaPoints
void setViaPoints(const ViaPointContainer *via_points)
Assign a new set of via-points.
Definition: optimal_planner.h:329
teb_local_planner::TEBBlockSolver
g2o::BlockSolver< g2o::BlockSolverTraits<-1, -1 > > TEBBlockSolver
Typedef for the block solver utilized for optimization.
Definition: optimal_planner.h:111
teb_local_planner::TebOptimalPlanner::extractVelocity
void extractVelocity(const PoseSE2 &pose1, const PoseSE2 &pose2, double dt, double &vx, double &vy, double &omega) const
Extract the velocity from consecutive poses and a time difference (including strafing velocity for ho...
Definition: optimal_planner.cpp:1133
teb_local_planner::TebOptimalPlanner::AddEdgesViaPoints
void AddEdgesViaPoints()
Add all edges (local cost functions) related to minimizing the distance to via-points.
Definition: optimal_planner.cpp:711
teb_local_planner::TebOptimalPlanner::obstacles_per_vertex_
std::vector< ObstContainer > obstacles_per_vertex_
Store the obstacles associated with the n-1 initial vertices.
Definition: optimal_planner.h:714
teb_local_planner::TebVisualizationPtr
boost::shared_ptr< TebVisualization > TebVisualizationPtr
Abbrev. for shared instances of the TebVisualization.
Definition: visualization.h:311
teb_local_planner::TebOptimalPlanner::buildGraph
bool buildGraph(double weight_multiplier=1.0)
Build the hyper-graph representing the TEB optimization problem.
Definition: optimal_planner.cpp:359
teb_local_planner::TebOptimalPlanner::teb_
TimedElasticBand teb_
Actual trajectory object.
Definition: optimal_planner.h:721
tf::Transform
teb_local_planner::TebOptimalPlanner::initialize
void initialize(const TebConfig &cfg, ObstContainer *obstacles=NULL, TebVisualizationPtr visual=TebVisualizationPtr(), const ViaPointContainer *via_points=NULL)
Initializes the optimal planner.
Definition: optimal_planner.cpp:118
teb_local_planner::TebOptimalPlanner::via_points_
const ViaPointContainer * via_points_
Store via points for planning.
Definition: optimal_planner.h:713
teb_local_planner::TebOptimalPlanner::prefer_rotdir_
RotType prefer_rotdir_
Store whether to prefer a specific initial rotation in optimization (might be activated in case the r...
Definition: optimal_planner.h:717
teb_local_planner::TebOptimalPlanner::setPreferredTurningDir
virtual void setPreferredTurningDir(RotType dir)
Prefer a desired initial turning direction (by penalizing the opposing one)
Definition: optimal_planner.h:381
teb_local_planner::TebOptimalPlanner::registerG2OTypes
static void registerG2OTypes()
Register the vertices and edges defined for the TEB to the g2o::Factory.
Definition: optimal_planner.cpp:167
teb_local_planner::TebConfig
Config class for the teb_local_planner and its components.
Definition: teb_config.h:62
teb_local_planner::PoseSE2
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
Definition: pose_se2.h:93
transform_datatypes.h
teb_local_planner::TebOptimalPlanner::getObstVector
const ObstContainer & getObstVector() const
Access the internal obstacle container.
Definition: optimal_planner.h:316
teb_local_planner::TebOptimalPlanner::TebOptimalPlanner
TebOptimalPlanner()
Default constructor.
Definition: optimal_planner.cpp:98
teb_local_planner::TebOptimalPlanner::setVelocityGoalFree
void setVelocityGoalFree()
Set the desired final velocity at the trajectory's goal pose to be the maximum velocity limit.
Definition: optimal_planner.h:296
teb_local_planner::TebOptimalPlanner::AddEdgesObstaclesLegacy
void AddEdgesObstaclesLegacy(double weight_multiplier=1.0)
Add all edges (local cost functions) related to keeping a distance from static obstacles (legacy asso...
Definition: optimal_planner.cpp:587
teb_local_planner::TebOptimalPlanner::optimizer_
boost::shared_ptr< g2o::SparseOptimizer > optimizer_
g2o optimizer for trajectory optimization
Definition: optimal_planner.h:722
teb_local_planner::TebOptimalPlanner::AddEdgesKinematicsCarlike
void AddEdgesKinematicsCarlike()
Add all edges (local cost functions) for satisfying kinematic constraints of a carlike robot.
Definition: optimal_planner.cpp:974
teb_local_planner::TebOptPlannerContainer
std::vector< TebOptimalPlannerPtr > TebOptPlannerContainer
Abbrev. for containers storing multiple teb optimal planners.
Definition: optimal_planner.h:738
teb_local_planner::TebOptimalPlanner::optimizeGraph
bool optimizeGraph(int no_iterations, bool clear_after=true)
Optimize the previously constructed hyper-graph to deform / optimize the TEB.
Definition: optimal_planner.cpp:404
teb_local_planner::TEBLinearSolver
g2o::LinearSolverCSparse< TEBBlockSolver::PoseMatrixType > TEBLinearSolver
Typedef for the linear solver utilized for optimization.
Definition: optimal_planner.h:114
teb_local_planner::TebOptimalPlanner::getFullTrajectory
void getFullTrajectory(std::vector< TrajectoryPointMsg > &trajectory) const
Return the complete trajectory including poses, velocity profiles and temporal information.
Definition: optimal_planner.cpp:1233
teb_local_planner::TebOptimalPlanner::AddEdgesShortestPath
void AddEdgesShortestPath()
Add all edges (local cost functions) for minimizing the path length.
Definition: optimal_planner.cpp:931
teb_local_planner::TebOptimalPlanner::teb
TimedElasticBand & teb()
Access the internal TimedElasticBand trajectory.
Definition: optimal_planner.h:396
teb_local_planner::TebOptimalPlanner::isOptimized
bool isOptimized() const
Check if last optimization was successful.
Definition: optimal_planner.h:422
teb_local_planner::TebOptimalPlanner::AddEdgesAcceleration
void AddEdgesAcceleration()
Add all edges (local cost functions) for limiting the translational and angular acceleration.
Definition: optimal_planner.cpp:807
teb_local_planner::TebOptimalPlanner::optimized_
bool optimized_
This variable is true as long as the last optimization has been completed successful.
Definition: optimal_planner.h:727
teb_local_planner::TebOptimalPlanner::cfg_
const TebConfig * cfg_
Config class that stores and manages all related parameters.
Definition: optimal_planner.h:711
teb_local_planner
Definition: distance_calculations.h:46
teb_local_planner::ViaPointContainer
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > ViaPointContainer
Typedef for a container storing via-points.
Definition: optimal_planner.h:118
visualization.h
teb_local_planner::TimedElasticBand::clearTimedElasticBand
void clearTimedElasticBand()
clear all poses and timediffs from the trajectory. The pose and timediff sequences will be empty and ...
Definition: timed_elastic_band.cpp:238
teb_local_planner::TebOptimalPlanner::setVelocityStart
void setVelocityStart(const geometry_msgs::Twist &vel_start)
Set the initial velocity at the trajectory's start pose (e.g. the robot's velocity) [twist overload].
Definition: optimal_planner.cpp:269
teb_local_planner::TebOptimalPlanner::clearPlanner
virtual void clearPlanner()
Reset the planner by clearing the internal graph and trajectory.
Definition: optimal_planner.h:367
teb_local_planner::TebOptimalPlanner::plan
virtual bool plan(const std::vector< geometry_msgs::PoseStamped > &initial_plan, const geometry_msgs::Twist *start_vel=NULL, bool free_goal_vel=false)
Plan a trajectory based on an initial reference plan.
Definition: optimal_planner.cpp:283
teb_local_planner::TebOptimalPlanner::AddEdgesObstacles
void AddEdgesObstacles(double weight_multiplier=1.0)
Add all edges (local cost functions) related to keeping a distance from static obstacles.
Definition: optimal_planner.cpp:480


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sun Jan 7 2024 03:45:15