This class optimizes an internal Timed Elastic Band trajectory using the g2o-framework. More...
#include <optimal_planner.h>
Public Member Functions | |
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. | |
TebOptimalPlanner () | |
Default constructor. | |
TebOptimalPlanner (const TebConfig &cfg, ObstContainer *obstacles=NULL, RobotFootprintModelPtr robot_model=boost::make_shared< PointRobotFootprint >(), TebVisualizationPtr visual=TebVisualizationPtr(), const ViaPointContainer *via_points=NULL) | |
Construct and initialize the TEB optimal planner. | |
virtual | ~TebOptimalPlanner () |
Destruct the optimal planner. | |
Plan a 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. | |
virtual bool | plan (const tf::Pose &start, const tf::Pose &goal, const geometry_msgs::Twist *start_vel=NULL, bool free_goal_vel=false) |
Plan a trajectory between a given start and goal pose (tf::Pose version) | |
virtual bool | plan (const PoseSE2 &start, const PoseSE2 &goal, const Eigen::Vector2d &start_vel, bool free_goal_vel=false) |
Plan a trajectory between a given start and goal pose. | |
virtual bool | getVelocityCommand (double &v, double &omega) const |
Get the velocity command from a previously optimized plan to control the robot at the current sampling interval. | |
bool | optimizeTEB (unsigned int iterations_innerloop, unsigned 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). | |
Desired initial and final velocity | |
void | setVelocityStart (const Eigen::Ref< const Eigen::Vector2d > &vel_start) |
Set the initial velocity at the trajectory's start pose (e.g. the robot's velocity). | |
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]. | |
void | setVelocityGoal (const Eigen::Ref< const Eigen::Vector2d > &vel_goal) |
Set the desired final velocity at the trajectory's goal pose. | |
void | setVelocityGoalFree () |
Set the desired final velocity at the trajectory's goal pose to be the maximum velocity limit. | |
Take obstacles into account | |
void | setObstVector (ObstContainer *obst_vector) |
Assign a new set of obstacles. | |
const ObstContainer & | getObstVector () const |
Access the internal obstacle container. | |
Take via-points into account | |
void | setViaPoints (const ViaPointContainer *via_points) |
Assign a new set of via-points. | |
const ViaPointContainer & | getViaPoints () const |
Access the internal via-point container. | |
Visualization | |
void | setVisualization (TebVisualizationPtr visualization) |
Register a TebVisualization class to enable visiualization routines (e.g. publish the local plan and pose sequence) | |
virtual void | visualize () |
Publish the local plan and pose sequence via ros topics (e.g. subscribe with rviz). | |
Protected Member Functions | |
boost::shared_ptr < g2o::SparseOptimizer > | initOptimizer () |
Initialize and configure the g2o sparse optimizer. | |
Hyper-Graph creation and optimization | |
bool | buildGraph () |
Build the hyper-graph representing the TEB optimization problem. | |
bool | optimizeGraph (int no_iterations, bool clear_after=true) |
Optimize the previously constructed hyper-graph to deform / optimize the TEB. | |
void | clearGraph () |
Clear an existing internal hyper-graph. | |
void | AddTEBVertices () |
Add all relevant vertices to the hyper-graph as optimizable variables. | |
void | AddEdgesVelocity () |
Add all edges (local cost functions) for limiting the translational and angular velocity. | |
void | AddEdgesAcceleration () |
Add all edges (local cost functions) for limiting the translational and angular acceleration. | |
void | AddEdgesTimeOptimal () |
Add all edges (local cost functions) for minimizing the transition time (resp. minimize time differences) | |
void | AddEdgesObstacles () |
Add all edges (local cost functions) related to keeping a distance from static obstacles. | |
void | AddEdgesInflatedObstacles () |
Add all edges (local cost functions) related to keeping a distance from static obstacles. | |
void | AddEdgesViaPoints () |
Add all edges (local cost functions) related to minimizing the distance to via-points. | |
void | AddEdgesDynamicObstacles () |
Add all edges (local cost functions) related to keeping a distance from dynamic (moving) obstacles. | |
void | AddEdgesKinematicsDiffDrive () |
Add all edges (local cost functions) for satisfying kinematic constraints of a differential drive robot. | |
void | AddEdgesKinematicsCarlike () |
Add all edges (local cost functions) for satisfying kinematic constraints of a carlike robot. | |
Protected Attributes | |
const TebConfig * | cfg_ |
Config class that stores and manages all related parameters. | |
double | cost_ |
Store cost value of the current hyper-graph. | |
bool | initialized_ |
Keeps track about the correct initialization of this class. | |
ObstContainer * | obstacles_ |
Store obstacles that are relevant for planning. | |
bool | optimized_ |
This variable is true as long as the last optimization has been completed successful. | |
boost::shared_ptr < g2o::SparseOptimizer > | optimizer_ |
g2o optimizer for trajectory optimization | |
RobotFootprintModelPtr | robot_model_ |
Robot model. | |
TimedElasticBand | teb_ |
Actual trajectory object. | |
std::pair< bool, Eigen::Vector2d > | vel_goal_ |
Store the final velocity at the goal pose. | |
std::pair< bool, Eigen::Vector2d > | vel_start_ |
Store the initial velocity at the start pose. | |
const ViaPointContainer * | via_points_ |
Store via points for planning. | |
TebVisualizationPtr | visualization_ |
Instance of the visualization class. | |
Utility methods and more | |
virtual void | clearPlanner () |
Reset the planner by clearing the internal graph and trajectory. | |
TimedElasticBand & | teb () |
Access the internal TimedElasticBand trajectory. | |
const TimedElasticBand & | teb () const |
Access the internal TimedElasticBand trajectory (read-only). | |
boost::shared_ptr < g2o::SparseOptimizer > | optimizer () |
Access the internal g2o optimizer. | |
boost::shared_ptr< const g2o::SparseOptimizer > | optimizer () const |
Access the internal g2o optimizer (read-only). | |
bool | isOptimized () const |
Check if last optimization was successful. | |
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). | |
virtual void | computeCurrentCost (std::vector< double > &cost, double obst_cost_scale=1.0, double viapoint_cost_scale=1.0, bool alternative_time_cost=false) |
double | getCurrentCost () const |
Access the cost vector. | |
void | extractVelocity (const PoseSE2 &pose1, const PoseSE2 &pose2, double dt, double &v, double &omega) const |
Extract the velocity from consecutive poses and a time difference. | |
void | getVelocityProfile (std::vector< geometry_msgs::Twist > &velocity_profile) const |
Compute the velocity profile of the trajectory. | |
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. | |
virtual bool | isHorizonReductionAppropriate (const std::vector< geometry_msgs::PoseStamped > &initial_plan) const |
Check if the planner suggests a shorter horizon (e.g. to resolve problems) | |
static void | registerG2OTypes () |
Register the vertices and edges defined for the TEB to the g2o::Factory. |
This class optimizes an internal Timed Elastic Band trajectory using the g2o-framework.
For an introduction and further details about the TEB optimization problem refer to:
Definition at line 105 of file optimal_planner.h.
Default constructor.
Definition at line 47 of file optimal_planner.cpp.
teb_local_planner::TebOptimalPlanner::TebOptimalPlanner | ( | const TebConfig & | cfg, |
ObstContainer * | obstacles = NULL , |
||
RobotFootprintModelPtr | robot_model = boost::make_shared<PointRobotFootprint>() , |
||
TebVisualizationPtr | visual = TebVisualizationPtr() , |
||
const ViaPointContainer * | via_points = NULL |
||
) |
Construct and initialize the TEB optimal planner.
cfg | Const reference to the TebConfig class for internal parameters |
obstacles | Container storing all relevant obstacles (see Obstacle) |
robot_model | Shared pointer to the robot shape model used for optimization (optional) |
visual | Shared pointer to the TebVisualization class (optional) |
via_points | Container storing via-points (optional) |
Definition at line 51 of file optimal_planner.cpp.
teb_local_planner::TebOptimalPlanner::~TebOptimalPlanner | ( | ) | [virtual] |
Destruct the optimal planner.
Definition at line 56 of file optimal_planner.cpp.
void teb_local_planner::TebOptimalPlanner::AddEdgesAcceleration | ( | ) | [protected] |
Add all edges (local cost functions) for limiting the translational and angular acceleration.
Definition at line 574 of file optimal_planner.cpp.
void teb_local_planner::TebOptimalPlanner::AddEdgesDynamicObstacles | ( | ) | [protected] |
Add all edges (local cost functions) related to keeping a distance from dynamic (moving) obstacles.
Definition at line 488 of file optimal_planner.cpp.
void teb_local_planner::TebOptimalPlanner::AddEdgesInflatedObstacles | ( | ) | [protected] |
Add all edges (local cost functions) related to keeping a distance from static obstacles.
Definition at line 431 of file optimal_planner.cpp.
void teb_local_planner::TebOptimalPlanner::AddEdgesKinematicsCarlike | ( | ) | [protected] |
Add all edges (local cost functions) for satisfying kinematic constraints of a carlike robot.
Definition at line 670 of file optimal_planner.cpp.
void teb_local_planner::TebOptimalPlanner::AddEdgesKinematicsDiffDrive | ( | ) | [protected] |
Add all edges (local cost functions) for satisfying kinematic constraints of a differential drive robot.
Definition at line 648 of file optimal_planner.cpp.
void teb_local_planner::TebOptimalPlanner::AddEdgesObstacles | ( | ) | [protected] |
Add all edges (local cost functions) related to keeping a distance from static obstacles.
Definition at line 377 of file optimal_planner.cpp.
void teb_local_planner::TebOptimalPlanner::AddEdgesTimeOptimal | ( | ) | [protected] |
Add all edges (local cost functions) for minimizing the transition time (resp. minimize time differences)
Definition at line 628 of file optimal_planner.cpp.
void teb_local_planner::TebOptimalPlanner::AddEdgesVelocity | ( | ) | [protected] |
Add all edges (local cost functions) for limiting the translational and angular velocity.
Definition at line 551 of file optimal_planner.cpp.
void teb_local_planner::TebOptimalPlanner::AddEdgesViaPoints | ( | ) | [protected] |
Add all edges (local cost functions) related to minimizing the distance to via-points.
Definition at line 515 of file optimal_planner.cpp.
void teb_local_planner::TebOptimalPlanner::AddTEBVertices | ( | ) | [protected] |
Add all relevant vertices to the hyper-graph as optimizable variables.
Vertices (if unfixed) represent the variables that will be optimized.
In case of the Timed-Elastic-Band poses and time differences form the vertices of the hyper-graph.
The order of insertion of vertices (to the graph) is important for efficiency, since it affect the sparsity pattern of the underlying hessian computed for optimization.
Definition at line 358 of file optimal_planner.cpp.
bool teb_local_planner::TebOptimalPlanner::buildGraph | ( | ) | [protected] |
Build the hyper-graph representing the TEB optimization problem.
This method creates the optimization problem according to the hyper-graph formulation.
For more details refer to the literature cited in the TebOptimalPlanner class description.
true
, if the graph was created successfully, false
otherwise. Definition at line 281 of file optimal_planner.cpp.
void teb_local_planner::TebOptimalPlanner::clearGraph | ( | ) | [protected] |
Clear an existing internal hyper-graph.
Definition at line 348 of file optimal_planner.cpp.
virtual void teb_local_planner::TebOptimalPlanner::clearPlanner | ( | ) | [inline, virtual] |
Reset the planner by clearing the internal graph and trajectory.
Implements teb_local_planner::PlannerInterface.
Definition at line 343 of file optimal_planner.h.
void teb_local_planner::TebOptimalPlanner::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).
Use this method to obtain information about the current edge errors / costs (local cost functions).
The vector of cost values is composed according to the different edge types (time_optimal, obstacles, ...).
Refer to the method declaration for the detailed composition.
The cost for the edges that minimize time differences (EdgeTimeOptimal) corresponds to the sum of all single squared time differneces: . Sometimes, the user may want to get a value that is proportional or identical to the actual trajectory transition time .
Set alternative_time_cost
to true in order to get the cost calculated using the latter equation, but check the implemented definition, if the value is scaled to match the magnitude of other cost values.
Remove the scaling term for the alternative time cost.
Can we use the last error (chi2) calculated from g2o instead of calculating it by ourself?
obst_cost_scale | Specify extra scaling for obstacle costs. |
viapoint_cost_scale | Specify extra scaling for via points. |
alternative_time_cost | Replace the cost for the time optimal objective by the actual (weighted) transition time. |
Definition at line 693 of file optimal_planner.cpp.
virtual void teb_local_planner::TebOptimalPlanner::computeCurrentCost | ( | std::vector< double > & | cost, |
double | obst_cost_scale = 1.0 , |
||
double | viapoint_cost_scale = 1.0 , |
||
bool | alternative_time_cost = false |
||
) | [inline, virtual] |
Compute and return the cost of the current optimization graph (supports multiple trajectories)
[out] | cost | current cost value for each trajectory [for a planner with just a single trajectory: size=1, vector will not be cleared] |
obst_cost_scale | Specify extra scaling for obstacle costs | |
viapoint_cost_scale | Specify extra scaling for via points. | |
alternative_time_cost | Replace the cost for the time optimal objective by the actual (weighted) transition time |
Definition at line 421 of file optimal_planner.h.
void teb_local_planner::TebOptimalPlanner::extractVelocity | ( | const PoseSE2 & | pose1, |
const PoseSE2 & | pose2, | ||
double | dt, | ||
double & | v, | ||
double & | omega | ||
) | const [inline] |
Extract the velocity from consecutive poses and a time difference.
The velocity is extracted using finite differences. The direction of the translational velocity is also determined.
pose1 | pose at time k | |
pose2 | consecutive pose at time k+1 | |
dt | actual time difference between k and k+1 (must be >0 !!!) | |
[out] | v | translational velocity |
[out] | omega | rotational velocity |
Definition at line 795 of file optimal_planner.cpp.
double teb_local_planner::TebOptimalPlanner::getCurrentCost | ( | ) | const [inline] |
Access the cost vector.
The accumulated cost value previously calculated using computeCurrentCost or by calling optimizeTEB with enabled cost flag.
Definition at line 434 of file optimal_planner.h.
void teb_local_planner::TebOptimalPlanner::getFullTrajectory | ( | std::vector< TrajectoryPointMsg > & | trajectory | ) | const |
Return the complete trajectory including poses, velocity profiles and temporal information.
It is useful for evaluation and debugging purposes or for open-loop control. Since the velocity obtained using difference quotients is the mean velocity between consecutive poses, the velocity at each pose at time stamp k is obtained by taking the average between both velocities. The velocity of the first pose is v_start (provided initial value) and the last one is v_goal (usually zero, if free_goal_vel is off). See getVelocityProfile() for the list of velocities between consecutive points.
[out] | trajectory | the resulting trajectory |
Definition at line 857 of file optimal_planner.cpp.
const ObstContainer& teb_local_planner::TebOptimalPlanner::getObstVector | ( | ) | const [inline] |
Access the internal obstacle container.
Definition at line 292 of file optimal_planner.h.
bool teb_local_planner::TebOptimalPlanner::getVelocityCommand | ( | double & | v, |
double & | omega | ||
) | const [virtual] |
Get the velocity command from a previously optimized plan to control the robot at the current sampling interval.
[out] | v | translational velocity [m/s] |
[out] | omega | rotational velocity [rad/s] |
true
if command is valid, false
otherwise Implements teb_local_planner::PlannerInterface.
Definition at line 808 of file optimal_planner.cpp.
void teb_local_planner::TebOptimalPlanner::getVelocityProfile | ( | std::vector< geometry_msgs::Twist > & | velocity_profile | ) | const |
Compute the velocity profile of the trajectory.
This method computes the translational and rotational velocity for the complete planned trajectory. The first velocity is the one that is provided as initial velocity (fixed). Velocities at index k=2...end-1 are related to the transition from pose_{k-1} to pose_k. The last velocity is the final velocity (fixed). The number of Twist objects is therefore sizePoses()+1; In summary: v[0] = v_start, v[1,...end-1] = +-(pose_{k+1}-pose{k})/dt, v(end) = v_goal It can be used for evaluation and debugging purposes or for open-loop control. For computing the velocity required for controlling the robot to the next step refer to getVelocityCommand().
[out] | velocity_profile | velocity profile will be written to this vector (after clearing any existing content) with the size=no_poses+1 |
Definition at line 832 of file optimal_planner.cpp.
const ViaPointContainer& teb_local_planner::TebOptimalPlanner::getViaPoints | ( | ) | const [inline] |
Access the internal via-point container.
Definition at line 311 of file optimal_planner.h.
void teb_local_planner::TebOptimalPlanner::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.
cfg | Const reference to the TebConfig class for internal parameters |
obstacles | Container storing all relevant obstacles (see Obstacle) |
robot_model | Shared pointer to the robot shape model used for optimization (optional) |
visual | Shared pointer to the TebVisualization class (optional) |
via_points | Container storing via-points (optional) |
Definition at line 66 of file optimal_planner.cpp.
boost::shared_ptr< g2o::SparseOptimizer > teb_local_planner::TebOptimalPlanner::initOptimizer | ( | ) | [protected] |
Initialize and configure the g2o sparse optimizer.
Definition at line 135 of file optimal_planner.cpp.
bool teb_local_planner::TebOptimalPlanner::isHorizonReductionAppropriate | ( | const std::vector< geometry_msgs::PoseStamped > & | initial_plan | ) | const [virtual] |
Check if the planner suggests a shorter horizon (e.g. to resolve problems)
This method is intendend to be called after determining that a trajectory provided by the planner is infeasible. In some cases a reduction of the horizon length might resolve problems. E.g. if a planned trajectory cut corners. Implemented cases for returning true
(remaining length must be larger than 2m to trigger any case):
initial_plan | The intial and transformed plan (part of the local map and pruned up to the robot position) |
true
, if the planner suggests a shorter horizon, false
otherwise. Reimplemented from teb_local_planner::PlannerInterface.
Definition at line 936 of file optimal_planner.cpp.
bool teb_local_planner::TebOptimalPlanner::isOptimized | ( | ) | const [inline] |
Check if last optimization was successful.
true
if the last optimization returned without errors, otherwise false
(also if no optimization has been called before). Definition at line 388 of file optimal_planner.h.
bool teb_local_planner::TebOptimalPlanner::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 |
||
) | [virtual] |
Check whether the planned trajectory is feasible or not.
This method currently checks only that the trajectory, or a part of the trajectory is collision free. Obstacles are here represented as costmap instead of the internal ObstacleContainer.
costmap_model | Pointer to the costmap model |
footprint_spec | The specification of the footprint of the robot in world coordinates |
inscribed_radius | The radius of the inscribed circle of the robot |
circumscribed_radius | The radius of the circumscribed circle of the robot |
look_ahead_idx | Number of poses along the trajectory that should be verified, if -1, the complete trajectory will be checked. |
true
, if the robot footprint along the first part of the trajectory intersects with any obstacle in the costmap, false
otherwise. Implements teb_local_planner::PlannerInterface.
Definition at line 907 of file optimal_planner.cpp.
bool teb_local_planner::TebOptimalPlanner::optimizeGraph | ( | int | no_iterations, |
bool | clear_after = true |
||
) | [protected] |
Optimize the previously constructed hyper-graph to deform / optimize the TEB.
This method invokes the g2o framework to solve the optimization problem considering dedicated sparsity patterns.
The current implementation calls a non-constrained sparse Levenberg-Marquardt algorithm. Constraints are considered by utilizing penalty approximations. Refer to the literature cited in the TebOptimalPlanner class description.
no_iterations | Number of solver iterations |
clear_after | Clear the graph after optimization. |
true
, if optimization terminates successfully, false
otherwise. Definition at line 316 of file optimal_planner.cpp.
boost::shared_ptr<g2o::SparseOptimizer> teb_local_planner::TebOptimalPlanner::optimizer | ( | ) | [inline] |
Access the internal g2o optimizer.
Definition at line 375 of file optimal_planner.h.
boost::shared_ptr<const g2o::SparseOptimizer> teb_local_planner::TebOptimalPlanner::optimizer | ( | ) | const [inline] |
Access the internal g2o optimizer (read-only).
Definition at line 381 of file optimal_planner.h.
bool teb_local_planner::TebOptimalPlanner::optimizeTEB | ( | unsigned int | iterations_innerloop, |
unsigned 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).
optimizeTEB implements the main optimization loop.
It consist of two nested loops:
iterations_innerloop
).The outer loop is repeated iterations_outerloop
times.
The ratio of inner and outer loop iterations significantly defines the contraction behavior and convergence rate of the trajectory optimization. Based on our experiences, 2-6 innerloop iterations are sufficient.
The number of outer loop iterations should be determined by considering the maximum CPU time required to match the control rate.
Optionally, the cost vector can be calculated by specifying compute_cost_afterwards
, see computeCurrentCost().
iterations_innerloop | Number of iterations for the actual solver loop |
iterations_outerloop | Specifies how often the trajectory should be resized followed by the inner solver loop. |
compute_cost_afterwards | if true Calculate the cost vector according to computeCurrentCost(), the vector can be accessed afterwards using getCurrentCost(). |
obst_cost_scale | Specify extra scaling for obstacle costs (only used if compute_cost_afterwards is true) |
viapoint_cost_scale | Specify extra scaling for via-point costs (only used if compute_cost_afterwards is true) |
alternative_time_cost | Replace the cost for the time optimal objective by the actual (weighted) transition time (only used if compute_cost_afterwards is true). |
true
if the optimization terminates successfully, false
otherwise Definition at line 156 of file optimal_planner.cpp.
bool teb_local_planner::TebOptimalPlanner::plan | ( | const std::vector< geometry_msgs::PoseStamped > & | initial_plan, |
const geometry_msgs::Twist * | start_vel = NULL , |
||
bool | free_goal_vel = false |
||
) | [virtual] |
Plan a trajectory based on an initial reference plan.
Call this method to create and optimize a trajectory that is initialized according to an initial reference plan (given as a container of poses).
The method supports hot-starting from previous solutions, if avaiable:
initial_plan | vector of geometry_msgs::PoseStamped |
start_vel | Current start velocity (e.g. the velocity of the robot, only linear.x and angular.z are used) |
free_goal_vel | if true , a nonzero final velocity at the goal pose is allowed, otherwise the final velocity will be zero (default: false) |
true
if planning was successful, false
otherwise Implements teb_local_planner::PlannerInterface.
Definition at line 210 of file optimal_planner.cpp.
bool teb_local_planner::TebOptimalPlanner::plan | ( | const tf::Pose & | start, |
const tf::Pose & | goal, | ||
const geometry_msgs::Twist * | start_vel = NULL , |
||
bool | free_goal_vel = false |
||
) | [virtual] |
Plan a trajectory between a given start and goal pose (tf::Pose version)
Call this method to create and optimize a trajectory that is initialized between a given start and goal pose.
The method supports hot-starting from previous solutions, if avaiable:
start | tf::Pose containing the start pose of the trajectory |
goal | tf::Pose containing the goal pose of the trajectory |
start_vel | Current start velocity (e.g. the velocity of the robot, only linear.x and angular.z are used) |
free_goal_vel | if true , a nonzero final velocity at the goal pose is allowed, otherwise the final velocity will be zero (default: false) |
true
if planning was successful, false
otherwise Implements teb_local_planner::PlannerInterface.
Definition at line 243 of file optimal_planner.cpp.
bool teb_local_planner::TebOptimalPlanner::plan | ( | const PoseSE2 & | start, |
const PoseSE2 & | goal, | ||
const Eigen::Vector2d & | start_vel, | ||
bool | free_goal_vel = false |
||
) | [virtual] |
Plan a trajectory between a given start and goal pose.
Call this method to create and optimize a trajectory that is initialized between a given start and goal pose.
The method supports hot-starting from previous solutions, if avaiable:
start | PoseSE2 containing the start pose of the trajectory |
goal | PoseSE2 containing the goal pose of the trajectory |
start_vel | Initial velocity at the start pose (2D vector containing the translational and angular velocity). |
free_goal_vel | if true , a nonzero final velocity at the goal pose is allowed, otherwise the final velocity will be zero (default: false) |
true
if planning was successful, false
otherwise Implements teb_local_planner::PlannerInterface.
Definition at line 251 of file optimal_planner.cpp.
void teb_local_planner::TebOptimalPlanner::registerG2OTypes | ( | ) | [static] |
Register the vertices and edges defined for the TEB to the g2o::Factory.
This allows the user to export the internal graph to a text file for instance. Access the optimizer() for more details.
Definition at line 111 of file optimal_planner.cpp.
void teb_local_planner::TebOptimalPlanner::setObstVector | ( | ObstContainer * | obst_vector | ) | [inline] |
Assign a new set of obstacles.
obst_vector | pointer to an obstacle container (can also be a nullptr) |
Definition at line 286 of file optimal_planner.h.
void teb_local_planner::TebOptimalPlanner::setVelocityGoal | ( | const Eigen::Ref< const Eigen::Vector2d > & | vel_goal | ) |
Set the desired final velocity at the trajectory's goal pose.
free_goal_vel
is set to false
in plan() vel_goal | 2D vector containing the translational and angular final velocity |
Definition at line 204 of file optimal_planner.cpp.
void teb_local_planner::TebOptimalPlanner::setVelocityGoalFree | ( | ) | [inline] |
Set the desired final velocity at the trajectory's goal pose to be the maximum velocity limit.
free_goal_vel
is set to false
in plan() Definition at line 272 of file optimal_planner.h.
void teb_local_planner::TebOptimalPlanner::setVelocityStart | ( | const Eigen::Ref< const Eigen::Vector2d > & | vel_start | ) |
Set the initial velocity at the trajectory's start pose (e.g. the robot's velocity).
vel_start | 2D vector containing the translational and angular velocity |
Definition at line 191 of file optimal_planner.cpp.
void teb_local_planner::TebOptimalPlanner::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].
vel_start | Current start velocity (e.g. the velocity of the robot, only linear.x and angular.z are used) |
Definition at line 197 of file optimal_planner.cpp.
void teb_local_planner::TebOptimalPlanner::setViaPoints | ( | const ViaPointContainer * | via_points | ) | [inline] |
Assign a new set of via-points.
via_points | pointer to a via_point container (can also be a nullptr) |
Any previously set container will be overwritten.
Definition at line 305 of file optimal_planner.h.
void teb_local_planner::TebOptimalPlanner::setVisualization | ( | TebVisualizationPtr | visualization | ) |
Register a TebVisualization class to enable visiualization routines (e.g. publish the local plan and pose sequence)
visualization | shared pointer to a TebVisualization instance |
Definition at line 87 of file optimal_planner.cpp.
TimedElasticBand& teb_local_planner::TebOptimalPlanner::teb | ( | ) | [inline] |
Access the internal TimedElasticBand trajectory.
Definition at line 362 of file optimal_planner.h.
const TimedElasticBand& teb_local_planner::TebOptimalPlanner::teb | ( | ) | const [inline] |
Access the internal TimedElasticBand trajectory (read-only).
Definition at line 368 of file optimal_planner.h.
void teb_local_planner::TebOptimalPlanner::visualize | ( | ) | [virtual] |
Publish the local plan and pose sequence via ros topics (e.g. subscribe with rviz).
Make sure to register a TebVisualization instance before using setVisualization() or an overlaoded constructor.
Reimplemented from teb_local_planner::PlannerInterface.
Definition at line 92 of file optimal_planner.cpp.
const TebConfig* teb_local_planner::TebOptimalPlanner::cfg_ [protected] |
Config class that stores and manages all related parameters.
Definition at line 659 of file optimal_planner.h.
double teb_local_planner::TebOptimalPlanner::cost_ [protected] |
Store cost value of the current hyper-graph.
Definition at line 663 of file optimal_planner.h.
bool teb_local_planner::TebOptimalPlanner::initialized_ [protected] |
Keeps track about the correct initialization of this class.
Definition at line 673 of file optimal_planner.h.
Store obstacles that are relevant for planning.
Definition at line 660 of file optimal_planner.h.
bool teb_local_planner::TebOptimalPlanner::optimized_ [protected] |
This variable is true
as long as the last optimization has been completed successful.
Definition at line 674 of file optimal_planner.h.
boost::shared_ptr<g2o::SparseOptimizer> teb_local_planner::TebOptimalPlanner::optimizer_ [protected] |
g2o optimizer for trajectory optimization
Definition at line 669 of file optimal_planner.h.
Robot model.
Definition at line 668 of file optimal_planner.h.
Actual trajectory object.
Definition at line 667 of file optimal_planner.h.
std::pair<bool, Eigen::Vector2d> teb_local_planner::TebOptimalPlanner::vel_goal_ [protected] |
Store the final velocity at the goal pose.
Definition at line 671 of file optimal_planner.h.
std::pair<bool, Eigen::Vector2d> teb_local_planner::TebOptimalPlanner::vel_start_ [protected] |
Store the initial velocity at the start pose.
Definition at line 670 of file optimal_planner.h.
const ViaPointContainer* teb_local_planner::TebOptimalPlanner::via_points_ [protected] |
Store via points for planning.
Definition at line 661 of file optimal_planner.h.
Instance of the visualization class.
Definition at line 666 of file optimal_planner.h.