Class PlannerInterface
Defined in File planner_interface.h
Inheritance Relationships
Derived Type
public hateb_local_planner::TebOptimalPlanner(Class TebOptimalPlanner)
Class Documentation
-
class PlannerInterface
This abstract class defines an interface for local planners.
Subclassed by hateb_local_planner::TebOptimalPlanner
Plan a trajectory
-
double local_weight_optimaltime_
-
virtual bool plan(const std::vector<geometry_msgs::PoseStamped> &initial_plan, const geometry_msgs::Twist *start_vel = nullptr, bool free_goal_vel = false, const AgentPlanVelMap *initial_agent_plan_vels = nullptr, hateb_local_planner::OptimizationCostArray *op_costs = nullptr, double dt_ref = 0.4, double dt_hyst = 0.1, int Mode = 0) = 0
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_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)
- Returns:
trueif planning was successful,falseotherwise
-
virtual bool plan(const tf::Pose &start, const tf::Pose &goal, const geometry_msgs::Twist *start_vel = nullptr, bool free_goal_vel = false, hateb_local_planner::OptimizationCostArray *op_costs = nullptr, double dt_ref = 0.4, double dt_hyst = 0.1, int Mode = 0) = 0
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:
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)
- Returns:
trueif planning was successful,falseotherwise
-
virtual bool plan(const PoseSE2 &start, const PoseSE2 &goal, const geometry_msgs::Twist *start_vel = nullptr, bool free_goal_vel = false, double pre_plan_time = 0.0, hateb_local_planner::OptimizationCostArray *op_costs = nullptr, double dt_ref = 0.4, double dt_hyst = 0.1, int Mode = 0) = 0
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:
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)
- Returns:
trueif planning was successful,falseotherwise
-
virtual bool getVelocityCommand(double &vx, double &vy, double &omega, int look_ahead_poses, double dt_ref) const = 0
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:
vx – [out] translational velocity [m/s]
vy – [out] strafing velocity which can be nonzero for holonomic robots [m/s]
omega – [out] rotational velocity [rad/s]
look_ahead_poses – [in] index of the final pose used to compute the velocity command.
- Returns:
trueif command is valid,falseotherwise
-
virtual void clearPlanner() = 0
Reset the planner.
-
inline virtual void setPreferredTurningDir(RotType dir)
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:
dir – This parameter might be RotType::left (prefer left), RotType::right (prefer right) or RotType::none (prefer none)
-
inline virtual void visualize()
Visualize planner specific stuff. Overwrite this method to provide an interface to perform all planner related visualizations at once.
-
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.
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_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.
- Returns:
true, if the robot footprint along the first part of the trajectory intersects with any obstacle in the costmap,falseotherwise.
-
inline virtual void computeCurrentCost(std::vector<double> &cost, double obst_cost_scale = 1.0, bool alternative_time_cost = false)
Compute and return the cost of the current optimization graph (supports multiple trajectories)
- Parameters:
cost – [out] 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
-
virtual cohan_msgs::Trajectory getFullTrajectory() const = 0
-
virtual cohan_msgs::Trajectory getFullAgentTrajectory(uint64_t agent_id) = 0
-
double local_weight_optimaltime_