39 #ifndef PLANNER_INTERFACE_H_ 40 #define PLANNER_INTERFACE_H_ 43 #include <boost/shared_ptr.hpp> 53 #include <geometry_msgs/PoseArray.h> 54 #include <geometry_msgs/PoseStamped.h> 55 #include <geometry_msgs/TwistStamped.h> 98 virtual bool plan(
const std::vector<geometry_msgs::PoseStamped>& initial_plan,
const geometry_msgs::Twist* start_vel = NULL,
bool free_goal_vel=
false) = 0;
176 double inscribed_radius = 0.0,
double circumscribed_radius=0.0,
int look_ahead_idx=-1) = 0;
198 virtual void computeCurrentCost(std::vector<double>& cost,
double obst_cost_scale=1.0,
bool alternative_time_cost=
false)
boost::shared_ptr< PlannerInterface > PlannerInterfacePtr
Abbrev. for shared instances of PlannerInterface or it's subclasses.
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 samplin...
This abstract class defines an interface for local planners.
virtual ~PlannerInterface()
Virtual destructor.
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) ...
PlannerInterface()
Default constructor.
virtual void visualize()
Visualize planner specific stuff. Overwrite this method to provide an interface to perform all planne...
virtual void setPreferredTurningDir(RotType dir)
Prefer a desired initial turning direction (by penalizing the opposing one)
virtual void computeCurrentCost(std::vector< double > &cost, double obst_cost_scale=1.0, bool alternative_time_cost=false)
RotType
Symbols for left/none/right rotations.
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 class implements a pose in the domain SE2: The pose consist of the position x and y and an orie...
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.
virtual void clearPlanner()=0
Reset the planner.