Go to the documentation of this file.
39 #ifndef PLANNER_INTERFACE_H_
40 #define PLANNER_INTERFACE_H_
43 #include <boost/shared_ptr.hpp>
54 #include <geometry_msgs/PoseArray.h>
55 #include <geometry_msgs/PoseStamped.h>
56 #include <geometry_msgs/TwistStamped.h>
67 class PlannerInterface
99 virtual bool plan(
const std::vector<geometry_msgs::PoseStamped>& initial_plan,
const geometry_msgs::Twist* start_vel = NULL,
bool free_goal_vel=
false) = 0;
125 virtual bool plan(
const PoseSE2& start,
const PoseSE2& goal,
const geometry_msgs::Twist* start_vel = NULL,
bool free_goal_vel=
false) = 0;
136 virtual bool getVelocityCommand(
double& vx,
double& vy,
double& omega,
int look_ahead_poses)
const = 0;
182 double inscribed_radius = 0.0,
double circumscribed_radius=0.0,
int look_ahead_idx=-1,
double feasibility_check_lookahead_distance=-1.0) = 0;
191 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, double feasibility_check_lookahead_distance=-1.0)=0
Check whether the planned trajectory is feasible or not.
boost::shared_ptr< BaseRobotFootprintModel > RobotFootprintModelPtr
Abbrev. for shared obstacle pointers.
virtual void clearPlanner()=0
Reset the planner.
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.
RotType
Symbols for left/none/right rotations
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 samplin...
virtual void computeCurrentCost(std::vector< double > &cost, double obst_cost_scale=1.0, bool alternative_time_cost=false)
virtual bool hasDiverged() const =0
Returns true if the planner has diverged.
virtual void visualize()
Visualize planner specific stuff. Overwrite this method to provide an interface to perform all planne...
virtual ~PlannerInterface()
Virtual destructor.
PlannerInterface()
Default constructor.
virtual void setPreferredTurningDir(RotType dir)
Prefer a desired initial turning direction (by penalizing the opposing one)
boost::shared_ptr< PlannerInterface > PlannerInterfacePtr
Abbrev. for shared instances of PlannerInterface or it's subclasses.
virtual void updateRobotModel(RobotFootprintModelPtr robot_model)
teb_local_planner
Author(s): Christoph Rösmann
autogenerated on Sun Jan 7 2024 03:45:15