16
16
#include " rclcpp/rclcpp.hpp"
17
17
#include " pluginlib/class_loader.hpp"
18
18
#include " pluginlib/class_list_macros.hpp"
19
+ #include " nav2_ros_common/lifecycle_node.hpp"
20
+ #include " nav2_ros_common/node_utils.hpp"
19
21
20
22
namespace nav2_pure_pursuit_controller
21
23
{
@@ -27,7 +29,7 @@ class PurePursuitController : public nav2_core::Controller
27
29
~PurePursuitController () override = default ;
28
30
29
31
void configure (
30
- const rclcpp_lifecycle ::LifecycleNode::WeakPtr & parent,
32
+ const nav2 ::LifecycleNode::WeakPtr & parent,
31
33
std::string name, const std::shared_ptr<tf2_ros::Buffer> tf,
32
34
const std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros) override ;
33
35
@@ -55,7 +57,7 @@ class PurePursuitController : public nav2_core::Controller
55
57
const rclcpp::Duration & transform_tolerance
56
58
) const ;
57
59
58
- rclcpp_lifecycle ::LifecycleNode::WeakPtr node_;
60
+ nav2 ::LifecycleNode::WeakPtr node_;
59
61
std::shared_ptr<tf2_ros::Buffer> tf_;
60
62
std::string plugin_name_;
61
63
std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
@@ -68,7 +70,7 @@ class PurePursuitController : public nav2_core::Controller
68
70
rclcpp::Duration transform_tolerance_ {0 , 0 };
69
71
70
72
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_;
72
74
};
73
75
74
76
} // namespace nav2_pure_pursuit_controller
0 commit comments