Skip to content

Commit

Permalink
forward porting #3053
Browse files Browse the repository at this point in the history
  • Loading branch information
SteveMacenski committed Jul 7, 2022
1 parent 0e287c1 commit 3f2dbf0
Showing 1 changed file with 3 additions and 1 deletion.
4 changes: 3 additions & 1 deletion nav2_costmap_2d/plugins/range_sensor_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -293,7 +293,9 @@ void RangeSensorLayer::updateCostmap(
in.header.frame_id = range_message.header.frame_id;

if (!tf_->canTransform(
in.header.frame_id, global_frame_, tf2_ros::fromMsg(in.header.stamp)))
in.header.frame_id, global_frame_,
tf2_ros::fromMsg(in.header.stamp),
tf2_ros::fromRclcpp(transform_tolerance_)))
{
RCLCPP_INFO(
logger_, "Range sensor layer can't transform from %s to %s",
Expand Down

0 comments on commit 3f2dbf0

Please sign in to comment.