Skip to content

Commit

Permalink
forward porting #3053 (#3064) (#3070)
Browse files Browse the repository at this point in the history
* forward porting #3053

* adding TF warning suggestion

(cherry picked from commit bb0d177)

Co-authored-by: Steve Macenski <[email protected]>
  • Loading branch information
mergify[bot] and SteveMacenski authored Jul 11, 2022
1 parent c25ab7a commit 6a9508b
Show file tree
Hide file tree
Showing 2 changed files with 4 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
1 change: 1 addition & 0 deletions nav2_costmap_2d/test/integration/range_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,7 @@ class TestNode : public ::testing::Test
: node_(std::make_shared<TestLifecycleNode>("range_test_node")),
tf_(node_->get_clock())
{
tf_.setUsingDedicatedThread(true);
// Standard non-plugin specific parameters
node_->declare_parameter("map_topic", rclcpp::ParameterValue(std::string("map")));
node_->declare_parameter("track_unknown_space", rclcpp::ParameterValue(false));
Expand Down

0 comments on commit 6a9508b

Please sign in to comment.