Skip to content

Commit

Permalink
Fix warnings when building against Rolling. (#896)
Browse files Browse the repository at this point in the history
Rolling has moved header files (deprecating the old one),
and changed the preferred form of some templated classes (like
TimeSynchronizer).  Fix those warnings here.

Note that this should *only* be applied for Rolling, as it will
fail to compile for earlier versions of ROS 2.

Signed-off-by: Chris Lalancette <[email protected]>
  • Loading branch information
clalancette authored Aug 27, 2024
1 parent f6b28e0 commit 19065fa
Show file tree
Hide file tree
Showing 2 changed files with 5 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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"
Expand Down
6 changes: 3 additions & 3 deletions src/ros_robot_localization_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_(""),
Expand Down

0 comments on commit 19065fa

Please sign in to comment.