Public Member Functions | List of all members
teb_local_planner::PlannerInterface Class Referenceabstract

This abstract class defines an interface for local planners. More...

#include <planner_interface.h>

Inheritance diagram for teb_local_planner::PlannerInterface:
Inheritance graph
[legend]

Public Member Functions

virtual void clearPlanner ()=0
 Reset the planner. More...
 
virtual void computeCurrentCost (std::vector< double > &cost, double obst_cost_scale=1.0, bool alternative_time_cost=false)
 
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)=0
 Check whether the planned trajectory is feasible or not. More...
 
 PlannerInterface ()
 Default constructor. More...
 
virtual void setPreferredTurningDir (RotType dir)
 Prefer a desired initial turning direction (by penalizing the opposing one) More...
 
virtual void visualize ()
 Visualize planner specific stuff. Overwrite this method to provide an interface to perform all planner related visualizations at once. More...
 
virtual ~PlannerInterface ()
 Virtual destructor. More...
 
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)=0
 Plan a trajectory based on an initial reference plan. More...
 
virtual bool plan (const tf::Pose &start, const tf::Pose &goal, const geometry_msgs::Twist *start_vel=NULL, bool free_goal_vel=false)=0
 Plan a trajectory between a given start and goal pose (tf::Pose version). More...
 
virtual bool plan (const PoseSE2 &start, const PoseSE2 &goal, const geometry_msgs::Twist *start_vel=NULL, bool free_goal_vel=false)=0
 Plan a trajectory between a given start and goal pose. More...
 
virtual bool getVelocityCommand (double &vx, double &vy, double &omega, int look_ahead_poses) const =0
 Get the velocity command from a previously optimized plan to control the robot at the current sampling interval. More...
 

Detailed Description

This abstract class defines an interface for local planners.

Definition at line 66 of file planner_interface.h.

Constructor & Destructor Documentation

teb_local_planner::PlannerInterface::PlannerInterface ( )
inline

Default constructor.

Definition at line 73 of file planner_interface.h.

virtual teb_local_planner::PlannerInterface::~PlannerInterface ( )
inlinevirtual

Virtual destructor.

Definition at line 79 of file planner_interface.h.

Member Function Documentation

virtual void teb_local_planner::PlannerInterface::clearPlanner ( )
pure virtual
virtual void teb_local_planner::PlannerInterface::computeCurrentCost ( std::vector< double > &  cost,
double  obst_cost_scale = 1.0,
bool  alternative_time_cost = false 
)
inlinevirtual

Compute and return the cost of the current optimization graph (supports multiple trajectories)

Parameters
[out]costcurrent cost value for each trajectory [for a planner with just a single trajectory: size=1, vector will not be cleared]
obst_cost_scaleSpecify extra scaling for obstacle costs
alternative_time_costReplace the cost for the time optimal objective by the actual (weighted) transition time

Definition at line 186 of file planner_interface.h.

virtual bool teb_local_planner::PlannerInterface::getVelocityCommand ( double &  vx,
double &  vy,
double &  omega,
int  look_ahead_poses 
) const
pure virtual

Get the velocity command from a previously optimized plan to control the robot at the current sampling interval.

Warning
Call plan() first and check if the generated plan is feasible.
Parameters
[out]vxtranslational velocity [m/s]
[out]vystrafing velocity which can be nonzero for holonomic robots [m/s]
[out]omegarotational velocity [rad/s]
[in]look_ahead_posesindex of the final pose used to compute the velocity command.
Returns
true if command is valid, false otherwise

Implemented in teb_local_planner::TebOptimalPlanner, and teb_local_planner::HomotopyClassPlanner.

virtual bool teb_local_planner::PlannerInterface::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 
)
pure 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.

Parameters
costmap_modelPointer to the costmap model
footprint_specThe specification of the footprint of the robot in world coordinates
inscribed_radiusThe radius of the inscribed circle of the robot
circumscribed_radiusThe radius of the circumscribed circle of the robot
look_ahead_idxNumber of poses along the trajectory that should be verified, if -1, the complete trajectory will be checked.
Returns
true, if the robot footprint along the first part of the trajectory intersects with any obstacle in the costmap, false otherwise.

Implemented in teb_local_planner::TebOptimalPlanner, and teb_local_planner::HomotopyClassPlanner.

virtual bool teb_local_planner::PlannerInterface::plan ( const std::vector< geometry_msgs::PoseStamped > &  initial_plan,
const geometry_msgs::Twist *  start_vel = NULL,
bool  free_goal_vel = false 
)
pure virtual

Plan a trajectory based on an initial reference plan.

Provide this method to create and optimize a trajectory that is initialized according to an initial reference plan (given as a container of poses).

Parameters
initial_planvector of geometry_msgs::PoseStamped
start_velCurrent start velocity (e.g. the velocity of the robot, only linear.x and angular.z are used)
free_goal_velif true, a nonzero final velocity at the goal pose is allowed, otherwise the final velocity will be zero (default: false)
Returns
true if planning was successful, false otherwise

Implemented in teb_local_planner::TebOptimalPlanner, and teb_local_planner::HomotopyClassPlanner.

virtual bool teb_local_planner::PlannerInterface::plan ( const tf::Pose start,
const tf::Pose goal,
const geometry_msgs::Twist *  start_vel = NULL,
bool  free_goal_vel = false 
)
pure virtual

Plan a trajectory between a given start and goal pose (tf::Pose version).

Provide this method to create and optimize a trajectory that is initialized between a given start and goal pose.

Parameters
starttf::Pose containing the start pose of the trajectory
goaltf::Pose containing the goal pose of the trajectory
start_velCurrent start velocity (e.g. the velocity of the robot, only linear.x and angular.z are used)
free_goal_velif true, a nonzero final velocity at the goal pose is allowed, otherwise the final velocity will be zero (default: false)
Returns
true if planning was successful, false otherwise

Implemented in teb_local_planner::TebOptimalPlanner, and teb_local_planner::HomotopyClassPlanner.

virtual bool teb_local_planner::PlannerInterface::plan ( const PoseSE2 start,
const PoseSE2 goal,
const geometry_msgs::Twist *  start_vel = NULL,
bool  free_goal_vel = false 
)
pure virtual

Plan a trajectory between a given start and goal pose.

Provide this method to create and optimize a trajectory that is initialized between a given start and goal pose.

Parameters
startPoseSE2 containing the start pose of the trajectory
goalPoseSE2 containing the goal pose of the trajectory
start_velInitial velocity at the start pose (twist msg containing the translational and angular velocity).
free_goal_velif true, a nonzero final velocity at the goal pose is allowed, otherwise the final velocity will be zero (default: false)
Returns
true if planning was successful, false otherwise

Implemented in teb_local_planner::TebOptimalPlanner, and teb_local_planner::HomotopyClassPlanner.

virtual void teb_local_planner::PlannerInterface::setPreferredTurningDir ( RotType  dir)
inlinevirtual

Prefer a desired initial turning direction (by penalizing the opposing one)

A desired (initial) turning direction might be specified in case the planned trajectory oscillates between two solutions (in the same equivalence class!) with similar cost. Check the parameters in order to adjust the weight of the penalty. Initial means that the penalty is applied only to the first few poses of the trajectory.

Parameters
dirThis parameter might be RotType::left (prefer left), RotType::right (prefer right) or RotType::none (prefer none)

Reimplemented in teb_local_planner::HomotopyClassPlanner, and teb_local_planner::TebOptimalPlanner.

Definition at line 153 of file planner_interface.h.

virtual void teb_local_planner::PlannerInterface::visualize ( )
inlinevirtual

Visualize planner specific stuff. Overwrite this method to provide an interface to perform all planner related visualizations at once.

Reimplemented in teb_local_planner::TebOptimalPlanner, and teb_local_planner::HomotopyClassPlanner.

Definition at line 159 of file planner_interface.h.


The documentation for this class was generated from the following file:


teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Wed Jun 3 2020 04:03:08