47 const geometry_msgs::PoseStamped &robot_pose,
48 const geometry_msgs::TwistStamped &robot_velocity,
49 geometry_msgs::TwistStamped &cmd_vel,
53 message = success ?
"Goal reached" :
"Controller failed";
54 return success ? 0 : 100;
75 "Note: you are running a nav_core based plugin, " 76 "which is wrapped into the MBF interface.");
virtual bool setPlan(const std::vector< geometry_msgs::PoseStamped > &plan)
Set the plan that the local planner is following.
virtual ~WrapperLocalPlanner()
Virtual destructor for the interface.
WrapperLocalPlanner(boost::shared_ptr< nav_core::BaseLocalPlanner >plugin)
Public constructor used for handling a nav_core-based plugin.
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 bool isGoalReached()
Check if the goal pose has been achieved by the local planner.
virtual void initialize(std::string name, TF *tf, costmap_2d::Costmap2DROS *costmap_ros)
Constructs the local planner.
boost::shared_ptr< nav_core::BaseLocalPlanner > nav_core_plugin_
virtual bool cancel()
Requests the planner to cancel, e.g. if it takes too much time.
#define ROS_WARN_STREAM(args)