diff --git a/include/robot_localization/ros_robot_localization_listener.hpp b/include/robot_localization/ros_robot_localization_listener.hpp index 9e5d679b..ae53e451 100644 --- a/include/robot_localization/ros_robot_localization_listener.hpp +++ b/include/robot_localization/ros_robot_localization_listener.hpp @@ -37,8 +37,8 @@ #include "Eigen/Dense" #include "geometry_msgs/msg/accel_with_covariance_stamped.hpp" -#include "message_filters/subscriber.h" -#include "message_filters/time_synchronizer.h" +#include "message_filters/subscriber.hpp" +#include "message_filters/time_synchronizer.hpp" #include "nav_msgs/msg/odometry.hpp" #include "rclcpp/qos.hpp" #include "rclcpp/rclcpp.hpp" diff --git a/src/ros_robot_localization_listener.cpp b/src/ros_robot_localization_listener.cpp index e5083708..d1b32d85 100644 --- a/src/ros_robot_localization_listener.cpp +++ b/src/ros_robot_localization_listener.cpp @@ -70,9 +70,9 @@ RosRobotLocalizationListener::RosRobotLocalizationListener( rclcpp::SubscriptionOptions options) : qos1_(1), qos10_(10), - odom_sub_(node, "odom/filtered", qos1_.get_rmw_qos_profile(), options), - accel_sub_(node, "acceleration/filtered", qos1_.get_rmw_qos_profile(), options), - sync_(odom_sub_, accel_sub_, 10u), + odom_sub_(node, "odom/filtered", qos1_, options), + accel_sub_(node, "acceleration/filtered", qos1_, options), + sync_(10u, odom_sub_, accel_sub_), node_clock_(node->get_node_clock_interface()->get_clock()), node_logger_(node->get_node_logging_interface()), base_frame_id_(""),