#include <wrapper_local_planner.h>
|
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...
|
|
virtual void | initialize (std::string name,::TF *tf, costmap_2d::Costmap2DROS *costmap_ros)=0 |
|
virtual | ~CostmapController () |
|
virtual | ~AbstractController () |
|
Definition at line 56 of file wrapper_local_planner.h.
Public constructor used for handling a nav_core-based plugin.
- Parameters
-
plugin | Backward compatible plugin |
Definition at line 87 of file wrapper_local_planner.cpp.
mbf_nav_core_wrapper::WrapperLocalPlanner::~WrapperLocalPlanner |
( |
| ) |
|
|
virtual |
bool mbf_nav_core_wrapper::WrapperLocalPlanner::cancel |
( |
| ) |
|
|
virtual |
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.
- Parameters
-
cmd_vel | Will be filled with the velocity command to be passed to the robot base |
message | Optional 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.
Constructs the local planner.
- Parameters
-
name | The name to give this instance of the local planner |
tf | A pointer to a transform listener |
costmap_ros | The 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.
- Parameters
-
xy_tolerance | Distance tolerance in meters |
yaw_tolerance | Heading 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 |
The documentation for this class was generated from the following files: