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 705d6ee5e5fc3..8163a1209883c 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
@@ -5,6 +5,9 @@
0.1.0
The accel_brake_map_calibrator
Tomoya Kimura
+ Taiki Tanaka
+ Takeshi Miura
+
Apache License 2.0
ament_cmake_auto
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 8c4550332a316..b664352f70fab 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
@@ -232,15 +232,13 @@ bool AccelBrakeMapCalibrator::getCurrentPitchFromTF(double * pitch)
}
// get tf
- geometry_msgs::msg::TransformStamped::ConstSharedPtr transform;
- try {
- transform = transform_listener_->getTransform(
- "map", "base_link", rclcpp::Time(0), rclcpp::Duration::from_seconds(0.5));
- } catch (tf2::TransformException & ex) {
+ const auto transform = transform_listener_->getTransform(
+ "map", "base_link", rclcpp::Time(0), rclcpp::Duration::from_seconds(0.5));
+ if (!transform) {
auto & clk = *this->get_clock();
RCLCPP_WARN_STREAM_THROTTLE(
rclcpp::get_logger("accel_brake_map_calibrator"), clk, 5000,
- "cannot get map to base_link transform. " << ex.what());
+ "cannot get map to base_link transform. ");
return false;
}
double roll, raw_pitch, yaw;