This abstract class defines an interface for local planners. More...
#include <planner_interface.h>
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 | isHorizonReductionAppropriate (const std::vector< geometry_msgs::PoseStamped > &initial_plan) const |
Implement this method to check if the planner suggests a shorter horizon (e.g. to resolve problems) More... | |
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) const =0 |
Get the velocity command from a previously optimized plan to control the robot at the current sampling interval. More... | |
This abstract class defines an interface for local planners.
Definition at line 66 of file planner_interface.h.
|
inline |
Default constructor.
Definition at line 73 of file planner_interface.h.
|
inlinevirtual |
Virtual destructor.
Definition at line 79 of file planner_interface.h.
|
pure virtual |
Reset the planner.
Implemented in teb_local_planner::HomotopyClassPlanner, and teb_local_planner::TebOptimalPlanner.
|
inlinevirtual |
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 | |
alternative_time_cost | Replace the cost for the time optimal objective by the actual (weighted) transition time |
Definition at line 198 of file planner_interface.h.
|
pure virtual |
Get the velocity command from a previously optimized plan to control the robot at the current sampling interval.
[out] | vx | translational velocity [m/s] |
[out] | vy | strafing velocity which can be nonzero for holonomic robots [m/s] |
[out] | omega | rotational velocity [rad/s] |
true
if command is valid, false
otherwise Implemented in teb_local_planner::TebOptimalPlanner, and teb_local_planner::HomotopyClassPlanner.
|
inlinevirtual |
Implement this method to 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. Since the trajectory representation is managed by the planner, it is part of the base planner_interface. The implementation is optional. If not specified, the method returns false
.
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 in teb_local_planner::TebOptimalPlanner, and teb_local_planner::HomotopyClassPlanner.
Definition at line 189 of file planner_interface.h.
|
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.
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. Implemented in teb_local_planner::TebOptimalPlanner, and teb_local_planner::HomotopyClassPlanner.
|
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).
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 Implemented in teb_local_planner::TebOptimalPlanner, and teb_local_planner::HomotopyClassPlanner.
|
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.
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 Implemented in teb_local_planner::TebOptimalPlanner, and teb_local_planner::HomotopyClassPlanner.
|
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.
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 (twist msg 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 Implemented in teb_local_planner::TebOptimalPlanner, and teb_local_planner::HomotopyClassPlanner.
|
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.
dir | This 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 152 of file planner_interface.h.
|
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 158 of file planner_interface.h.