Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add duration parameter to the cantransform call in updateCostmap in r… #3053

Closed
wants to merge 1 commit into from
Closed
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 4 additions & 1 deletion nav2_costmap_2d/plugins/range_sensor_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -292,8 +292,11 @@ void RangeSensorLayer::updateCostmap(
in.header.stamp = range_message.header.stamp;
in.header.frame_id = range_message.header.frame_id;

std::string * errstr = NULL;
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Might want to include that error string in the RCLCPP INFO when it fails to give more context, if you're going to collect it!

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_), errstr))
{
RCLCPP_INFO(
logger_, "Range sensor layer can't transform from %s to %s",
Expand Down