diff --git a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/CMakeLists.txt b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/CMakeLists.txt
index 9d713ecaf84d7..1bf8123c82a31 100644
--- a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/CMakeLists.txt
+++ b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/CMakeLists.txt
@@ -19,6 +19,13 @@ ament_auto_add_executable(accel_brake_map_calibrator
)
ament_target_dependencies(accel_brake_map_calibrator)
+# workaround to allow deprecated header to build on both galactic and rolling
+if(${tf2_geometry_msgs_VERSION} VERSION_LESS 0.18.0)
+ target_compile_definitions(accel_brake_map_calibrator PRIVATE
+ USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
+ )
+endif()
+
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
diff --git a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/include/accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/include/accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp
index 1874e77c868bc..55aaad9923aaf 100644
--- a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/include/accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp
+++ b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/include/accel_brake_map_calibrator/accel_brake_map_calibrator_node.hpp
@@ -22,6 +22,13 @@
#include "raw_vehicle_cmd_converter/brake_map.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2/utils.h"
+
+#ifdef USE_TF2_GEOMETRY_MSGS_DEPRECATED_HEADER
+#include "tf2_geometry_msgs/tf2_geometry_msgs.h"
+#else
+#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
+#endif
+
#include "tier4_autoware_utils/planning/planning_marker_helper.hpp"
#include "tier4_autoware_utils/ros/transform_listener.hpp"
diff --git a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/package.xml b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/package.xml
index d8971e55a3976..eeb846ad5fde3 100644
--- a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/package.xml
+++ b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/package.xml
@@ -16,6 +16,7 @@
rclcpp
std_msgs
std_srvs
+ tf2_geometry_msgs
tf2_ros
tier4_autoware_utils
tier4_debug_msgs
diff --git a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp
index 60873f674fbd4..2d7ddb588c424 100644
--- a/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp
+++ b/vehicle/accel_brake_map_calibrator/accel_brake_map_calibrator/src/accel_brake_map_calibrator_node.cpp
@@ -984,7 +984,7 @@ T AccelBrakeMapCalibrator::getNearestTimeDataFromVec(
double nearest_time = std::numeric_limits::max();
const double target_time = rclcpp::Time(base_data->header.stamp).seconds() - back_time;
T nearest_time_data;
- for (const auto data : vec) {
+ for (const auto & data : vec) {
const double data_time = rclcpp::Time(data->header.stamp).seconds();
const auto delta_time = std::abs(target_time - data_time);
if (nearest_time > delta_time) {
@@ -1001,7 +1001,7 @@ DataStampedPtr AccelBrakeMapCalibrator::getNearestTimeDataFromVec(
double nearest_time = std::numeric_limits::max();
const double target_time = base_data->data_time.seconds() - back_time;
DataStampedPtr nearest_time_data;
- for (const auto data : vec) {
+ for (const auto & data : vec) {
const double data_time = data->data_time.seconds();
const auto delta_time = std::abs(target_time - data_time);
if (nearest_time > delta_time) {