Skip to content

Commit

Permalink
Fix format strings in calls to RCLCPP macros (ros-navigation#2139)
Browse files Browse the repository at this point in the history
  • Loading branch information
SyllogismRXS authored and ruffsl committed Jul 2, 2021
1 parent 900a6e8 commit 28cb51d
Show file tree
Hide file tree
Showing 9 changed files with 14 additions and 14 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -85,7 +85,7 @@ void IsStuckCondition::logStuck(const std::string & msg) const
return;
}

RCLCPP_INFO(node_->get_logger(), msg);
RCLCPP_INFO(node_->get_logger(), msg.c_str());
prev_msg = msg;
}

Expand Down
2 changes: 1 addition & 1 deletion nav2_behavior_tree/plugins/decorator/speed_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,7 +43,7 @@ SpeedController::SpeedController(

if (min_rate_ <= 0.0 || max_rate_ <= 0.0) {
std::string err_msg = "SpeedController node cannot have rate <= 0.0";
RCLCPP_FATAL(node_->get_logger(), err_msg);
RCLCPP_FATAL(node_->get_logger(), err_msg.c_str());
throw BT::BehaviorTreeException(err_msg);
}

Expand Down
8 changes: 4 additions & 4 deletions nav2_costmap_2d/plugins/costmap_filters/speed_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -281,16 +281,16 @@ void SpeedFilter::process(
if (speed_limit_ < 0.0) {
RCLCPP_WARN(
logger_,
"SpeedFilter: Speed limit in filter_mask[%i, %i] is less than 0%, "
"which can not be true. Setting it to 0% value.",
"SpeedFilter: Speed limit in filter_mask[%i, %i] is less than 0%%, "
"which can not be true. Setting it to 0%% value.",
mask_robot_i, mask_robot_j);
speed_limit_ = NO_SPEED_LIMIT;
}
if (speed_limit_ > 100.0) {
RCLCPP_WARN(
logger_,
"SpeedFilter: Speed limit in filter_mask[%i, %i] is higher than 100%, "
"which can not be true. Setting it to 100% value.",
"SpeedFilter: Speed limit in filter_mask[%i, %i] is higher than 100%%, "
"which can not be true. Setting it to 100%% value.",
mask_robot_i, mask_robot_j);
speed_limit_ = 100.0;
}
Expand Down
4 changes: 2 additions & 2 deletions nav2_costmap_2d/src/clear_costmap_service.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ void ClearCostmapService::clearExceptRegionCallback(
{
RCLCPP_INFO(
logger_,
"Received request to clear except a region the " + costmap_.getName());
("Received request to clear except a region the " + costmap_.getName()).c_str());

clearRegion(request->reset_distance, true);
}
Expand All @@ -88,7 +88,7 @@ void ClearCostmapService::clearEntireCallback(
{
RCLCPP_INFO(
logger_,
"Received request to clear entirely the " + costmap_.getName());
("Received request to clear entirely the " + costmap_.getName()).c_str());

clearEntirely();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ class TestPublisher : public rclcpp::Node
nav_msgs::msg::OccupancyGrid msg;
LOAD_MAP_STATUS status = loadMapFromYaml(pub_map_file, msg);
if (status != LOAD_MAP_SUCCESS) {
RCLCPP_ERROR(get_logger(), "Can not load %s map file", pub_map_file);
RCLCPP_ERROR(get_logger(), "Can not load %s map file", pub_map_file.c_str());
return;
}

Expand Down
2 changes: 1 addition & 1 deletion nav2_planner/src/planner_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -255,7 +255,7 @@ PlannerServer::computePlan()

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

Expand Down
4 changes: 2 additions & 2 deletions nav2_system_tests/src/planning/planner_tester.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -344,7 +344,7 @@ bool PlannerTester::defaultPlannerRandomTests(

RCLCPP_INFO(
this->get_logger(),
"Tested with %u tests. Planner failed on %u. Test time %u ms",
"Tested with %u tests. Planner failed on %u. Test time %ld ms",
number_tests, num_fail, elapsed.count());

if ((num_fail / number_tests) > acceptable_fail_ratio) {
Expand All @@ -368,7 +368,7 @@ bool PlannerTester::plannerTest(
// Then request to compute a path
TaskStatus status = createPlan(goal, path);

RCLCPP_DEBUG(this->get_logger(), "Path request status: %d", status);
RCLCPP_DEBUG(this->get_logger(), "Path request status: %d", static_cast<int8_t>(status));

if (status == TaskStatus::FAILED) {
return false;
Expand Down
2 changes: 1 addition & 1 deletion nav2_util/src/costmap.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ Costmap::Costmap(
{
if (lethal_threshold_ < 0. || lethal_threshold_ > 100.) {
RCLCPP_WARN(
node_->get_logger(), "Costmap: Lethal threshold set to %.2f, it should be within"
node_->get_logger(), "Costmap: Lethal threshold set to %d, it should be within"
" bounds 0-100. This could result in potential collisions!", lethal_threshold_);
// lethal_threshold_ = std::max(std::min(lethal_threshold_, 100), 0);
}
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 @@ -253,7 +253,7 @@ WaypointFollower::followWaypoints()
new_goal = true;
if (goal_index >= goal->poses.size()) {
RCLCPP_INFO(
get_logger(), "Completed all %i waypoints requested.",
get_logger(), "Completed all %lu waypoints requested.",
goal->poses.size());
result->missed_waypoints = failed_ids_;
action_server_->succeeded_current(result);
Expand Down

0 comments on commit 28cb51d

Please sign in to comment.