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 
101 {
102 public:
103 
108 
117  TebOptimalPlanner(const TebConfig& cfg, ObstContainer* obstacles = NULL, RobotFootprintModelPtr robot_model = boost::make_shared<PointRobotFootprint>(),
118  TebVisualizationPtr visual = TebVisualizationPtr(), const ViaPointContainer* via_points = NULL);
119 
123  virtual ~TebOptimalPlanner();
124 
133  void initialize(const TebConfig& cfg, ObstContainer* obstacles = NULL, RobotFootprintModelPtr robot_model = boost::make_shared<PointRobotFootprint>(),
134  TebVisualizationPtr visual = TebVisualizationPtr(), const ViaPointContainer* via_points = NULL);
135 
139  void updateRobotModel(RobotFootprintModelPtr robot_model );
140 
143 
161  virtual bool plan(const std::vector<geometry_msgs::PoseStamped>& initial_plan, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false);
162 
179  virtual bool plan(const tf::Pose& start, const tf::Pose& goal, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false);
180 
197  virtual bool plan(const PoseSE2& start, const PoseSE2& goal, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false);
198 
199 
209  virtual bool getVelocityCommand(double& vx, double& vy, double& omega, int look_ahead_poses) const;
210 
211 
238  bool optimizeTEB(int iterations_innerloop, int iterations_outerloop, bool compute_cost_afterwards = false,
239  double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false);
240 
242 
243 
246 
247 
254  void setVelocityStart(const geometry_msgs::Twist& vel_start);
255 
261  void setVelocityGoal(const geometry_msgs::Twist& vel_goal);
262 
267  void setVelocityGoalFree() {vel_goal_.first = false;}
268 
270 
271 
274 
275 
282 
287  const ObstContainer& getObstVector() const {return *obstacles_;}
288 
290 
293 
294 
300  void setViaPoints(const ViaPointContainer* via_points) {via_points_ = via_points;}
301 
306  const ViaPointContainer& getViaPoints() const {return *via_points_;}
307 
309 
310 
313 
319  void setVisualization(TebVisualizationPtr visualization);
320 
327  virtual void visualize();
328 
330 
331 
334 
338  virtual void clearPlanner()
339  {
340  clearGraph();
342  }
343 
353 
360  static void registerG2OTypes();
361 
367  TimedElasticBand& teb() {return teb_;};
368 
373  const TimedElasticBand& teb() const {return teb_;};
374 
381 
387 
393  bool isOptimized() const {return optimized_;};
394 
398  bool hasDiverged() const override;
399 
421  void computeCurrentCost(double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false);
422 
431  virtual void computeCurrentCost(std::vector<double>& cost, double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false)
432  {
433  computeCurrentCost(obst_cost_scale, viapoint_cost_scale, alternative_time_cost);
434  cost.push_back( getCurrentCost() );
435  }
436 
444  double getCurrentCost() const {return cost_;}
445 
446 
459  inline void extractVelocity(const PoseSE2& pose1, const PoseSE2& pose2, double dt, double& vx, double& vy, double& omega) const;
460 
479  void getVelocityProfile(std::vector<geometry_msgs::Twist>& velocity_profile) const;
480 
492  void getFullTrajectory(std::vector<TrajectoryPointMsg>& trajectory) const;
493 
507  virtual bool isTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector<geometry_msgs::Point>& footprint_spec, double inscribed_radius = 0.0,
508  double circumscribed_radius=0.0, int look_ahead_idx=-1);
509 
511 
512 protected:
513 
516 
529  bool buildGraph(double weight_multiplier=1.0);
530 
543  bool optimizeGraph(int no_iterations, bool clear_after=true);
544 
550  void clearGraph();
551 
564  void AddTEBVertices();
565 
572  void AddEdgesVelocity();
573 
582  void AddEdgesAcceleration();
583 
590  void AddEdgesTimeOptimal();
591 
598  void AddEdgesShortestPath();
599 
608  void AddEdgesObstacles(double weight_multiplier=1.0);
609 
617  void AddEdgesObstaclesLegacy(double weight_multiplier=1.0);
618 
625  void AddEdgesViaPoints();
626 
637  void AddEdgesDynamicObstacles(double weight_multiplier=1.0);
638 
647 
656 
662  void AddEdgesPreferRotDir();
663 
670 
672 
673 
679 
680 
681  // external objects (store weak pointers)
682  const TebConfig* cfg_;
684  const ViaPointContainer* via_points_;
685  std::vector<ObstContainer> obstacles_per_vertex_;
686 
687  double cost_;
689 
690  // internal objects (memory management owned)
695  std::pair<bool, geometry_msgs::Twist> vel_start_;
696  std::pair<bool, geometry_msgs::Twist> vel_goal_;
697 
699  bool optimized_;
700 
701 public:
702  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
703 };
704 
710 typedef std::vector< TebOptimalPlannerPtr > TebOptPlannerContainer;
711 
712 } // namespace teb_local_planner
713 
714 #endif /* OPTIMAL_PLANNER_H_ */
static void registerG2OTypes()
Register the vertices and edges defined for the TEB to the g2o::Factory.
void setVelocityStart(const geometry_msgs::Twist &vel_start)
Set the initial velocity at the trajectory&#39;s start pose (e.g. the robot&#39;s velocity) [twist overload]...
bool optimizeGraph(int no_iterations, bool clear_after=true)
Optimize the previously constructed hyper-graph to deform / optimize the TEB.
void setVelocityGoalFree()
Set the desired final velocity at the trajectory&#39;s goal pose to be the maximum velocity limit...
std::pair< bool, geometry_msgs::Twist > vel_start_
Store the initial velocity at the start pose.
TimedElasticBand & teb()
Access the internal TimedElasticBand trajectory.
This abstract class defines an interface for local planners.
void clearGraph()
Clear an existing internal hyper-graph.
void getFullTrajectory(std::vector< TrajectoryPointMsg > &trajectory) const
Return the complete trajectory including poses, velocity profiles and temporal information.
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)
Check whether the planned trajectory is feasible or not.
ROSCPP_DECL void start()
void setVisualization(TebVisualizationPtr visualization)
Register a TebVisualization class to enable visiualization routines (e.g. publish the local plan and ...
std::pair< bool, geometry_msgs::Twist > vel_goal_
Store the final velocity at the goal pose.
void AddEdgesShortestPath()
Add all edges (local cost functions) for minimizing the path length.
virtual void visualize()
Publish the local plan and pose sequence via ros topics (e.g. subscribe with rviz).
void AddEdgesTimeOptimal()
Add all edges (local cost functions) for minimizing the transition time (resp. minimize time differen...
Config class for the teb_local_planner and its components.
Definition: teb_config.h:61
void AddEdgesAcceleration()
Add all edges (local cost functions) for limiting the translational and angular acceleration.
Class that defines a trajectory modeled as an elastic band with augmented tempoarl information...
boost::shared_ptr< g2o::SparseOptimizer > optimizer()
Access the internal g2o optimizer.
void setVelocityGoal(const geometry_msgs::Twist &vel_goal)
Set the desired final velocity at the trajectory&#39;s goal pose.
void setObstVector(ObstContainer *obst_vector)
Assign a new set of obstacles.
double getCurrentCost() const
Access the cost vector.
TebVisualizationPtr visual
void AddEdgesVelocity()
Add all edges (local cost functions) for limiting the translational and angular velocity.
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...
virtual void setPreferredTurningDir(RotType dir)
Prefer a desired initial turning direction (by penalizing the opposing one)
bool hasDiverged() const override
Returns true if the planner has diverged.
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). ...
const ObstContainer & getObstVector() const
Access the internal obstacle container.
void AddEdgesPreferRotDir()
Add all edges (local cost functions) for prefering a specifiy turning direction (by penalizing the ot...
virtual ~TebOptimalPlanner()
Destruct the optimal planner.
boost::shared_ptr< TebOptimalPlanner > TebOptimalPlannerPtr
Abbrev. for shared instances of the TebOptimalPlanner.
void updateRobotModel(RobotFootprintModelPtr robot_model)
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.
bool buildGraph(double weight_multiplier=1.0)
Build the hyper-graph representing the TEB optimization problem.
void AddTEBVertices()
Add all relevant vertices to the hyper-graph as optimizable variables.
boost::shared_ptr< const TebOptimalPlanner > TebOptimalPlannerConstPtr
Abbrev. for shared const TebOptimalPlanner pointers.
ObstContainer * obstacles_
Store obstacles that are relevant for planning.
TebVisualizationPtr visualization_
Instance of the visualization class.
g2o::BlockSolver< g2o::BlockSolverTraits<-1, -1 > > TEBBlockSolver
Typedef for the block solver utilized for optimization.
RotType
Symbols for left/none/right rotations.
Definition: misc.h:53
void AddEdgesVelocityObstacleRatio()
Add all edges (local cost function) for reducing the velocity of a vertex due to its associated obsta...
void AddEdgesViaPoints()
Add all edges (local cost functions) related to minimizing the distance to via-points.
bool initialized_
Keeps track about the correct initialization of this class.
void AddEdgesDynamicObstacles(double weight_multiplier=1.0)
Add all edges (local cost functions) related to keeping a distance from dynamic (moving) obstacles...
boost::shared_ptr< TebVisualization > TebVisualizationPtr
Abbrev. for shared instances of the TebVisualization.
std::vector< ObstaclePtr > ObstContainer
Abbrev. for containers storing multiple obstacles.
Definition: obstacles.h:297
bool optimized_
This variable is true as long as the last optimization has been completed successful.
TebOptimalPlanner()
Default constructor.
void setViaPoints(const ViaPointContainer *via_points)
Assign a new set of via-points.
void clearTimedElasticBand()
clear all poses and timediffs from the trajectory. The pose and timediff sequences will be empty and ...
std::vector< TebOptimalPlannerPtr > TebOptPlannerContainer
Abbrev. for containers storing multiple teb optimal planners.
RobotFootprintModelPtr robot_model_
Robot model.
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:57
void initialize(const TebConfig &cfg, ObstContainer *obstacles=NULL, RobotFootprintModelPtr robot_model=boost::make_shared< PointRobotFootprint >(), TebVisualizationPtr visual=TebVisualizationPtr(), const ViaPointContainer *via_points=NULL)
Initializes the optimal planner.
virtual void clearPlanner()
Reset the planner by clearing the internal graph and trajectory.
const TimedElasticBand & teb() const
Access the internal TimedElasticBand trajectory (read-only).
void getVelocityProfile(std::vector< geometry_msgs::Twist > &velocity_profile) const
Compute the velocity profile of the trajectory.
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...
std::vector< ObstaclePtr > obst_vector
This class optimizes an internal Timed Elastic Band trajectory using the g2o-framework.
bool isOptimized() const
Check if last optimization was successful.
std::vector< ObstContainer > obstacles_per_vertex_
Store the obstacles associated with the n-1 initial vertices.
double cost_
Store cost value of the current hyper-graph.
void AddEdgesKinematicsCarlike()
Add all edges (local cost functions) for satisfying kinematic constraints of a carlike robot...
ViaPointContainer via_points
const ViaPointContainer & getViaPoints() const
Access the internal via-point container.
const ViaPointContainer * via_points_
Store via points for planning.
TimedElasticBand teb_
Actual trajectory object.
boost::shared_ptr< g2o::SparseOptimizer > initOptimizer()
Initialize and configure the g2o sparse optimizer.
g2o::LinearSolverCSparse< TEBBlockSolver::PoseMatrixType > TEBLinearSolver
Typedef for the linear solver utilized for optimization.
boost::shared_ptr< const g2o::SparseOptimizer > optimizer() const
Access the internal g2o optimizer (read-only).
void AddEdgesObstacles(double weight_multiplier=1.0)
Add all edges (local cost functions) related to keeping a distance from static obstacles.
const TebConfig * cfg_
Config class that stores and manages all related parameters.
void AddEdgesKinematicsDiffDrive()
Add all edges (local cost functions) for satisfying kinematic constraints of a differential drive rob...
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > ViaPointContainer
Typedef for a container storing via-points.
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).
boost::shared_ptr< g2o::SparseOptimizer > optimizer_
g2o optimizer for trajectory optimization
void AddEdgesObstaclesLegacy(double weight_multiplier=1.0)
Add all edges (local cost functions) related to keeping a distance from static obstacles (legacy asso...
RotType prefer_rotdir_
Store whether to prefer a specific initial rotation in optimization (might be activated in case the r...
virtual void computeCurrentCost(std::vector< double > &cost, double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false)


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Jun 1 2022 02:26:31