Skip to content
Open
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
19 changes: 19 additions & 0 deletions rclcpp/include/rclcpp/node_options.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,7 @@ class NodeOptions
* - clock_qos = rclcpp::ClockQoS()
* - use_clock_thread = true
* - enable_logger_service = false
* - log_level = rclcpp::Logger::Level::Unset
* - rosout_qos = rclcpp::RosoutQoS()
* - parameter_event_qos = rclcpp::ParameterEventQoS
* - with history setting and depth from rmw_qos_profile_parameter_events
Expand Down Expand Up @@ -260,6 +261,22 @@ class NodeOptions
NodeOptions &
enable_logger_service(bool enable_log_service);

/// Return the log_level option.
RCLCPP_PUBLIC
rclcpp::Logger::Level
log_level() const;

/// Set the log_level option, return this for logger idiom.
/**
* This allows to set the initial log level for this node, makes it different
* from global context.
*
* \param[in] log_level A rclcpp::Logger::Level value.
*/
RCLCPP_PUBLIC
NodeOptions &
log_level(rclcpp::Logger::Level log_level);

/// Return the start_parameter_event_publisher flag.
RCLCPP_PUBLIC
bool
Expand Down Expand Up @@ -451,6 +468,8 @@ class NodeOptions

bool enable_logger_service_ {false};

rclcpp::Logger::Level log_level_ {rclcpp::Logger::Level::Unset};

rclcpp::QoS parameter_event_qos_ = rclcpp::ParameterEventsQoS(
rclcpp::QoSInitialization::from_rmw(rmw_qos_profile_parameter_events)
);
Expand Down
3 changes: 3 additions & 0 deletions rclcpp/src/rclcpp/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -250,6 +250,9 @@ Node::Node(
options.parameter_event_qos(),
rclcpp::detail::PublisherQosParametersTraits{});

if (options.log_level() != rclcpp::Logger::Level::Unset) {
node_logging_->get_logger().set_level(options.log_level());
}
if (options.enable_logger_service()) {
node_logging_->create_logger_services(node_services_);
}
Expand Down
14 changes: 14 additions & 0 deletions rclcpp/src/rclcpp/node_options.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,6 +81,7 @@ NodeOptions::operator=(const NodeOptions & other)
this->clock_qos_ = other.clock_qos_;
this->use_clock_thread_ = other.use_clock_thread_;
this->enable_logger_service_ = other.enable_logger_service_;
this->log_level_ = other.log_level_;
this->parameter_event_qos_ = other.parameter_event_qos_;
this->rosout_qos_ = other.rosout_qos_;
this->parameter_event_publisher_options_ = other.parameter_event_publisher_options_;
Expand Down Expand Up @@ -262,6 +263,19 @@ NodeOptions::enable_logger_service(bool enable_logger_service)
return *this;
}

rclcpp::Logger::Level
NodeOptions::log_level() const
{
return this->log_level_;
}

NodeOptions &
NodeOptions::log_level(rclcpp::Logger::Level log_level)
{
this->log_level_ = log_level;
return *this;
}

bool
NodeOptions::start_parameter_event_publisher() const
{
Expand Down
14 changes: 14 additions & 0 deletions rclcpp_components/src/component_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -177,6 +177,20 @@ ComponentManager::create_node_options(const std::shared_ptr<LoadNode::Request> r
.parameter_overrides(parameters)
.arguments(remap_rules);

if (request->log_level != 0) {
if (request->log_level != static_cast<uint8_t>(rclcpp::Logger::Level::Debug) &&
request->log_level != static_cast<uint8_t>(rclcpp::Logger::Level::Info) &&
request->log_level != static_cast<uint8_t>(rclcpp::Logger::Level::Warn) &&
request->log_level != static_cast<uint8_t>(rclcpp::Logger::Level::Error) &&
request->log_level != static_cast<uint8_t>(rclcpp::Logger::Level::Fatal))
{
throw ComponentManagerException(
"Invalid log_level value: " + std::to_string(request->log_level) +
". Valid values are DEBUG (10), INFO (20), WARN (30), ERROR (40), FATAL (50).");
}
options.log_level(static_cast<rclcpp::Logger::Level>(request->log_level));
}

for (const auto & a : request->extra_arguments) {
const rclcpp::Parameter extra_argument = rclcpp::Parameter::from_parameter_msg(a);
if (extra_argument.get_name() == "forward_global_arguments") {
Expand Down