diff --git a/localization/landmark_based_localizer/lidar_marker_localizer/src/lidar_marker_localizer.cpp b/localization/landmark_based_localizer/lidar_marker_localizer/src/lidar_marker_localizer.cpp index ae43015710578..b3a2a36fbb726 100644 --- a/localization/landmark_based_localizer/lidar_marker_localizer/src/lidar_marker_localizer.cpp +++ b/localization/landmark_based_localizer/lidar_marker_localizer/src/lidar_marker_localizer.cpp @@ -58,7 +58,6 @@ LidarMarkerLocalizer::LidarMarkerLocalizer() static_cast(this->declare_parameter("limit_distance_from_self_pose_to_marker")); param_.base_covariance_ = this->declare_parameter>("base_covariance"); - rclcpp::CallbackGroup::SharedPtr points_callback_group; points_callback_group = this->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive); auto points_sub_opt = rclcpp::SubscriptionOptions(); diff --git a/localization/landmark_based_localizer/lidar_marker_localizer/src/lidar_marker_localizer.hpp b/localization/landmark_based_localizer/lidar_marker_localizer/src/lidar_marker_localizer.hpp index cc6cc2595e243..a02543a086349 100644 --- a/localization/landmark_based_localizer/lidar_marker_localizer/src/lidar_marker_localizer.hpp +++ b/localization/landmark_based_localizer/lidar_marker_localizer/src/lidar_marker_localizer.hpp @@ -23,10 +23,10 @@ #include #include -#include #include #include #include +#include #ifdef ROS_DISTRO_GALACTIC #include