Public Types | Public Member Functions | Protected Member Functions | List of all members
mbf_abstract_core::AbstractPlanner Class Referenceabstract

#include <abstract_planner.h>

Public Types

typedef boost::shared_ptr< ::mbf_abstract_core::AbstractPlannerPtr
 

Public Member Functions

virtual bool cancel ()=0
 Requests the planner to cancel, e.g. if it takes too much time. More...
 
virtual uint32_t makePlan (const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, double tolerance, std::vector< geometry_msgs::PoseStamped > &plan, double &cost, std::string &message)=0
 Given a goal pose in the world, compute a plan. More...
 
virtual ~AbstractPlanner ()
 Destructor. More...
 

Protected Member Functions

 AbstractPlanner ()
 Constructor. More...
 

Detailed Description

Definition at line 51 of file abstract_planner.h.

Member Typedef Documentation

Definition at line 54 of file abstract_planner.h.

Constructor & Destructor Documentation

virtual mbf_abstract_core::AbstractPlanner::~AbstractPlanner ( )
inlinevirtual

Destructor.

Definition at line 59 of file abstract_planner.h.

mbf_abstract_core::AbstractPlanner::AbstractPlanner ( )
inlineprotected

Constructor.

Definition at line 100 of file abstract_planner.h.

Member Function Documentation

virtual bool mbf_abstract_core::AbstractPlanner::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::AbstractPlanner::makePlan ( const geometry_msgs::PoseStamped &  start,
const geometry_msgs::PoseStamped &  goal,
double  tolerance,
std::vector< geometry_msgs::PoseStamped > &  plan,
double &  cost,
std::string &  message 
)
pure virtual

Given a goal pose in the world, compute a plan.

Parameters
startThe start pose
goalThe goal pose
toleranceIf the goal is obstructed, how many meters the planner can relax the constraint in x and y before failing
planThe plan... filled by the planner
costThe cost for the the plan
messageOptional more detailed outcome as a string
Returns
Result code as described on GetPath action result: SUCCESS = 0 1..9 are reserved as plugin specific non-error results FAILURE = 50 # Unspecified failure, only used for old, non-mfb_core based plugins CANCELED = 51 INVALID_START = 52 INVALID_GOAL = 53 NO_PATH_FOUND = 54 PAT_EXCEEDED = 55 EMPTY_PATH = 56 TF_ERROR = 57 NOT_INITIALIZED = 58 INVALID_PLUGIN = 59 INTERNAL_ERROR = 60 71..99 are reserved as plugin specific errors

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


mbf_abstract_core
Author(s): Sebastian Pütz , Jorge Santos
autogenerated on Tue Jun 18 2019 19:34:30