diff --git a/action_tutorials/action_tutorials_cpp/src/fibonacci_action_client.cpp b/action_tutorials/action_tutorials_cpp/src/fibonacci_action_client.cpp index 8ddcfc100..eec7d31f6 100644 --- a/action_tutorials/action_tutorials_cpp/src/fibonacci_action_client.cpp +++ b/action_tutorials/action_tutorials_cpp/src/fibonacci_action_client.cpp @@ -100,7 +100,7 @@ class FibonacciActionClient : public rclcpp::Node for (auto number : feedback->partial_sequence) { ss << number << " "; } - RCLCPP_INFO(this->get_logger(), ss.str().c_str()); + RCLCPP_INFO(this->get_logger(), "%s", ss.str().c_str()); } ACTION_TUTORIALS_CPP_LOCAL @@ -124,7 +124,7 @@ class FibonacciActionClient : public rclcpp::Node for (auto number : result.result->sequence) { ss << number << " "; } - RCLCPP_INFO(this->get_logger(), ss.str().c_str()); + RCLCPP_INFO(this->get_logger(), "%s", ss.str().c_str()); rclcpp::shutdown(); } }; // class FibonacciActionClient diff --git a/demo_nodes_cpp/src/parameters/even_parameters_node.cpp b/demo_nodes_cpp/src/parameters/even_parameters_node.cpp index 37cd4adbf..d294b4d49 100644 --- a/demo_nodes_cpp/src/parameters/even_parameters_node.cpp +++ b/demo_nodes_cpp/src/parameters/even_parameters_node.cpp @@ -49,11 +49,10 @@ class EvenParameterNode : public rclcpp::Node result.successful &= true; } else if (rclcpp::ParameterType::PARAMETER_INTEGER == parameter_type) { if (parameter.as_int() % 2 != 0) { - RCLCPP_INFO( - this->get_logger(), "Requested value '%d' for parameter '%s' " - "is not an even number: rejecting change...", - parameter.as_int(), - parameter.get_name().c_str() + RCLCPP_INFO_STREAM( + this->get_logger(), + "Requested value '" << parameter.as_int() << "' for parameter '" << + parameter.get_name() << "' is not an even number: rejecting change..." ); result.successful = false; } else { diff --git a/demo_nodes_cpp/src/parameters/list_parameters.cpp b/demo_nodes_cpp/src/parameters/list_parameters.cpp index 2b89fe429..0d01d6853 100644 --- a/demo_nodes_cpp/src/parameters/list_parameters.cpp +++ b/demo_nodes_cpp/src/parameters/list_parameters.cpp @@ -75,7 +75,7 @@ class ListParameters : public rclcpp::Node for (auto & prefix : parameters_and_prefixes.prefixes) { ss << "\n " << prefix; } - RCLCPP_INFO(this->get_logger(), ss.str().c_str()); + RCLCPP_INFO(this->get_logger(), "%s", ss.str().c_str()); rclcpp::shutdown(); } }; diff --git a/demo_nodes_cpp/src/parameters/list_parameters_async.cpp b/demo_nodes_cpp/src/parameters/list_parameters_async.cpp index a2f3180f1..57d976376 100644 --- a/demo_nodes_cpp/src/parameters/list_parameters_async.cpp +++ b/demo_nodes_cpp/src/parameters/list_parameters_async.cpp @@ -82,7 +82,7 @@ int main(int argc, char ** argv) for (auto & prefix : parameter_list.prefixes) { ss << "\n " << prefix; } - RCLCPP_INFO(node->get_logger(), ss.str().c_str()); + RCLCPP_INFO(node->get_logger(), "%s", ss.str().c_str()); rclcpp::shutdown(); diff --git a/demo_nodes_cpp/src/parameters/parameter_events.cpp b/demo_nodes_cpp/src/parameters/parameter_events.cpp index 3b7c916e6..b4382ad6b 100644 --- a/demo_nodes_cpp/src/parameters/parameter_events.cpp +++ b/demo_nodes_cpp/src/parameters/parameter_events.cpp @@ -40,7 +40,7 @@ void on_parameter_event( ss << "\n " << deleted_parameter.name; } ss << "\n"; - RCLCPP_INFO(logger, ss.str().c_str()); + RCLCPP_INFO(logger, "%s", ss.str().c_str()); } int main(int argc, char ** argv) diff --git a/demo_nodes_cpp/src/parameters/parameter_events_async.cpp b/demo_nodes_cpp/src/parameters/parameter_events_async.cpp index a1f1dfaeb..30cff7fb9 100644 --- a/demo_nodes_cpp/src/parameters/parameter_events_async.cpp +++ b/demo_nodes_cpp/src/parameters/parameter_events_async.cpp @@ -57,7 +57,7 @@ class ParameterEventsAsyncNode : public rclcpp::Node ss << "\n " << deleted_parameter.name; } ss << "\n"; - RCLCPP_INFO(this->get_logger(), ss.str().c_str()); + RCLCPP_INFO(this->get_logger(), "%s", ss.str().c_str()); }; // Setup callback for changes to parameters. diff --git a/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp b/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp index 48a81beaa..e3799c6d7 100644 --- a/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp +++ b/demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp @@ -78,7 +78,7 @@ class SetAndGetParameters : public rclcpp::Node ss << "\nParameter value (" << parameter.get_type_name() << "): " << parameter.value_to_string(); } - RCLCPP_INFO(this->get_logger(), ss.str().c_str()); + RCLCPP_INFO(this->get_logger(), "%s", ss.str().c_str()); rclcpp::shutdown(); } diff --git a/demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp b/demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp index 0afa1155d..e0c7c44d7 100644 --- a/demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp +++ b/demo_nodes_cpp/src/parameters/set_and_get_parameters_async.cpp @@ -85,7 +85,7 @@ int main(int argc, char ** argv) ss << "\nParameter value (" << parameter.get_type_name() << "): " << parameter.value_to_string(); } - RCLCPP_INFO(node->get_logger(), ss.str().c_str()); + RCLCPP_INFO(node->get_logger(), "%s", ss.str().c_str()); rclcpp::shutdown(); diff --git a/demo_nodes_cpp/src/services/add_two_ints_client.cpp b/demo_nodes_cpp/src/services/add_two_ints_client.cpp index efa126592..8442801b5 100644 --- a/demo_nodes_cpp/src/services/add_two_ints_client.cpp +++ b/demo_nodes_cpp/src/services/add_two_ints_client.cpp @@ -65,7 +65,7 @@ int main(int argc, char ** argv) // TODO(wjwwood): consider error condition auto result = send_request(node, client, request); if (result) { - RCLCPP_INFO(node->get_logger(), "Result of add_two_ints: %zd", result->sum); + RCLCPP_INFO_STREAM(node->get_logger(), "Result of add_two_ints: " << result->sum); } else { RCLCPP_ERROR(node->get_logger(), "Interrupted while waiting for response. Exiting."); } diff --git a/logging_demo/src/logger_config_component.cpp b/logging_demo/src/logger_config_component.cpp index 17d49c5b4..b0c91ee1e 100644 --- a/logging_demo/src/logger_config_component.cpp +++ b/logging_demo/src/logger_config_component.cpp @@ -58,7 +58,7 @@ LoggerConfig::handle_logger_config_request( if (RCUTILS_RET_OK != ret) { RCLCPP_ERROR( this->get_logger(), "Error %d getting severity level from request: %s", ret, - rcl_get_error_string()); + rcl_get_error_string().str); rcl_reset_error(); response->success = false; return; diff --git a/topic_statistics_demo/src/imu_talker_listener_nodes.cpp b/topic_statistics_demo/src/imu_talker_listener_nodes.cpp index 5520b4f58..570c7e80d 100644 --- a/topic_statistics_demo/src/imu_talker_listener_nodes.cpp +++ b/topic_statistics_demo/src/imu_talker_listener_nodes.cpp @@ -57,7 +57,7 @@ void ImuTalker::publish() msg.header.stamp = this->now(); } - RCLCPP_DEBUG(get_logger(), "Publishing header: %lu", msg.header.stamp.nanosec); + RCLCPP_DEBUG(get_logger(), "Publishing header: %u", msg.header.stamp.nanosec); publisher_->publish(msg); } @@ -83,7 +83,7 @@ void ImuListener::start_listening() 10, /* QoS history_depth */ [this](const typename sensor_msgs::msg::Imu::SharedPtr msg) -> void { - RCLCPP_DEBUG(get_logger(), "Listener heard: %lu", msg->header.stamp.nanosec); + RCLCPP_DEBUG(get_logger(), "Listener heard: %u", msg->header.stamp.nanosec); }, subscription_options_); }