Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
Public Types | Public Member Functions | List of all members
nav2_core::GlobalPlanner Class Referenceabstract

Abstract interface for global planners to adhere to with pluginlib. More...

#include <nav2_core/include/nav2_core/global_planner.hpp>

Inheritance diagram for nav2_core::GlobalPlanner:
Inheritance graph
[legend]

Public Types

using Ptr = std::shared_ptr< GlobalPlanner >
 

Public Member Functions

virtual ~GlobalPlanner ()
 Virtual destructor.
 
virtual void configure (const rclcpp_lifecycle::LifecycleNode::WeakPtr &parent, std::string name, std::shared_ptr< tf2_ros::Buffer > tf, std::shared_ptr< nav2_costmap_2d::Costmap2DROS > costmap_ros)=0
 
virtual void cleanup ()=0
 Method to cleanup resources used on shutdown.
 
virtual void activate ()=0
 Method to active planner and any threads involved in execution.
 
virtual void deactivate ()=0
 Method to deactive planner and any threads involved in execution.
 
virtual nav_msgs::msg::Path createPlan (const geometry_msgs::msg::PoseStamped &start, const geometry_msgs::msg::PoseStamped &goal)=0
 Method create the plan from a starting and ending goal. More...
 

Detailed Description

Abstract interface for global planners to adhere to with pluginlib.

Definition at line 34 of file global_planner.hpp.

Member Function Documentation

◆ configure()

virtual void nav2_core::GlobalPlanner::configure ( const rclcpp_lifecycle::LifecycleNode::WeakPtr &  parent,
std::string  name,
std::shared_ptr< tf2_ros::Buffer >  tf,
std::shared_ptr< nav2_costmap_2d::Costmap2DROS costmap_ros 
)
pure virtual
Parameters
parentpointer to user's node
nameThe name of this planner
tfA pointer to a TF buffer
costmap_rosA pointer to the costmap

Implemented in nav2_theta_star_planner::ThetaStarPlanner, nav2_smac_planner::SmacPlannerLattice, nav2_smac_planner::SmacPlannerHybrid, nav2_smac_planner::SmacPlanner2D, and nav2_navfn_planner::NavfnPlanner.

◆ createPlan()

virtual nav_msgs::msg::Path nav2_core::GlobalPlanner::createPlan ( const geometry_msgs::msg::PoseStamped &  start,
const geometry_msgs::msg::PoseStamped &  goal 
)
pure virtual

Method create the plan from a starting and ending goal.

Parameters
startThe starting pose of the robot
goalThe goal pose of the robot
Returns
The sequence of poses to get from start to goal, if any

Implemented in nav2_theta_star_planner::ThetaStarPlanner, nav2_smac_planner::SmacPlannerLattice, nav2_smac_planner::SmacPlannerHybrid, nav2_smac_planner::SmacPlanner2D, and nav2_navfn_planner::NavfnPlanner.


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