Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(accel_brake_map_calibrator): fix usage of transform listener #2682

Merged
merged 2 commits into from
Jan 18, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,9 @@
<version>0.1.0</version>
<description>The accel_brake_map_calibrator</description>
<maintainer email="tomoya.kimura@tier4.jp">Tomoya Kimura</maintainer>
<maintainer email="taiki.tanaka@tier4.jp">Taiki Tanaka</maintainer>
<maintainer email="takeshi.miura@tier4.jp">Takeshi Miura</maintainer>

<license>Apache License 2.0</license>

<buildtool_depend>ament_cmake_auto</buildtool_depend>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down