Go to the documentation of this file.
41 #ifndef MBF_COSTMAP_NAV__WRAPPER_LOCAL_PLANNER_H_
42 #define MBF_COSTMAP_NAV__WRAPPER_LOCAL_PLANNER_H_
69 const geometry_msgs::PoseStamped &robot_pose,
70 const geometry_msgs::TwistStamped &robot_velocity,
71 geometry_msgs::TwistStamped &cmd_vel,
72 std::string &message);
87 virtual bool isGoalReached(
double xy_tolerance,
double yaw_tolerance);
94 virtual bool setPlan(
const std::vector<geometry_msgs::PoseStamped> &plan);
virtual bool cancel()
Requests the planner to cancel, e.g. if it takes too much time.
virtual bool setPlan(const std::vector< geometry_msgs::PoseStamped > &plan)
Set the plan that the local planner is following.
boost::shared_ptr< nav_core::BaseLocalPlanner > nav_core_plugin_
WrapperLocalPlanner(boost::shared_ptr< nav_core::BaseLocalPlanner >plugin)
Public constructor used for handling a nav_core-based plugin.
virtual bool isGoalReached()
Check if the goal pose has been achieved by the local planner.
virtual uint32_t computeVelocityCommands(const geometry_msgs::PoseStamped &robot_pose, const geometry_msgs::TwistStamped &robot_velocity, geometry_msgs::TwistStamped &cmd_vel, std::string &message)
Given the current position, orientation, and velocity of the robot, compute velocity commands to send...
virtual ~WrapperLocalPlanner()
Virtual destructor for the interface.
virtual void initialize(std::string name, TF *tf, costmap_2d::Costmap2DROS *costmap_ros)
Constructs the local planner.
mbf_costmap_nav
Author(s): Sebastian Pütz
autogenerated on Wed Mar 2 2022 00:33:55