Public Member Functions | Private Attributes | List of all members
mbf_nav_core_wrapper::WrapperLocalPlanner Class Reference

#include <wrapper_local_planner.h>

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

Public Member Functions

virtual bool cancel ()
 Requests the planner to cancel, e.g. if it takes too much time. More...
 
virtual uint32_t computeVelocityCommands (const geometry_msgs::PoseStamped &robot_pose, const geometry_msgs::TwistStamped &robot_velocity, geometry_msgs::TwistStamped &cmd_vel, std::string &message)
 Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base. More...
 
virtual void initialize (std::string name, TF *tf, costmap_2d::Costmap2DROS *costmap_ros)
 Constructs the local planner. More...
 
virtual bool isGoalReached ()
 Check if the goal pose has been achieved by the local planner. More...
 
virtual bool isGoalReached (double xy_tolerance, double yaw_tolerance)
 Check if the goal pose has been achieved by the local planner within tolerance limits. More...
 
virtual bool setPlan (const std::vector< geometry_msgs::PoseStamped > &plan)
 Set the plan that the local planner is following. More...
 
 WrapperLocalPlanner (boost::shared_ptr< nav_core::BaseLocalPlanner >plugin)
 Public constructor used for handling a nav_core-based plugin. More...
 
virtual ~WrapperLocalPlanner ()
 Virtual destructor for the interface. More...
 
- Public Member Functions inherited from mbf_costmap_core::CostmapController
virtual void initialize (std::string name,::TF *tf, costmap_2d::Costmap2DROS *costmap_ros)=0
 
virtual ~CostmapController ()
 
- Public Member Functions inherited from mbf_abstract_core::AbstractController
virtual ~AbstractController ()
 

Private Attributes

boost::shared_ptr< nav_core::BaseLocalPlannernav_core_plugin_
 

Additional Inherited Members

- Public Types inherited from mbf_costmap_core::CostmapController
typedef boost::shared_ptr< ::mbf_costmap_core::CostmapControllerPtr
 
- Public Types inherited from mbf_abstract_core::AbstractController
typedef boost::shared_ptr< ::mbf_abstract_core::AbstractControllerPtr
 
- Protected Member Functions inherited from mbf_costmap_core::CostmapController
 CostmapController ()
 
- Protected Member Functions inherited from mbf_abstract_core::AbstractController
 AbstractController ()
 

Detailed Description

Definition at line 56 of file wrapper_local_planner.h.

Constructor & Destructor Documentation

mbf_nav_core_wrapper::WrapperLocalPlanner::WrapperLocalPlanner ( boost::shared_ptr< nav_core::BaseLocalPlanner plugin)

Public constructor used for handling a nav_core-based plugin.

Parameters
pluginBackward compatible plugin

Definition at line 87 of file wrapper_local_planner.cpp.

mbf_nav_core_wrapper::WrapperLocalPlanner::~WrapperLocalPlanner ( )
virtual

Virtual destructor for the interface.

Definition at line 91 of file wrapper_local_planner.cpp.

Member Function Documentation

bool mbf_nav_core_wrapper::WrapperLocalPlanner::cancel ( )
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_costmap_core::CostmapController.

Definition at line 72 of file wrapper_local_planner.cpp.

uint32_t mbf_nav_core_wrapper::WrapperLocalPlanner::computeVelocityCommands ( const geometry_msgs::PoseStamped &  robot_pose,
const geometry_msgs::TwistStamped &  robot_velocity,
geometry_msgs::TwistStamped &  cmd_vel,
std::string &  message 
)
virtual

Given the current position, orientation, and velocity of the robot, compute velocity commands to send to the base.

Remarks
New on MBF API; replaces version without output code and message
Parameters
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, as this is a wrapper to the nav_core, only 0 (SUCCESS) and 100 (FAILURE) are supported.

Implements mbf_costmap_core::CostmapController.

Definition at line 46 of file wrapper_local_planner.cpp.

void mbf_nav_core_wrapper::WrapperLocalPlanner::initialize ( std::string  name,
TF tf,
costmap_2d::Costmap2DROS costmap_ros 
)
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

Definition at line 80 of file wrapper_local_planner.cpp.

bool mbf_nav_core_wrapper::WrapperLocalPlanner::isGoalReached ( )
virtual

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

Returns
True if achieved, false otherwise

Definition at line 57 of file wrapper_local_planner.cpp.

bool mbf_nav_core_wrapper::WrapperLocalPlanner::isGoalReached ( double  xy_tolerance,
double  yaw_tolerance 
)
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_costmap_core::CostmapController.

Definition at line 62 of file wrapper_local_planner.cpp.

bool mbf_nav_core_wrapper::WrapperLocalPlanner::setPlan ( const std::vector< geometry_msgs::PoseStamped > &  plan)
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_costmap_core::CostmapController.

Definition at line 67 of file wrapper_local_planner.cpp.

Member Data Documentation

boost::shared_ptr< nav_core::BaseLocalPlanner > mbf_nav_core_wrapper::WrapperLocalPlanner::nav_core_plugin_
private

Definition at line 123 of file wrapper_local_planner.h.


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


mbf_costmap_nav
Author(s): Sebastian Pütz
autogenerated on Fri Nov 6 2020 03:56:29