@@ -424,8 +424,7 @@ std::optional<Obstacle> SurroundObstacleCheckerNode::getNearestObstacleByPointCl
424
424
return std::nullopt;
425
425
}
426
426
427
- const auto transform_stamped =
428
- getTransform (" base_link" , pointcloud_ptr_->header .frame_id , pointcloud_ptr_->header .stamp , 0.5 );
427
+ const auto transform_stamped = getTransform (" base_link" , pointcloud_ptr_->header .frame_id );
429
428
430
429
if (!transform_stamped) {
431
430
return std::nullopt;
@@ -468,8 +467,7 @@ std::optional<Obstacle> SurroundObstacleCheckerNode::getNearestObstacleByDynamic
468
467
{
469
468
if (!object_ptr_ || !use_dynamic_object_) return std::nullopt;
470
469
471
- const auto transform_stamped =
472
- getTransform (object_ptr_->header .frame_id , " base_link" , object_ptr_->header .stamp , 0.5 );
470
+ const auto transform_stamped = getTransform (object_ptr_->header .frame_id , " base_link" );
473
471
474
472
if (!transform_stamped) {
475
473
return std::nullopt;
@@ -522,14 +520,12 @@ std::optional<Obstacle> SurroundObstacleCheckerNode::getNearestObstacleByDynamic
522
520
}
523
521
524
522
std::optional<geometry_msgs::msg::TransformStamped> SurroundObstacleCheckerNode::getTransform (
525
- const std::string & source, const std::string & target, const rclcpp::Time & stamp,
526
- double duration_sec) const
523
+ const std::string & source, const std::string & target) const
527
524
{
528
525
geometry_msgs::msg::TransformStamped transform_stamped;
529
526
530
527
try {
531
- transform_stamped =
532
- tf_buffer_.lookupTransform (source, target, stamp, tf2::durationFromSec (duration_sec));
528
+ transform_stamped = tf_buffer_.lookupTransform (source, target, tf2::TimePointZero);
533
529
} catch (tf2::TransformException & ex) {
534
530
return {};
535
531
}
0 commit comments