Go to the documentation of this file.
37 #ifndef MBF_MESH_CORE__MESH_CONTROLLER_H
38 #define MBF_MESH_CORE__MESH_CONTROLLER_H
40 #include <boost/shared_ptr.hpp>
41 #include <geometry_msgs/PoseStamped.h>
42 #include <geometry_msgs/TwistStamped.h>
72 const geometry_msgs::TwistStamped& velocity,
73 geometry_msgs::TwistStamped& cmd_vel, std::string& message) = 0;
83 virtual bool isGoalReached(
double dist_tolerance,
double angle_tolerance) = 0;
90 virtual bool setPlan(
const std::vector<geometry_msgs::PoseStamped>& plan) = 0;
virtual bool initialize(const std::string &name, const boost::shared_ptr< tf2_ros::Buffer > &tf_ptr, const boost::shared_ptr< mesh_map::MeshMap > &mesh_map_ptr)=0
Initializes the controller plugin with a name, a tf pointer and a mesh map pointer.
virtual ~MeshController()
Destructor.
virtual bool isGoalReached(double dist_tolerance, double angle_tolerance)=0
Check if the goal pose has been achieved by the local planner.
boost::shared_ptr< mbf_mesh_core::MeshController > Ptr
MeshController()
Constructor.
virtual bool cancel()=0
Requests the planner to cancel, e.g. if it takes too much time.
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.
mbf_mesh_core
Author(s): Sebastian Pütz
autogenerated on Thu Jan 25 2024 03:42:49