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 // g2o custom edges and vertices for the TEB planner
72 
73 // messages
74 #include <nav_msgs/Path.h>
75 #include <geometry_msgs/PoseStamped.h>
76 #include <tf/transform_datatypes.h>
77 #include <teb_local_planner/TrajectoryMsg.h>
78 
79 #include <nav_msgs/Odometry.h>
80 #include <limits.h>
81 
82 namespace teb_local_planner
83 {
84 
86 typedef g2o::BlockSolver< g2o::BlockSolverTraits<-1, -1> > TEBBlockSolver;
87 
89 typedef g2o::LinearSolverCSparse<TEBBlockSolver::PoseMatrixType> TEBLinearSolver;
90 //typedef g2o::LinearSolverCholmod<TEBBlockSolver::PoseMatrixType> TEBLinearSolver;
91 
93 typedef std::vector< Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> > ViaPointContainer;
94 
95 
112 {
113 public:
114 
119 
128  TebOptimalPlanner(const TebConfig& cfg, ObstContainer* obstacles = NULL, RobotFootprintModelPtr robot_model = boost::make_shared<PointRobotFootprint>(),
129  TebVisualizationPtr visual = TebVisualizationPtr(), const ViaPointContainer* via_points = NULL);
130 
134  virtual ~TebOptimalPlanner();
135 
144  void initialize(const TebConfig& cfg, ObstContainer* obstacles = NULL, RobotFootprintModelPtr robot_model = boost::make_shared<PointRobotFootprint>(),
145  TebVisualizationPtr visual = TebVisualizationPtr(), const ViaPointContainer* via_points = NULL);
146 
147 
148 
151 
169  virtual bool plan(const std::vector<geometry_msgs::PoseStamped>& initial_plan, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false);
170 
187  virtual bool plan(const tf::Pose& start, const tf::Pose& goal, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false);
188 
205  virtual bool plan(const PoseSE2& start, const PoseSE2& goal, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false);
206 
207 
217  virtual bool getVelocityCommand(double& vx, double& vy, double& omega, int look_ahead_poses) const;
218 
219 
246  bool optimizeTEB(int iterations_innerloop, int iterations_outerloop, bool compute_cost_afterwards = false,
247  double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false);
248 
250 
251 
254 
255 
262  void setVelocityStart(const geometry_msgs::Twist& vel_start);
263 
269  void setVelocityGoal(const geometry_msgs::Twist& vel_goal);
270 
275  void setVelocityGoalFree() {vel_goal_.first = false;}
276 
278 
279 
282 
283 
290 
295  const ObstContainer& getObstVector() const {return *obstacles_;}
296 
298 
301 
302 
308  void setViaPoints(const ViaPointContainer* via_points) {via_points_ = via_points;}
309 
314  const ViaPointContainer& getViaPoints() const {return *via_points_;}
315 
317 
318 
321 
327  void setVisualization(TebVisualizationPtr visualization);
328 
335  virtual void visualize();
336 
338 
339 
342 
346  virtual void clearPlanner()
347  {
348  clearGraph();
350  }
351 
361 
368  static void registerG2OTypes();
369 
375  TimedElasticBand& teb() {return teb_;};
376 
381  const TimedElasticBand& teb() const {return teb_;};
382 
389 
395 
401  bool isOptimized() const {return optimized_;};
402 
424  void computeCurrentCost(double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false);
425 
434  virtual void computeCurrentCost(std::vector<double>& cost, double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false)
435  {
436  computeCurrentCost(obst_cost_scale, viapoint_cost_scale, alternative_time_cost);
437  cost.push_back( getCurrentCost() );
438  }
439 
447  double getCurrentCost() const {return cost_;}
448 
449 
462  inline void extractVelocity(const PoseSE2& pose1, const PoseSE2& pose2, double dt, double& vx, double& vy, double& omega) const;
463 
482  void getVelocityProfile(std::vector<geometry_msgs::Twist>& velocity_profile) const;
483 
495  void getFullTrajectory(std::vector<TrajectoryPointMsg>& trajectory) const;
496 
510  virtual bool isTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector<geometry_msgs::Point>& footprint_spec, double inscribed_radius = 0.0,
511  double circumscribed_radius=0.0, int look_ahead_idx=-1);
512 
514 
515 protected:
516 
519 
532  bool buildGraph(double weight_multiplier=1.0);
533 
546  bool optimizeGraph(int no_iterations, bool clear_after=true);
547 
553  void clearGraph();
554 
567  void AddTEBVertices();
568 
575  void AddEdgesVelocity();
576 
585  void AddEdgesAcceleration();
586 
593  void AddEdgesTimeOptimal();
594 
601  void AddEdgesShortestPath();
602 
611  void AddEdgesObstacles(double weight_multiplier=1.0);
612 
621  void AddEdgesObstaclesLegacy(double weight_multiplier=1.0);
622 
629  void AddEdgesViaPoints();
630 
641  void AddEdgesDynamicObstacles(double weight_multiplier=1.0);
642 
651 
660 
666  void AddEdgesPreferRotDir();
667 
669 
670 
676 
677 
678  // external objects (store weak pointers)
679  const TebConfig* cfg_;
681  const ViaPointContainer* via_points_;
682 
683  double cost_;
685 
686  // internal objects (memory management owned)
691  std::pair<bool, geometry_msgs::Twist> vel_start_;
692  std::pair<bool, geometry_msgs::Twist> vel_goal_;
693 
695  bool optimized_;
696 
697 public:
698  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
699 };
700 
706 typedef std::vector< TebOptimalPlannerPtr > TebOptPlannerContainer;
707 
708 } // namespace teb_local_planner
709 
710 #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.
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.
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).
const ObstContainer & getObstVector() const
Access the internal obstacle container.
const ViaPointContainer & getViaPoints() const
Access the internal via-point container.
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 void setPreferredTurningDir(RotType dir)
Prefer a desired initial turning direction (by penalizing the opposing one)
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). ...
boost::shared_ptr< const g2o::SparseOptimizer > optimizer() const
Access the internal g2o optimizer (read-only).
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.
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 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 getFullTrajectory(std::vector< TrajectoryPointMsg > &trajectory) const
Return the complete trajectory including poses, velocity profiles and temporal information.
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.
void getVelocityProfile(std::vector< geometry_msgs::Twist > &velocity_profile) const
Compute the velocity profile of the trajectory.
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...
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.
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...
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...
const TimedElasticBand & teb() const
Access the internal TimedElasticBand trajectory (read-only).
ViaPointContainer via_points
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.
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 3 2020 04:03:08