diff --git a/nav2_bt_navigator/src/navigators/navigate_through_poses.cpp b/nav2_bt_navigator/src/navigators/navigate_through_poses.cpp index ebd1cd4e77..237f6ba8ba 100644 --- a/nav2_bt_navigator/src/navigators/navigate_through_poses.cpp +++ b/nav2_bt_navigator/src/navigators/navigate_through_poses.cpp @@ -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); } diff --git a/nav2_costmap_2d/plugins/inflation_layer.cpp b/nav2_costmap_2d/plugins/inflation_layer.cpp index ac9245e8ad..796c2fd62f 100644 --- a/nav2_costmap_2d/plugins/inflation_layer.cpp +++ b/nav2_costmap_2d/plugins/inflation_layer.cpp @@ -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_); } diff --git a/nav2_planner/src/planner_server.cpp b/nav2_planner/src/planner_server.cpp index a81dd8d886..e9efb627a4 100644 --- a/nav2_planner/src/planner_server.cpp +++ b/nav2_planner/src/planner_server.cpp @@ -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); @@ -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(); diff --git a/nav2_waypoint_follower/src/waypoint_follower.cpp b/nav2_waypoint_follower/src/waypoint_follower.cpp index 6f8d9e1dab..804de9ad31 100644 --- a/nav2_waypoint_follower/src/waypoint_follower.cpp +++ b/nav2_waypoint_follower/src/waypoint_follower.cpp @@ -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);