Public Types | Public Member Functions | Protected Member Functions
mbf_abstract_core::AbstractController Class Reference

#include <abstract_controller.h>

List of all members.

Public Types

typedef boost::shared_ptr
< ::mbf_abstract_core::AbstractController
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 bool isGoalReached (double dist_tolerance, double angle_tolerance)=0
 Check if the goal pose has been achieved by the local planner.
virtual bool setPlan (const std::vector< geometry_msgs::PoseStamped > &plan)=0
 Set the plan that the local planner is following.
virtual ~AbstractController ()
 Destructor.

Protected Member Functions

 AbstractController ()
 Constructor.

Detailed Description

Definition at line 51 of file abstract_controller.h.


Member Typedef Documentation

Definition at line 55 of file abstract_controller.h.


Constructor & Destructor Documentation

Destructor.

Definition at line 60 of file abstract_controller.h.

Constructor.

Definition at line 119 of file abstract_controller.h.


Member Function Documentation

virtual bool mbf_abstract_core::AbstractController::cancel ( ) [pure virtual]

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

Returns:
True if a cancel has been successfully requested, false if not implemented.
virtual uint32_t mbf_abstract_core::AbstractController::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
virtual bool mbf_abstract_core::AbstractController::isGoalReached ( double  dist_tolerance,
double  angle_tolerance 
) [pure virtual]

Check if the goal pose has been achieved by the local planner.

Parameters:
angle_toleranceThe angle tolerance in which the current pose will be partly accepted as reached goal
dist_toleranceThe distance tolerance in which the current pose will be partly accepted as reached goal
Returns:
True if achieved, false otherwise
virtual bool mbf_abstract_core::AbstractController::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

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


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