From c0fa13742ea38efc2f1c88f04411b194bf5c3dec Mon Sep 17 00:00:00 2001 From: danielsanchezaran Date: Tue, 3 Sep 2024 18:01:37 +0900 Subject: [PATCH] feat(autonomous_emergency_braking): increase aeb speed by getting last transform (#8734) set stamp to 0 to get the latest stamp instead of waiting for the stamp Signed-off-by: Daniel Sanchez --- control/autoware_autonomous_emergency_braking/src/node.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/control/autoware_autonomous_emergency_braking/src/node.cpp b/control/autoware_autonomous_emergency_braking/src/node.cpp index 49bf307db0f23..26c6decceaff7 100644 --- a/control/autoware_autonomous_emergency_braking/src/node.cpp +++ b/control/autoware_autonomous_emergency_braking/src/node.cpp @@ -250,7 +250,7 @@ void AEB::onImu(const Imu::ConstSharedPtr input_msg) geometry_msgs::msg::TransformStamped transform_stamped{}; try { transform_stamped = tf_buffer_.lookupTransform( - "base_link", input_msg->header.frame_id, input_msg->header.stamp, + "base_link", input_msg->header.frame_id, rclcpp::Time(0), rclcpp::Duration::from_seconds(0.5)); } catch (tf2::TransformException & ex) { RCLCPP_ERROR_STREAM( @@ -631,7 +631,7 @@ std::optional AEB::generateEgoPath(const Trajectory & predicted_traj) geometry_msgs::msg::TransformStamped transform_stamped{}; try { transform_stamped = tf_buffer_.lookupTransform( - "base_link", predicted_traj.header.frame_id, predicted_traj.header.stamp, + "base_link", predicted_traj.header.frame_id, rclcpp::Time(0), rclcpp::Duration::from_seconds(0.5)); } catch (tf2::TransformException & ex) { RCLCPP_ERROR_STREAM( @@ -705,7 +705,7 @@ void AEB::createObjectDataUsingPredictedObjects( geometry_msgs::msg::TransformStamped transform_stamped{}; try { transform_stamped = tf_buffer_.lookupTransform( - "base_link", predicted_objects_ptr_->header.frame_id, stamp, + "base_link", predicted_objects_ptr_->header.frame_id, rclcpp::Time(0), rclcpp::Duration::from_seconds(0.5)); } catch (tf2::TransformException & ex) { RCLCPP_ERROR_STREAM(get_logger(), "[AEB] Failed to look up transform from base_link to map");