15 #ifndef NAV2_CORE__GLOBAL_PLANNER_HPP_
16 #define NAV2_CORE__GLOBAL_PLANNER_HPP_
20 #include "rclcpp/rclcpp.hpp"
21 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
22 #include "tf2_ros/buffer.h"
23 #include "nav_msgs/msg/path.hpp"
24 #include "geometry_msgs/msg/pose_stamped.hpp"
25 #include "nav2_util/lifecycle_node.hpp"
37 using Ptr = std::shared_ptr<GlobalPlanner>;
51 const rclcpp_lifecycle::LifecycleNode::WeakPtr & parent,
52 std::string name, std::shared_ptr<tf2_ros::Buffer> tf,
53 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) = 0;
77 const geometry_msgs::msg::PoseStamped & start,
78 const geometry_msgs::msg::PoseStamped & goal) = 0;
Abstract interface for global planners to adhere to with pluginlib.
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.
virtual void activate()=0
Method to active planner and any threads involved in execution.
virtual void cleanup()=0
Method to cleanup resources used on shutdown.
virtual void deactivate()=0
Method to deactive planner and any threads involved in execution.
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 ~GlobalPlanner()
Virtual destructor.