2929#include < vector>
3030
3131#include " message_filters/subscriber.hpp"
32+ #include " rclcpp/version.h"
3233
3334#include " geometry_msgs/msg/pose_stamped.hpp"
34- #include " nav2_util /lifecycle_node.hpp"
35+ #include " nav2_ros_common /lifecycle_node.hpp"
3536#include " nav2_amcl/motion_model/motion_model.hpp"
3637#include " nav2_amcl/sensors/laser/laser.hpp"
3738#include " nav2_msgs/msg/particle.hpp"
4142#include " pluginlib/class_loader.hpp"
4243#include " rclcpp/node_options.hpp"
4344#include " sensor_msgs/msg/laser_scan.hpp"
44- #include " nav2_util /service_server.hpp"
45+ #include " nav2_ros_common /service_server.hpp"
4546#include " std_srvs/srv/empty.hpp"
4647#include " tf2_ros/message_filter.h"
4748#include " tf2_ros/transform_broadcaster.h"
@@ -55,7 +56,7 @@ namespace nav2_amcl
5556 * @class AmclNode
5657 * @brief ROS wrapper for AMCL
5758 */
58- class AmclNode : public nav2_util ::LifecycleNode
59+ class AmclNode : public nav2 ::LifecycleNode
5960{
6061public:
6162 /*
@@ -72,23 +73,23 @@ class AmclNode : public nav2_util::LifecycleNode
7273 /*
7374 * @brief Lifecycle configure
7475 */
75- nav2_util ::CallbackReturn on_configure (const rclcpp_lifecycle::State & state) override ;
76+ nav2 ::CallbackReturn on_configure (const rclcpp_lifecycle::State & state) override ;
7677 /*
7778 * @brief Lifecycle activate
7879 */
79- nav2_util ::CallbackReturn on_activate (const rclcpp_lifecycle::State & state) override ;
80+ nav2 ::CallbackReturn on_activate (const rclcpp_lifecycle::State & state) override ;
8081 /*
8182 * @brief Lifecycle deactivate
8283 */
83- nav2_util ::CallbackReturn on_deactivate (const rclcpp_lifecycle::State & state) override ;
84+ nav2 ::CallbackReturn on_deactivate (const rclcpp_lifecycle::State & state) override ;
8485 /*
8586 * @brief Lifecycle cleanup
8687 */
87- nav2_util ::CallbackReturn on_cleanup (const rclcpp_lifecycle::State & state) override ;
88+ nav2 ::CallbackReturn on_cleanup (const rclcpp_lifecycle::State & state) override ;
8889 /*
8990 * @brief Lifecycle shutdown
9091 */
91- nav2_util ::CallbackReturn on_shutdown (const rclcpp_lifecycle::State & state) override ;
92+ nav2 ::CallbackReturn on_shutdown (const rclcpp_lifecycle::State & state) override ;
9293
9394 /* *
9495 * @brief Callback executed when a parameter change is detected
@@ -108,7 +109,7 @@ class AmclNode : public nav2_util::LifecycleNode
108109 // in order to isolate TF timer used in message filter.
109110 rclcpp::CallbackGroup::SharedPtr callback_group_;
110111 rclcpp::executors::SingleThreadedExecutor::SharedPtr executor_;
111- std::unique_ptr<nav2_util ::NodeThread> executor_thread_;
112+ std::unique_ptr<nav2 ::NodeThread> executor_thread_;
112113
113114 // Pose hypothesis
114115 typedef struct
@@ -171,8 +172,15 @@ class AmclNode : public nav2_util::LifecycleNode
171172 * @brief Initialize incoming data message subscribers and filters
172173 */
173174 void initMessageFilters ();
175+
176+ // To Support Kilted and Older from Message Filters API change
177+ #if RCLCPP_VERSION_GTE(29, 6, 0)
178+ std::unique_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan>> laser_scan_sub_;
179+ #else
174180 std::unique_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
175- rclcpp_lifecycle::LifecycleNode>> laser_scan_sub_;
181+ nav2::LifecycleNode>> laser_scan_sub_;
182+ #endif
183+
176184 std::unique_ptr<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>> laser_scan_filter_;
177185 message_filters::Connection laser_scan_connection_;
178186
@@ -201,8 +209,7 @@ class AmclNode : public nav2_util::LifecycleNode
201209 * @brief Initialize state services
202210 */
203211 void initServices ();
204- nav2_util::ServiceServer<std_srvs::srv::Empty,
205- std::shared_ptr<nav2_util::LifecycleNode>>::SharedPtr global_loc_srv_;
212+ nav2::ServiceServer<std_srvs::srv::Empty>::SharedPtr global_loc_srv_;
206213 /*
207214 * @brief Service callback for a global relocalization request
208215 */
@@ -212,8 +219,7 @@ class AmclNode : public nav2_util::LifecycleNode
212219 std::shared_ptr<std_srvs::srv::Empty::Response> response);
213220
214221 // service server for providing an initial pose guess
215- nav2_util::ServiceServer<nav2_msgs::srv::SetInitialPose,
216- std::shared_ptr<nav2_util::LifecycleNode>>::SharedPtr initial_guess_srv_;
222+ nav2::ServiceServer<nav2_msgs::srv::SetInitialPose>::SharedPtr initial_guess_srv_;
217223 /*
218224 * @brief Service callback for an initial pose guess request
219225 */
@@ -223,8 +229,7 @@ class AmclNode : public nav2_util::LifecycleNode
223229 std::shared_ptr<nav2_msgs::srv::SetInitialPose::Response> response);
224230
225231 // Let amcl update samples without requiring motion
226- nav2_util::ServiceServer<std_srvs::srv::Empty,
227- std::shared_ptr<nav2_util::LifecycleNode>>::SharedPtr nomotion_update_srv_;
232+ nav2::ServiceServer<std_srvs::srv::Empty>::SharedPtr nomotion_update_srv_;
228233 /*
229234 * @brief Request an AMCL update even though the robot hasn't moved
230235 */
0 commit comments