Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #ifndef PLANNER_INTERFACE_H_
00040 #define PLANNER_INTERFACE_H_
00041
00042
00043 #include <boost/shared_ptr.hpp>
00044
00045
00046 #include <tf/transform_datatypes.h>
00047 #include <base_local_planner/costmap_model.h>
00048
00049
00050 #include <teb_local_planner/pose_se2.h>
00051
00052
00053 #include <geometry_msgs/PoseArray.h>
00054 #include <geometry_msgs/PoseStamped.h>
00055 #include <geometry_msgs/TwistStamped.h>
00056
00057
00058 namespace teb_local_planner
00059 {
00060
00061
00066 class PlannerInterface
00067 {
00068 public:
00069
00073 PlannerInterface()
00074 {
00075 }
00079 virtual ~PlannerInterface()
00080 {
00081 }
00082
00083
00086
00098 virtual bool plan(const std::vector<geometry_msgs::PoseStamped>& initial_plan, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false) = 0;
00099
00111 virtual bool plan(const tf::Pose& start, const tf::Pose& goal, const geometry_msgs::Twist* start_vel = NULL, bool free_goal_vel=false) = 0;
00112
00124 virtual bool plan(const PoseSE2& start, const PoseSE2& goal, const Eigen::Vector2d& start_vel, bool free_goal_vel=false) = 0;
00125
00133 virtual bool getVelocityCommand(double& v, double& omega) const = 0;
00134
00136
00137
00141 virtual void clearPlanner() = 0;
00142
00147 virtual void visualize()
00148 {
00149 }
00150
00164 virtual bool isTrajectoryFeasible(base_local_planner::CostmapModel* costmap_model, const std::vector<geometry_msgs::Point>& footprint_spec,
00165 double inscribed_radius = 0.0, double circumscribed_radius=0.0, int look_ahead_idx=-1) = 0;
00166
00167
00178 virtual bool isHorizonReductionAppropriate(const std::vector<geometry_msgs::PoseStamped>& initial_plan) const {return false;}
00179
00187 virtual void computeCurrentCost(std::vector<double>& cost, double obst_cost_scale=1.0, bool alternative_time_cost=false)
00188 {
00189 }
00190
00191 };
00192
00194 typedef boost::shared_ptr<PlannerInterface> PlannerInterfacePtr;
00195
00196
00197 }
00198
00199 #endif