Go to the documentation of this file.
39 #ifndef OPTIMAL_PLANNER_H_
40 #define OPTIMAL_PLANNER_H_
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>
63 #include <nav_msgs/Path.h>
64 #include <geometry_msgs/PoseStamped.h>
66 #include <teb_local_planner/TrajectoryMsg.h>
68 #include <nav_msgs/Odometry.h>
75 typedef g2o::BlockSolver< g2o::BlockSolverTraits<-1, -1> >
TEBBlockSolver;
78 typedef g2o::LinearSolverCSparse<TEBBlockSolver::PoseMatrixType>
TEBLinearSolver;
82 typedef std::vector< Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> >
ViaPointContainer;
100 class TebOptimalPlanner :
public PlannerInterface
154 virtual bool plan(
const std::vector<geometry_msgs::PoseStamped>& initial_plan,
const geometry_msgs::Twist* start_vel = NULL,
bool free_goal_vel=
false);
202 virtual bool getVelocityCommand(
double& vx,
double& vy,
double& omega,
int look_ahead_poses)
const;
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);
360 TimedElasticBand&
teb() {
return teb_;};
366 const TimedElasticBand&
teb()
const {
return teb_;};
414 void computeCurrentCost(
double obst_cost_scale=1.0,
double viapoint_cost_scale=1.0,
bool alternative_time_cost=
false);
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)
452 inline void extractVelocity(
const PoseSE2& pose1,
const PoseSE2& pose2,
double dt,
double& vx,
double& vy,
double& omega)
const;
501 double circumscribed_radius=0.0,
int look_ahead_idx=-1,
double feasibility_check_lookahead_distance=-1.0);
522 bool buildGraph(
double weight_multiplier=1.0);
536 bool optimizeGraph(
int no_iterations,
bool clear_after=
true);
687 std::pair<bool, geometry_msgs::Twist>
vel_start_;
688 std::pair<bool, geometry_msgs::Twist>
vel_goal_;
694 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
boost::shared_ptr< g2o::SparseOptimizer > optimizer()
Access the internal g2o optimizer.
bool hasDiverged() const override
Returns true if the planner has diverged.
void getVelocityProfile(std::vector< geometry_msgs::Twist > &velocity_profile) const
Compute the velocity profile of the trajectory.
void AddEdgesVelocity()
Add all edges (local cost functions) for limiting the translational and angular velocity.
std::pair< bool, geometry_msgs::Twist > vel_start_
Store the initial velocity at the start pose.
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).
double cost_
Store cost value of the current hyper-graph.
ViaPointContainer via_points
std::pair< bool, geometry_msgs::Twist > vel_goal_
Store the final velocity at the goal pose.
void AddEdgesKinematicsDiffDrive()
Add all edges (local cost functions) for satisfying kinematic constraints of a differential drive rob...
Class that defines a trajectory modeled as an elastic band with augmented tempoarl information.
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).
void setVelocityGoal(const geometry_msgs::Twist &vel_goal)
Set the desired final velocity at the trajectory's goal pose.
boost::shared_ptr< g2o::SparseOptimizer > initOptimizer()
Initialize and configure the g2o sparse optimizer.
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.
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...
void setObstVector(ObstContainer *obst_vector)
Assign a new set of obstacles.
void AddEdgesDynamicObstacles(double weight_multiplier=1.0)
Add all edges (local cost functions) related to keeping a distance from dynamic (moving) obstacles.
RotType
Symbols for left/none/right rotations
boost::shared_ptr< const TebOptimalPlanner > TebOptimalPlannerConstPtr
Abbrev. for shared const TebOptimalPlanner pointers.
void AddEdgesVelocityObstacleRatio()
Add all edges (local cost function) for reducing the velocity of a vertex due to its associated obsta...
void clearGraph()
Clear an existing internal hyper-graph.
boost::shared_ptr< TebOptimalPlanner > TebOptimalPlannerPtr
Abbrev. for shared instances of the TebOptimalPlanner.
double getCurrentCost() const
Access the cost vector.
ObstContainer * obstacles_
Store obstacles that are relevant for planning.
void AddEdgesPreferRotDir()
Add all edges (local cost functions) for prefering a specifiy turning direction (by penalizing the ot...
void setVisualization(TebVisualizationPtr visualization)
Register a TebVisualization class to enable visiualization routines (e.g. publish the local plan and ...
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...
void AddTEBVertices()
Add all relevant vertices to the hyper-graph as optimizable variables.
TebVisualizationPtr visualization_
Instance of the visualization class.
TebVisualizationPtr visual
bool initialized_
Keeps track about the correct initialization of this class.
virtual ~TebOptimalPlanner()
Destruct the optimal planner.
virtual void visualize()
Publish the local plan and pose sequence via ros topics (e.g. subscribe with rviz).
std::vector< ObstaclePtr > ObstContainer
Abbrev. for containers storing multiple obstacles.
std::vector< ObstaclePtr > obst_vector
void setViaPoints(const ViaPointContainer *via_points)
Assign a new set of via-points.
g2o::BlockSolver< g2o::BlockSolverTraits<-1, -1 > > TEBBlockSolver
Typedef for the block solver utilized for optimization.
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...
void AddEdgesViaPoints()
Add all edges (local cost functions) related to minimizing the distance to via-points.
std::vector< ObstContainer > obstacles_per_vertex_
Store the obstacles associated with the n-1 initial vertices.
boost::shared_ptr< TebVisualization > TebVisualizationPtr
Abbrev. for shared instances of the TebVisualization.
bool buildGraph(double weight_multiplier=1.0)
Build the hyper-graph representing the TEB optimization problem.
TimedElasticBand teb_
Actual trajectory object.
void initialize(const TebConfig &cfg, ObstContainer *obstacles=NULL, TebVisualizationPtr visual=TebVisualizationPtr(), const ViaPointContainer *via_points=NULL)
Initializes the optimal planner.
const ViaPointContainer * via_points_
Store via points for planning.
RotType prefer_rotdir_
Store whether to prefer a specific initial rotation in optimization (might be activated in case the r...
virtual void setPreferredTurningDir(RotType dir)
Prefer a desired initial turning direction (by penalizing the opposing one)
static void registerG2OTypes()
Register the vertices and edges defined for the TEB to the g2o::Factory.
Config class for the teb_local_planner and its components.
This class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
const ObstContainer & getObstVector() const
Access the internal obstacle container.
TebOptimalPlanner()
Default constructor.
void setVelocityGoalFree()
Set the desired final velocity at the trajectory's goal pose to be the maximum velocity limit.
void AddEdgesObstaclesLegacy(double weight_multiplier=1.0)
Add all edges (local cost functions) related to keeping a distance from static obstacles (legacy asso...
boost::shared_ptr< g2o::SparseOptimizer > optimizer_
g2o optimizer for trajectory optimization
void AddEdgesKinematicsCarlike()
Add all edges (local cost functions) for satisfying kinematic constraints of a carlike robot.
std::vector< TebOptimalPlannerPtr > TebOptPlannerContainer
Abbrev. for containers storing multiple teb optimal planners.
bool optimizeGraph(int no_iterations, bool clear_after=true)
Optimize the previously constructed hyper-graph to deform / optimize the TEB.
g2o::LinearSolverCSparse< TEBBlockSolver::PoseMatrixType > TEBLinearSolver
Typedef for the linear solver utilized for optimization.
void getFullTrajectory(std::vector< TrajectoryPointMsg > &trajectory) const
Return the complete trajectory including poses, velocity profiles and temporal information.
void AddEdgesShortestPath()
Add all edges (local cost functions) for minimizing the path length.
TimedElasticBand & teb()
Access the internal TimedElasticBand trajectory.
bool isOptimized() const
Check if last optimization was successful.
void AddEdgesAcceleration()
Add all edges (local cost functions) for limiting the translational and angular acceleration.
bool optimized_
This variable is true as long as the last optimization has been completed successful.
const TebConfig * cfg_
Config class that stores and manages all related parameters.
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > ViaPointContainer
Typedef for a container storing via-points.
void clearTimedElasticBand()
clear all poses and timediffs from the trajectory. The pose and timediff sequences will be empty and ...
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].
virtual void clearPlanner()
Reset the planner by clearing the internal graph and trajectory.
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.
void AddEdgesObstacles(double weight_multiplier=1.0)
Add all edges (local cost functions) related to keeping a distance from static obstacles.
teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sun Jan 7 2024 03:45:15