Skip to content

Commit 106514e

Browse files
committed
chore: reduce timeout
Signed-off-by: badai-nguyen <dai.nguyen@tier4.jp>
1 parent 915a4fa commit 106514e

File tree

1 file changed

+4
-3
lines changed
  • perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter

1 file changed

+4
-3
lines changed

perception/autoware_compare_map_segmentation/src/voxel_based_compare_map_filter/node.cpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -103,14 +103,15 @@ void VoxelBasedCompareMapFilterComponent::input_indices_callback(
103103
// Lookup the transform from input frame to "map"
104104
geometry_msgs::msg::TransformStamped transform_stamped = tf_buffer_.lookupTransform(
105105
tf_input_frame_, tf_input_orig_frame_, rclcpp::Time(cloud->header.stamp),
106-
rclcpp::Duration::from_seconds(1.0));
106+
rclcpp::Duration::from_seconds(0.0));
107107

108108
// Transform the point cloud
109109
tf2::doTransform(*cloud, cloud_transformed, transform_stamped);
110-
cloud_transformed.header.frame_id = tf_input_frame_; // Update frame ID to "map"
111110
cloud_tf = std::make_shared<PointCloud2>(cloud_transformed);
112111
} catch (tf2::TransformException & ex) {
113-
RCLCPP_WARN(this->get_logger(), "Could not transform point cloud: %s", ex.what());
112+
RCLCPP_WARN_THROTTLE(
113+
this->get_logger(), *this->get_clock(), 5000, "Could not transform pointcloud: %s",
114+
ex.what());
114115
cloud_tf = cloud; // Fallback to original data
115116
}
116117
} else {

0 commit comments

Comments
 (0)