Class GlobalPlanner

Class Documentation

class GlobalPlanner

Abstract interface for global planners to adhere to with pluginlib.

Public Types

using Ptr = std::shared_ptr<GlobalPlanner>

Public Functions

inline 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
Parameters:
  • parent – pointer to user’s node

  • name – The name of this planner

  • tf – A pointer to a TF buffer

  • costmap_ros – A pointer to the costmap

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.

Parameters:
  • start – The starting pose of the robot

  • goal – The goal pose of the robot

Returns:

The sequence of poses to get from start to goal, if any