#include <abstract_planner.h>
Public Types | |
typedef boost::shared_ptr < ::mbf_abstract_core::AbstractPlanner > | Ptr |
Public Member Functions | |
virtual bool | cancel ()=0 |
Requests the planner to cancel, e.g. if it takes too much time. | |
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. | |
virtual | ~AbstractPlanner () |
Destructor. | |
Protected Member Functions | |
AbstractPlanner () | |
Constructor. |
Definition at line 51 of file abstract_planner.h.
typedef boost::shared_ptr< ::mbf_abstract_core::AbstractPlanner > mbf_abstract_core::AbstractPlanner::Ptr |
Definition at line 54 of file abstract_planner.h.
virtual mbf_abstract_core::AbstractPlanner::~AbstractPlanner | ( | ) | [inline, virtual] |
Destructor.
Definition at line 59 of file abstract_planner.h.
mbf_abstract_core::AbstractPlanner::AbstractPlanner | ( | ) | [inline, protected] |
Constructor.
Definition at line 100 of file abstract_planner.h.
virtual bool mbf_abstract_core::AbstractPlanner::cancel | ( | ) | [pure virtual] |
Requests the planner to cancel, e.g. if it takes too much time.
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.
start | The start pose |
goal | The goal pose |
tolerance | If the goal is obstructed, how many meters the planner can relax the constraint in x and y before failing |
plan | The plan... filled by the planner |
cost | The cost for the the plan |
message | Optional more detailed outcome as a string |