Public Member Functions | Private Attributes
mbf_nav_core_wrapper::WrapperGlobalPlanner Class Reference

#include <wrapper_global_planner.h>

Inheritance diagram for mbf_nav_core_wrapper::WrapperGlobalPlanner:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool cancel ()
 Requests the planner to cancel, e.g. if it takes too much time.
virtual void initialize (std::string name, costmap_2d::Costmap2DROS *costmap_ros)
 Initialization function for the CostmapPlanner.
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)
 Given a goal pose in the world, compute a plan.
 WrapperGlobalPlanner (boost::shared_ptr< nav_core::BaseGlobalPlanner > plugin)
 Public constructor used for handling a nav_core-based plugin.
virtual ~WrapperGlobalPlanner ()
 Virtual destructor for the interface.

Private Attributes

boost::shared_ptr
< nav_core::BaseGlobalPlanner
nav_core_plugin_

Detailed Description

Definition at line 54 of file wrapper_global_planner.h.


Constructor & Destructor Documentation

Public constructor used for handling a nav_core-based plugin.

Parameters:
pluginBackward compatible plugin

Definition at line 75 of file wrapper_global_planner.cpp.

Virtual destructor for the interface.

Definition at line 79 of file wrapper_global_planner.cpp.


Member Function Documentation

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_costmap_core::CostmapPlanner.

Definition at line 65 of file wrapper_global_planner.cpp.

void mbf_nav_core_wrapper::WrapperGlobalPlanner::initialize ( std::string  name,
costmap_2d::Costmap2DROS costmap_ros 
) [virtual]

Initialization function for the CostmapPlanner.

Parameters:
nameThe name of this planner
costmap_rosA pointer to the ROS wrapper of the costmap to use for planning

Implements mbf_costmap_core::CostmapPlanner.

Definition at line 70 of file wrapper_global_planner.cpp.

uint32_t mbf_nav_core_wrapper::WrapperGlobalPlanner::makePlan ( const geometry_msgs::PoseStamped &  start,
const geometry_msgs::PoseStamped &  goal,
double  tolerance,
std::vector< geometry_msgs::PoseStamped > &  plan,
double &  cost,
std::string &  message 
) [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, As this is a wrapper to the nav_core, only 0 (SUCCESS) and 50 (FAILURE) are supported

Implements mbf_costmap_core::CostmapPlanner.

Definition at line 46 of file wrapper_global_planner.cpp.


Member Data Documentation

Definition at line 99 of file wrapper_global_planner.h.


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


mbf_costmap_nav
Author(s): Sebastian Pütz
autogenerated on Mon Jun 17 2019 20:11:40