Skip to content

Commit

Permalink
Fix size_t format specifier (ros-navigation#3003)
Browse files Browse the repository at this point in the history
  • Loading branch information
m2-farzan authored and redvinaa committed Jun 30, 2022
1 parent f2bdf66 commit b490324
Show file tree
Hide file tree
Showing 4 changed files with 5 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -203,7 +203,7 @@ NavigateThroughPosesNavigator::initializeGoalPoses(ActionT::Goal::ConstSharedPtr
{
if (goal->poses.size() > 0) {
RCLCPP_INFO(
logger_, "Begin navigating from current location through %li poses to (%.2f, %.2f)",
logger_, "Begin navigating from current location through %zu poses to (%.2f, %.2f)",
goal->poses.size(), goal->poses.back().pose.position.x, goal->poses.back().pose.position.y);
}

Expand Down
2 changes: 1 addition & 1 deletion nav2_costmap_2d/plugins/inflation_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -171,7 +171,7 @@ InflationLayer::onFootprintChanged()
need_reinflation_ = true;

RCLCPP_DEBUG(
logger_, "InflationLayer::onFootprintChanged(): num footprint points: %lu,"
logger_, "InflationLayer::onFootprintChanged(): num footprint points: %zu,"
" inscribed_radius_ = %.3f, inflation_radius_ = %.3f",
layered_costmap_->getFootprint().size(), inscribed_radius_, inflation_radius_);
}
Expand Down
4 changes: 2 additions & 2 deletions nav2_planner/src/planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -332,7 +332,7 @@ bool PlannerServer::validatePath(

RCLCPP_DEBUG(
get_logger(),
"Found valid path of size %lu to (%.2f, %.2f)",
"Found valid path of size %zu to (%.2f, %.2f)",
path.poses.size(), goal.pose.position.x,
goal.pose.position.y);

Expand Down Expand Up @@ -422,7 +422,7 @@ PlannerServer::computePlanThroughPoses()
} catch (std::exception & ex) {
RCLCPP_WARN(
get_logger(),
"%s plugin failed to plan through %li points with final goal (%.2f, %.2f): \"%s\"",
"%s plugin failed to plan through %zu points with final goal (%.2f, %.2f): \"%s\"",
goal->planner_id.c_str(), goal->goals.size(), goal->goals.back().pose.position.x,
goal->goals.back().pose.position.y, ex.what());
action_server_poses_->terminate_current();
Expand Down
2 changes: 1 addition & 1 deletion nav2_waypoint_follower/src/waypoint_follower.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -263,7 +263,7 @@ WaypointFollower::followWaypoints()
new_goal = true;
if (goal_index >= goal->poses.size()) {
RCLCPP_INFO(
get_logger(), "Completed all %lu waypoints requested.",
get_logger(), "Completed all %zu waypoints requested.",
goal->poses.size());
result->missed_waypoints = failed_ids_;
action_server_->succeeded_current(result);
Expand Down

0 comments on commit b490324

Please sign in to comment.