Skip to content

Commit

Permalink
Fix wrong warning message format (Closes ros-navigation#3415)
Browse files Browse the repository at this point in the history
  • Loading branch information
jlblancoc committed Feb 18, 2023
1 parent 6d12726 commit ee4c929
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions nav2_costmap_2d/plugins/voxel_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -275,12 +275,12 @@ void VoxelLayer::raytraceFreespace(
if (!worldToMap3DFloat(ox, oy, oz, sensor_x, sensor_y, sensor_z)) {
RCLCPP_WARN(
logger_,
"Sensor origin at (%.2f, %.2f %.2f) is out of map bounds"
"Sensor origin at (%.2f, %.2f %.2f) is out of map bounds "
"(%.2f, %.2f, %.2f) to (%.2f, %.2f, %.2f). "
"The costmap cannot raytrace for it.",
ox, oy, oz,
ox + getSizeInMetersX(), oy + getSizeInMetersY(), oz + getSizeInMetersZ(),
origin_x_, origin_y_, origin_z_);
origin_x_, origin_y_, origin_z_,
origin_x_ + getSizeInMetersX(), origin_y_ + getSizeInMetersY(), origin_z_ + getSizeInMetersZ());

return;
}
Expand Down

0 comments on commit ee4c929

Please sign in to comment.