From 932e87fde0614e9342e8889c7961f103e615e4e3 Mon Sep 17 00:00:00 2001 From: Yukinari Hisaki <42021302+yhisaki@users.noreply.github.com> Date: Mon, 16 Dec 2024 12:18:07 +0900 Subject: [PATCH] chore(autoware_costmap_generator): suppress Could not find a connection between 'map' and 'base_link' (#9655) Signed-off-by: Y.Hisaki --- .../autoware_costmap_generator/src/costmap_generator.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/planning/autoware_costmap_generator/src/costmap_generator.cpp b/planning/autoware_costmap_generator/src/costmap_generator.cpp index 052bb2728a3b1..081a6ead91cda 100644 --- a/planning/autoware_costmap_generator/src/costmap_generator.cpp +++ b/planning/autoware_costmap_generator/src/costmap_generator.cpp @@ -51,6 +51,7 @@ #include #include #include +#include #include #include @@ -68,14 +69,15 @@ namespace // Copied from scenario selector geometry_msgs::msg::PoseStamped::ConstSharedPtr getCurrentPose( - const tf2_ros::Buffer & tf_buffer, const rclcpp::Logger & logger) + const tf2_ros::Buffer & tf_buffer, const rclcpp::Logger & logger, + const rclcpp::Clock::SharedPtr clock) { geometry_msgs::msg::TransformStamped tf_current_pose; try { tf_current_pose = tf_buffer.lookupTransform("map", "base_link", tf2::TimePointZero); } catch (tf2::TransformException & ex) { - RCLCPP_ERROR(logger, "%s", ex.what()); + RCLCPP_ERROR_THROTTLE(logger, *clock, 5000, "%s", ex.what()); return nullptr; } @@ -253,7 +255,7 @@ void CostmapGenerator::update_data() void CostmapGenerator::set_current_pose() { - current_pose_ = getCurrentPose(tf_buffer_, this->get_logger()); + current_pose_ = getCurrentPose(tf_buffer_, this->get_logger(), this->get_clock()); } void CostmapGenerator::onTimer()