Public Types | Public Member Functions | Protected Member Functions
mbf_costmap_core::CostmapController Class Reference

#include <costmap_controller.h>

Inheritance diagram for mbf_costmap_core::CostmapController:
Inheritance graph
[legend]

List of all members.

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 ()

Detailed Description

Definition at line 53 of file costmap_controller.h.


Member Typedef Documentation

Reimplemented from mbf_abstract_core::AbstractController.

Definition at line 56 of file costmap_controller.h.


Constructor & Destructor Documentation

Virtual destructor for the interface.

Definition at line 124 of file costmap_controller.h.

Definition at line 127 of file costmap_controller.h.


Member Function Documentation

virtual bool mbf_costmap_core::CostmapController::cancel ( ) [pure virtual]

Requests the planner to cancel, e.g. if it takes too much time.

Remarks:
New on MBF API
Returns:
True if a cancel has been successfully requested, false if not implemented.

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.

Parameters:
posethe current pose of the robot.
velocitythe current velocity of the robot.
cmd_velWill be filled with the velocity command to be passed to the robot base.
messageOptional more detailed outcome as a string
Returns:
Result code as described on ExePath action result: SUCCESS = 0 1..9 are reserved as plugin specific non-error results FAILURE = 100 Unspecified failure, only used for old, non-mfb_core based plugins CANCELED = 101 NO_VALID_CMD = 102 PAT_EXCEEDED = 103 COLLISION = 104 OSCILLATION = 105 ROBOT_STUCK = 106 MISSED_GOAL = 107 MISSED_PATH = 108 BLOCKED_PATH = 109 INVALID_PATH = 110 TF_ERROR = 111 NOT_INITIALIZED = 112 INVALID_PLUGIN = 113 INTERNAL_ERROR = 114 121..149 are reserved as plugin specific errors

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.

Parameters:
nameThe name to give this instance of the local planner
tfA pointer to a transform listener
costmap_rosThe 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.

Remarks:
New on MBF API
Parameters:
xy_toleranceDistance tolerance in meters
yaw_toleranceHeading tolerance in radians
Returns:
True if achieved, false otherwise

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.

Parameters:
planThe plan to pass to the local planner
Returns:
True if the plan was updated successfully, false otherwise

Implements mbf_abstract_core::AbstractController.


The documentation for this class was generated from the following file:


mbf_costmap_core
Author(s): Jorge Santos , Sebastian Pütz
autogenerated on Mon Jun 17 2019 20:11:38