From 861d8095ff3400f79427641b1e02061dd6d074e7 Mon Sep 17 00:00:00 2001 From: Sanjeev <62834697+kumar-sanjeeev@users.noreply.github.com> Date: Fri, 20 Dec 2024 21:45:15 +0100 Subject: [PATCH] Update header files of realtime_tools pkg (#676) (cherry picked from commit 1dd221a456699ebbdeea2ce48f836410dbef0328) --- .../include/passthrough_controller/passthrough_controller.hpp | 2 +- .../rrbot_sensor_for_position_feedback.hpp | 2 +- .../include/ros2_control_demo_example_7/r6bot_controller.hpp | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/example_12/controllers/include/passthrough_controller/passthrough_controller.hpp b/example_12/controllers/include/passthrough_controller/passthrough_controller.hpp index 829aa7101..c90a894c9 100644 --- a/example_12/controllers/include/passthrough_controller/passthrough_controller.hpp +++ b/example_12/controllers/include/passthrough_controller/passthrough_controller.hpp @@ -22,7 +22,7 @@ #include #include "controller_interface/chainable_controller_interface.hpp" -#include "realtime_tools/realtime_buffer.h" +#include "realtime_tools/realtime_buffer.hpp" #include "std_msgs/msg/float64_multi_array.hpp" // auto-generated by generate_parameter_library #include "passthrough_controller_parameters.hpp" diff --git a/example_14/hardware/include/ros2_control_demo_example_14/rrbot_sensor_for_position_feedback.hpp b/example_14/hardware/include/ros2_control_demo_example_14/rrbot_sensor_for_position_feedback.hpp index 9716755d2..0fe41d604 100644 --- a/example_14/hardware/include/ros2_control_demo_example_14/rrbot_sensor_for_position_feedback.hpp +++ b/example_14/hardware/include/ros2_control_demo_example_14/rrbot_sensor_for_position_feedback.hpp @@ -34,7 +34,7 @@ #include "rclcpp/logger.hpp" #include "rclcpp/macros.hpp" #include "rclcpp/time.hpp" -#include "realtime_tools/realtime_buffer.h" +#include "realtime_tools/realtime_buffer.hpp" namespace ros2_control_demo_example_14 { diff --git a/example_7/controller/include/ros2_control_demo_example_7/r6bot_controller.hpp b/example_7/controller/include/ros2_control_demo_example_7/r6bot_controller.hpp index b01cd9592..ee8c24f96 100644 --- a/example_7/controller/include/ros2_control_demo_example_7/r6bot_controller.hpp +++ b/example_7/controller/include/ros2_control_demo_example_7/r6bot_controller.hpp @@ -33,7 +33,7 @@ #include "rclcpp/timer.hpp" #include "rclcpp_lifecycle/lifecycle_publisher.hpp" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" -#include "realtime_tools/realtime_buffer.h" +#include "realtime_tools/realtime_buffer.hpp" #include "trajectory_msgs/msg/joint_trajectory.hpp" #include "trajectory_msgs/msg/joint_trajectory_point.hpp"