Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
Expand Down
9 changes: 4 additions & 5 deletions demo_nodes_cpp/src/parameters/even_parameters_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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 {
Expand Down
2 changes: 1 addition & 1 deletion demo_nodes_cpp/src/parameters/list_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
};
Expand Down
2 changes: 1 addition & 1 deletion demo_nodes_cpp/src/parameters/list_parameters_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();

Expand Down
2 changes: 1 addition & 1 deletion demo_nodes_cpp/src/parameters/parameter_events.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)
Expand Down
2 changes: 1 addition & 1 deletion demo_nodes_cpp/src/parameters/parameter_events_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand Down
2 changes: 1 addition & 1 deletion demo_nodes_cpp/src/parameters/set_and_get_parameters.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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();

Expand Down
2 changes: 1 addition & 1 deletion demo_nodes_cpp/src/services/add_two_ints_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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.");
}
Expand Down
2 changes: 1 addition & 1 deletion logging_demo/src/logger_config_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
4 changes: 2 additions & 2 deletions topic_statistics_demo/src/imu_talker_listener_nodes.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}

Expand All @@ -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_);
}
Expand Down