Skip to content
Snippets Groups Projects
Unverified Commit 2efdad8e authored by Kevin DeMarco's avatar Kevin DeMarco Committed by GitHub
Browse files

Fix format strings in calls to RCLCPP macros (#2139)

parent e7432f17
Branches
No related tags found
No related merge requests found
...@@ -85,7 +85,7 @@ void IsStuckCondition::logStuck(const std::string & msg) const ...@@ -85,7 +85,7 @@ void IsStuckCondition::logStuck(const std::string & msg) const
return; return;
} }
RCLCPP_INFO(node_->get_logger(), msg); RCLCPP_INFO(node_->get_logger(), msg.c_str());
prev_msg = msg; prev_msg = msg;
} }
......
...@@ -43,7 +43,7 @@ SpeedController::SpeedController( ...@@ -43,7 +43,7 @@ SpeedController::SpeedController(
if (min_rate_ <= 0.0 || max_rate_ <= 0.0) { if (min_rate_ <= 0.0 || max_rate_ <= 0.0) {
std::string err_msg = "SpeedController node cannot have 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); throw BT::BehaviorTreeException(err_msg);
} }
......
...@@ -281,16 +281,16 @@ void SpeedFilter::process( ...@@ -281,16 +281,16 @@ void SpeedFilter::process(
if (speed_limit_ < 0.0) { if (speed_limit_ < 0.0) {
RCLCPP_WARN( RCLCPP_WARN(
logger_, logger_,
"SpeedFilter: Speed limit in filter_mask[%i, %i] is less than 0%, " "SpeedFilter: Speed limit in filter_mask[%i, %i] is less than 0%%, "
"which can not be true. Setting it to 0% value.", "which can not be true. Setting it to 0%% value.",
mask_robot_i, mask_robot_j); mask_robot_i, mask_robot_j);
speed_limit_ = NO_SPEED_LIMIT; speed_limit_ = NO_SPEED_LIMIT;
} }
if (speed_limit_ > 100.0) { if (speed_limit_ > 100.0) {
RCLCPP_WARN( RCLCPP_WARN(
logger_, logger_,
"SpeedFilter: Speed limit in filter_mask[%i, %i] is higher than 100%, " "SpeedFilter: Speed limit in filter_mask[%i, %i] is higher than 100%%, "
"which can not be true. Setting it to 100% value.", "which can not be true. Setting it to 100%% value.",
mask_robot_i, mask_robot_j); mask_robot_i, mask_robot_j);
speed_limit_ = 100.0; speed_limit_ = 100.0;
} }
......
...@@ -68,7 +68,7 @@ void ClearCostmapService::clearExceptRegionCallback( ...@@ -68,7 +68,7 @@ void ClearCostmapService::clearExceptRegionCallback(
{ {
RCLCPP_INFO( RCLCPP_INFO(
logger_, 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); clearRegion(request->reset_distance, true);
} }
...@@ -88,7 +88,7 @@ void ClearCostmapService::clearEntireCallback( ...@@ -88,7 +88,7 @@ void ClearCostmapService::clearEntireCallback(
{ {
RCLCPP_INFO( RCLCPP_INFO(
logger_, logger_,
"Received request to clear entirely the " + costmap_.getName()); ("Received request to clear entirely the " + costmap_.getName()).c_str());
clearEntirely(); clearEntirely();
} }
......
...@@ -35,7 +35,7 @@ public: ...@@ -35,7 +35,7 @@ public:
nav_msgs::msg::OccupancyGrid msg; nav_msgs::msg::OccupancyGrid msg;
LOAD_MAP_STATUS status = loadMapFromYaml(pub_map_file, msg); LOAD_MAP_STATUS status = loadMapFromYaml(pub_map_file, msg);
if (status != LOAD_MAP_SUCCESS) { 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; return;
} }
......
...@@ -255,7 +255,7 @@ PlannerServer::computePlan() ...@@ -255,7 +255,7 @@ PlannerServer::computePlan()
RCLCPP_DEBUG( RCLCPP_DEBUG(
get_logger(), 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, result->path.poses.size(), goal->pose.pose.position.x,
goal->pose.pose.position.y); goal->pose.pose.position.y);
......
...@@ -344,7 +344,7 @@ bool PlannerTester::defaultPlannerRandomTests( ...@@ -344,7 +344,7 @@ bool PlannerTester::defaultPlannerRandomTests(
RCLCPP_INFO( RCLCPP_INFO(
this->get_logger(), 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()); number_tests, num_fail, elapsed.count());
if ((num_fail / number_tests) > acceptable_fail_ratio) { if ((num_fail / number_tests) > acceptable_fail_ratio) {
...@@ -368,7 +368,7 @@ bool PlannerTester::plannerTest( ...@@ -368,7 +368,7 @@ bool PlannerTester::plannerTest(
// Then request to compute a path // Then request to compute a path
TaskStatus status = createPlan(goal, 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) { if (status == TaskStatus::FAILED) {
return false; return false;
......
...@@ -39,7 +39,7 @@ Costmap::Costmap( ...@@ -39,7 +39,7 @@ Costmap::Costmap(
{ {
if (lethal_threshold_ < 0. || lethal_threshold_ > 100.) { if (lethal_threshold_ < 0. || lethal_threshold_ > 100.) {
RCLCPP_WARN( 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_); " bounds 0-100. This could result in potential collisions!", lethal_threshold_);
// lethal_threshold_ = std::max(std::min(lethal_threshold_, 100), 0); // lethal_threshold_ = std::max(std::min(lethal_threshold_, 100), 0);
} }
......
...@@ -253,7 +253,7 @@ WaypointFollower::followWaypoints() ...@@ -253,7 +253,7 @@ WaypointFollower::followWaypoints()
new_goal = true; new_goal = true;
if (goal_index >= goal->poses.size()) { if (goal_index >= goal->poses.size()) {
RCLCPP_INFO( RCLCPP_INFO(
get_logger(), "Completed all %i waypoints requested.", get_logger(), "Completed all %lu waypoints requested.",
goal->poses.size()); goal->poses.size());
result->missed_waypoints = failed_ids_; result->missed_waypoints = failed_ids_;
action_server_->succeeded_current(result); action_server_->succeeded_current(result);
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment