From e392b159ddea2d17e916b532c8eb2cbdb9dbb9dd Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Thu, 5 Dec 2024 20:56:13 +0000 Subject: [PATCH] Update includes --- .../test_chainable_controller/test_chainable_controller.hpp | 2 +- joint_limits/include/joint_limits/joint_limiter_interface.hpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/controller_manager/test/test_chainable_controller/test_chainable_controller.hpp b/controller_manager/test/test_chainable_controller/test_chainable_controller.hpp index f4f59ad9df..018f78b457 100644 --- a/controller_manager/test/test_chainable_controller/test_chainable_controller.hpp +++ b/controller_manager/test/test_chainable_controller/test_chainable_controller.hpp @@ -22,7 +22,7 @@ #include "controller_interface/chainable_controller_interface.hpp" #include "controller_manager/visibility_control.h" #include "rclcpp/subscription.hpp" -#include "realtime_tools/realtime_buffer.h" +#include "realtime_tools/realtime_buffer.hpp" #include "semantic_components/imu_sensor.hpp" #include "std_msgs/msg/float64_multi_array.hpp" diff --git a/joint_limits/include/joint_limits/joint_limiter_interface.hpp b/joint_limits/include/joint_limits/joint_limiter_interface.hpp index 42403d56ae..17bffed021 100644 --- a/joint_limits/include/joint_limits/joint_limiter_interface.hpp +++ b/joint_limits/include/joint_limits/joint_limiter_interface.hpp @@ -24,7 +24,7 @@ #include "joint_limits/visibility_control.h" #include "rclcpp/node.hpp" #include "rclcpp_lifecycle/lifecycle_node.hpp" -#include "realtime_tools/realtime_buffer.h" +#include "realtime_tools/realtime_buffer.hpp" #include "trajectory_msgs/msg/joint_trajectory_point.hpp" namespace joint_limits