Provides an interface for global planners used in navigation.
More...
#include <global_planner_plugin.h>
Provides an interface for global planners used in navigation.
Definition at line 32 of file global_planner_plugin.h.
◆ ~GlobalPlannerPlugin()
virtual cb_global_planner::GlobalPlannerPlugin::~GlobalPlannerPlugin |
( |
| ) |
|
|
inlinevirtual |
◆ GlobalPlannerPlugin()
cb_global_planner::GlobalPlannerPlugin::GlobalPlannerPlugin |
( |
| ) |
|
|
inlineprotected |
◆ checkPlan()
virtual bool cb_global_planner::GlobalPlannerPlugin::checkPlan |
( |
const std::vector< geometry_msgs::PoseStamped > & |
plan | ) |
|
|
pure virtual |
Checks if a plan is valid.
- Parameters
-
plan | The plan that needs to be checked |
- Returns
- True if a valid plan was valid, false otherwise
Implemented in cb_global_planner::AStarPlannerGPP.
◆ initialize()
Initialization function for the BaseGlobalPlanner.
- Parameters
-
name | The name of this planner |
tf | tf buffer |
costmap_ros | A pointer to the ROS wrapper of the costmap to use for planning |
Implemented in cb_global_planner::AStarPlannerGPP.
◆ makePlan()
virtual bool cb_global_planner::GlobalPlannerPlugin::makePlan |
( |
const geometry_msgs::PoseStamped & |
start, |
|
|
const cb_base_navigation_msgs::PositionConstraint & |
pc, |
|
|
std::vector< geometry_msgs::PoseStamped > & |
plan, |
|
|
std::vector< tf2::Vector3 > & |
goal_positions |
|
) |
| |
|
pure virtual |
Given a set of goal constraints, compute a plan.
- Parameters
-
start | The start pose |
pc | Position contraints on the goal position |
plan | The plan... filled by the planner |
- Returns
- True if a valid plan was found, false otherwise
Implemented in cb_global_planner::AStarPlannerGPP.
The documentation for this class was generated from the following file: