cb_base_navigation
Public Member Functions | Protected Member Functions | List of all members
cb_global_planner::GlobalPlannerPlugin Class Referenceabstract

Provides an interface for global planners used in navigation. More...

#include <global_planner_plugin.h>

Inheritance diagram for cb_global_planner::GlobalPlannerPlugin:
Inheritance graph
[legend]

Public Member Functions

virtual bool checkPlan (const std::vector< geometry_msgs::PoseStamped > &plan)=0
 Checks if a plan is valid. More...
 
virtual void initialize (std::string name, tf2_ros::Buffer *tf, costmap_2d::Costmap2DROS *global_costmap_ros)=0
 Initialization function for the BaseGlobalPlanner. More...
 
virtual bool 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)=0
 Given a set of goal constraints, compute a plan. More...
 
virtual ~GlobalPlannerPlugin ()
 Virtual destructor for the interface. More...
 

Protected Member Functions

 GlobalPlannerPlugin ()
 

Detailed Description

Provides an interface for global planners used in navigation.

Definition at line 32 of file global_planner_plugin.h.

Constructor & Destructor Documentation

◆ ~GlobalPlannerPlugin()

virtual cb_global_planner::GlobalPlannerPlugin::~GlobalPlannerPlugin ( )
inlinevirtual

Virtual destructor for the interface.

Definition at line 62 of file global_planner_plugin.h.

◆ GlobalPlannerPlugin()

cb_global_planner::GlobalPlannerPlugin::GlobalPlannerPlugin ( )
inlineprotected

Definition at line 65 of file global_planner_plugin.h.

Member Function Documentation

◆ checkPlan()

virtual bool cb_global_planner::GlobalPlannerPlugin::checkPlan ( const std::vector< geometry_msgs::PoseStamped > &  plan)
pure virtual

Checks if a plan is valid.

Parameters
planThe plan that needs to be checked
Returns
True if a valid plan was valid, false otherwise

Implemented in cb_global_planner::AStarPlannerGPP.

◆ initialize()

virtual void cb_global_planner::GlobalPlannerPlugin::initialize ( std::string  name,
tf2_ros::Buffer *  tf,
costmap_2d::Costmap2DROS global_costmap_ros 
)
pure virtual

Initialization function for the BaseGlobalPlanner.

Parameters
nameThe name of this planner
tftf buffer
costmap_rosA 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
startThe start pose
pcPosition contraints on the goal position
planThe 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: