From 4e4f54c12afb9f9319e8fe23afa89b637fdc63aa Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Wed, 21 Oct 2020 14:49:13 -0700 Subject: [PATCH 1/2] Include tf2_ros/buffer.h where needed After some cleanup in https://github.com/ros2/geometry2/pull/325, the header is no longer being transitively included. Signed-off-by: Jacob Perron --- include/robot_localization/ros_robot_localization_listener.hpp | 1 + 1 file changed, 1 insertion(+) diff --git a/include/robot_localization/ros_robot_localization_listener.hpp b/include/robot_localization/ros_robot_localization_listener.hpp index ac5707531..4f50d4a32 100644 --- a/include/robot_localization/ros_robot_localization_listener.hpp +++ b/include/robot_localization/ros_robot_localization_listener.hpp @@ -38,6 +38,7 @@ #include #include #include +#include #include #include From 2891cbce905b85be412a8619f1e5d8805ad74c95 Mon Sep 17 00:00:00 2001 From: Jacob Perron Date: Wed, 21 Oct 2020 15:25:53 -0700 Subject: [PATCH 2/2] Fix deprecated usage of FutureReturnCode The namespace rclcpp::executors:: was deprecated in Foxy and removed in https://github.com/ros2/rclcpp/pull/1327. Signed-off-by: Jacob Perron --- test/test_ekf_localization_node_interfaces.cpp | 2 +- test/test_ukf_localization_node_interfaces.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/test/test_ekf_localization_node_interfaces.cpp b/test/test_ekf_localization_node_interfaces.cpp index 5af7495b4..e368d4dfe 100644 --- a/test/test_ekf_localization_node_interfaces.cpp +++ b/test/test_ekf_localization_node_interfaces.cpp @@ -88,7 +88,7 @@ void resetFilter(rclcpp::Node::SharedPtr node_) double deltaY = 0.0; double deltaZ = 0.0; - if (ret == rclcpp::executor::FutureReturnCode::SUCCESS) { + if (ret == rclcpp::FutureReturnCode::SUCCESS) { // timing and spinning has been changed as per ros2 rclcpp::Rate(2).sleep(); rclcpp::spin_some(node_); diff --git a/test/test_ukf_localization_node_interfaces.cpp b/test/test_ukf_localization_node_interfaces.cpp index 9ed1b0a84..6efb4dc79 100644 --- a/test/test_ukf_localization_node_interfaces.cpp +++ b/test/test_ukf_localization_node_interfaces.cpp @@ -88,7 +88,7 @@ void resetFilter(rclcpp::Node::SharedPtr node_) double deltaY = 0.0; double deltaZ = 0.0; // Timing and spinning is updated as per ros2 - if (ret == rclcpp::executor::FutureReturnCode::SUCCESS) { + if (ret == rclcpp::FutureReturnCode::SUCCESS) { rclcpp::Rate(2).sleep(); rclcpp::spin_some(node_); deltaX = filtered_.pose.pose.position.x -