diff --git a/diff_drive_controller/src/diff_drive_controller.cpp b/diff_drive_controller/src/diff_drive_controller.cpp index 291071a3aa..c63a171c8a 100644 --- a/diff_drive_controller/src/diff_drive_controller.cpp +++ b/diff_drive_controller/src/diff_drive_controller.cpp @@ -26,7 +26,7 @@ #include "hardware_interface/types/hardware_interface_type_values.hpp" #include "lifecycle_msgs/msg/state.hpp" #include "rclcpp/logging.hpp" -#include "tf2/LinearMath/Quaternion.h" +#include namespace { diff --git a/mecanum_drive_controller/src/mecanum_drive_controller.cpp b/mecanum_drive_controller/src/mecanum_drive_controller.cpp index 8336f0fbf3..e36e9bcc5f 100644 --- a/mecanum_drive_controller/src/mecanum_drive_controller.cpp +++ b/mecanum_drive_controller/src/mecanum_drive_controller.cpp @@ -22,7 +22,6 @@ #include "controller_interface/helpers.hpp" #include "hardware_interface/types/hardware_interface_type_values.hpp" #include "lifecycle_msgs/msg/state.hpp" -#include "tf2/transform_datatypes.h" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" namespace diff --git a/mecanum_drive_controller/src/odometry.cpp b/mecanum_drive_controller/src/odometry.cpp index bb873fcfdb..bac2566ea2 100644 --- a/mecanum_drive_controller/src/odometry.cpp +++ b/mecanum_drive_controller/src/odometry.cpp @@ -14,7 +14,6 @@ #include "mecanum_drive_controller/odometry.hpp" -#include "tf2/transform_datatypes.h" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" namespace mecanum_drive_controller diff --git a/tricycle_controller/CMakeLists.txt b/tricycle_controller/CMakeLists.txt index 7192afa5cc..5287a37f3c 100644 --- a/tricycle_controller/CMakeLists.txt +++ b/tricycle_controller/CMakeLists.txt @@ -20,7 +20,7 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS realtime_tools std_srvs tf2 - tf2_msgs + tf2_geometry_msgs ) find_package(ament_cmake REQUIRED) @@ -69,7 +69,7 @@ if(BUILD_TESTING) rclcpp_lifecycle realtime_tools tf2 - tf2_msgs + tf2_geometry_msgs ) add_definitions(-DTEST_FILES_DIRECTORY="${CMAKE_CURRENT_SOURCE_DIR}/test") diff --git a/tricycle_controller/package.xml b/tricycle_controller/package.xml index b57aae052a..08b7702517 100644 --- a/tricycle_controller/package.xml +++ b/tricycle_controller/package.xml @@ -37,7 +37,7 @@ realtime_tools std_srvs tf2 - tf2_msgs + tf2_geometry_msgs ament_cmake_gmock controller_manager diff --git a/tricycle_controller/src/tricycle_controller.cpp b/tricycle_controller/src/tricycle_controller.cpp index 02f5449b4c..40c724ef8d 100644 --- a/tricycle_controller/src/tricycle_controller.cpp +++ b/tricycle_controller/src/tricycle_controller.cpp @@ -27,8 +27,8 @@ #include "hardware_interface/types/hardware_interface_type_values.hpp" #include "lifecycle_msgs/msg/state.hpp" #include "rclcpp/logging.hpp" -#include "tf2/LinearMath/Quaternion.h" #include "tricycle_controller/tricycle_controller.hpp" +#include namespace {