39 #ifndef MBF_COSTMAP_CORE__COSTMAP_CONTROLLER_H_ 40 #define MBF_COSTMAP_CORE__COSTMAP_CONTROLLER_H_ 86 const geometry_msgs::TwistStamped& velocity,
87 geometry_msgs::TwistStamped &cmd_vel,
88 std::string &message) = 0;
97 virtual bool isGoalReached(
double xy_tolerance,
double yaw_tolerance) = 0;
104 virtual bool setPlan(
const std::vector<geometry_msgs::PoseStamped> &plan) = 0;
111 virtual bool cancel() = 0;
virtual uint32_t computeVelocityCommands(const geometry_msgs::PoseStamped &pose, const geometry_msgs::TwistStamped &velocity, geometry_msgs::TwistStamped &cmd_vel, std::string &message)=0
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
boost::shared_ptr< ::mbf_costmap_core::CostmapController > Ptr
virtual bool cancel()=0
Requests the planner to cancel, e.g. if it takes too much time.
virtual bool isGoalReached(double xy_tolerance, double yaw_tolerance)=0
Check if the goal pose has been achieved by the local planner within tolerance limits.
virtual void initialize(std::string name, TF *tf, costmap_2d::Costmap2DROS *costmap_ros)=0
Constructs the local planner.
virtual ~CostmapController()
Virtual destructor for the interface.
virtual bool setPlan(const std::vector< geometry_msgs::PoseStamped > &plan)=0
Set the plan that the local planner is following.