1616#include " rclcpp/rclcpp.hpp"
1717#include " pluginlib/class_loader.hpp"
1818#include " pluginlib/class_list_macros.hpp"
19+ #include " nav2_ros_common/lifecycle_node.hpp"
20+ #include " nav2_ros_common/node_utils.hpp"
1921
2022namespace nav2_pure_pursuit_controller
2123{
@@ -27,7 +29,7 @@ class PurePursuitController : public nav2_core::Controller
2729 ~PurePursuitController () override = default ;
2830
2931 void configure (
30- const rclcpp_lifecycle ::LifecycleNode::WeakPtr & parent,
32+ const nav2 ::LifecycleNode::WeakPtr & parent,
3133 std::string name, const std::shared_ptr<tf2_ros::Buffer> tf,
3234 const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override ;
3335
@@ -55,7 +57,7 @@ class PurePursuitController : public nav2_core::Controller
5557 const rclcpp::Duration & transform_tolerance
5658 ) const ;
5759
58- rclcpp_lifecycle ::LifecycleNode::WeakPtr node_;
60+ nav2 ::LifecycleNode::WeakPtr node_;
5961 std::shared_ptr<tf2_ros::Buffer> tf_;
6062 std::string plugin_name_;
6163 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
@@ -68,7 +70,7 @@ class PurePursuitController : public nav2_core::Controller
6870 rclcpp::Duration transform_tolerance_ {0 , 0 };
6971
7072 nav_msgs::msg::Path global_plan_;
71- std::shared_ptr<rclcpp_lifecycle::LifecyclePublisher <nav_msgs::msg::Path>> global_pub_;
73+ std::shared_ptr<nav2::Publisher <nav_msgs::msg::Path>> global_pub_;
7274};
7375
7476} // namespace nav2_pure_pursuit_controller
0 commit comments