#include <costmap_controller.h>
Public Types | |
typedef boost::shared_ptr < ::mbf_costmap_core::CostmapController > | Ptr |
Public Member Functions | |
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 to the base. | |
virtual void | initialize (std::string name, TF *tf, costmap_2d::Costmap2DROS *costmap_ros)=0 |
Constructs the local planner. | |
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 bool | setPlan (const std::vector< geometry_msgs::PoseStamped > &plan)=0 |
Set the plan that the local planner is following. | |
virtual | ~CostmapController () |
Virtual destructor for the interface. | |
Protected Member Functions | |
CostmapController () |
Definition at line 53 of file costmap_controller.h.
typedef boost::shared_ptr< ::mbf_costmap_core::CostmapController > mbf_costmap_core::CostmapController::Ptr |
Reimplemented from mbf_abstract_core::AbstractController.
Definition at line 56 of file costmap_controller.h.
virtual mbf_costmap_core::CostmapController::~CostmapController | ( | ) | [inline, virtual] |
Virtual destructor for the interface.
Definition at line 124 of file costmap_controller.h.
mbf_costmap_core::CostmapController::CostmapController | ( | ) | [inline, protected] |
Definition at line 127 of file costmap_controller.h.
virtual bool mbf_costmap_core::CostmapController::cancel | ( | ) | [pure virtual] |
Requests the planner to cancel, e.g. if it takes too much time.
Implements mbf_abstract_core::AbstractController.
virtual uint32_t mbf_costmap_core::CostmapController::computeVelocityCommands | ( | const geometry_msgs::PoseStamped & | pose, |
const geometry_msgs::TwistStamped & | velocity, | ||
geometry_msgs::TwistStamped & | cmd_vel, | ||
std::string & | message | ||
) | [pure virtual] |
Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base.
pose | the current pose of the robot. |
velocity | the current velocity of the robot. |
cmd_vel | Will be filled with the velocity command to be passed to the robot base. |
message | Optional more detailed outcome as a string |
Implements mbf_abstract_core::AbstractController.
virtual void mbf_costmap_core::CostmapController::initialize | ( | std::string | name, |
TF * | tf, | ||
costmap_2d::Costmap2DROS * | costmap_ros | ||
) | [pure virtual] |
Constructs the local planner.
name | The name to give this instance of the local planner |
tf | A pointer to a transform listener |
costmap_ros | The cost map to use for assigning costs to local plans |
virtual bool mbf_costmap_core::CostmapController::isGoalReached | ( | double | xy_tolerance, |
double | yaw_tolerance | ||
) | [pure virtual] |
Check if the goal pose has been achieved by the local planner within tolerance limits.
xy_tolerance | Distance tolerance in meters |
yaw_tolerance | Heading tolerance in radians |
Implements mbf_abstract_core::AbstractController.
virtual bool mbf_costmap_core::CostmapController::setPlan | ( | const std::vector< geometry_msgs::PoseStamped > & | plan | ) | [pure virtual] |
Set the plan that the local planner is following.
plan | The plan to pass to the local planner |
Implements mbf_abstract_core::AbstractController.