39 #ifndef MBF_ABSTRACT_CORE__ABSTRACT_CONTROLLER_H_ 40 #define MBF_ABSTRACT_CORE__ABSTRACT_CONTROLLER_H_ 45 #include <boost/shared_ptr.hpp> 46 #include <geometry_msgs/TwistStamped.h> 47 #include <geometry_msgs/PoseStamped.h> 90 const geometry_msgs::TwistStamped& velocity,
91 geometry_msgs::TwistStamped &cmd_vel,
92 std::string &message) = 0;
100 virtual bool isGoalReached(
double dist_tolerance,
double angle_tolerance) = 0;
107 virtual bool setPlan(
const std::vector<geometry_msgs::PoseStamped> &plan) = 0;
113 virtual bool cancel() = 0;
virtual bool isGoalReached(double dist_tolerance, double angle_tolerance)=0
Check if the goal pose has been achieved by the local planner.
virtual bool cancel()=0
Requests the planner to cancel, e.g. if it takes too much time.
AbstractController()
Constructor.
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...
virtual bool setPlan(const std::vector< geometry_msgs::PoseStamped > &plan)=0
Set the plan that the local planner is following.
virtual ~AbstractController()
Destructor.
boost::shared_ptr< ::mbf_abstract_core::AbstractController > Ptr