From 516c73733d905469223f4132e91a57835335d92d Mon Sep 17 00:00:00 2001 From: Bence Magyar Date: Mon, 5 May 2025 17:32:11 +0100 Subject: [PATCH] fix deprecated tf2 header (#361) (cherry picked from commit 6d8e31df048fdfe652e46a43557a4afbc0273b97) --- control_toolbox/src/control_filters/gravity_compensation.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/control_toolbox/src/control_filters/gravity_compensation.cpp b/control_toolbox/src/control_filters/gravity_compensation.cpp index df3eb1c7..21e70b57 100644 --- a/control_toolbox/src/control_filters/gravity_compensation.cpp +++ b/control_toolbox/src/control_filters/gravity_compensation.cpp @@ -16,7 +16,7 @@ #include "geometry_msgs/msg/vector3_stamped.hpp" #include "geometry_msgs/msg/wrench_stamped.hpp" -#include "tf2/LinearMath/Vector3.h" +#include "tf2/LinearMath/Vector3.hpp" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" namespace control_filters