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 @@ -108,9 +108,7 @@ class HardwareComponentInterface : public rclcpp_lifecycle::node_interfaces::Lif
CallbackReturn init(const hardware_interface::HardwareComponentParams & params)
{
clock_ = params.clock;
auto logger_copy = params.logger;
logger_ = logger_copy.get_child(
"hardware_component." + params.hardware_info.type + "." + params.hardware_info.name);
logger_ = params.logger;
info_ = params.hardware_info;
if (params.hardware_info.is_async)
{
Expand All @@ -120,7 +118,7 @@ class HardwareComponentInterface : public rclcpp_lifecycle::node_interfaces::Lif
realtime_tools::AsyncSchedulingPolicy(info_.async_params.scheduling_policy);
async_thread_params.cpu_affinity_cores = info_.async_params.cpu_affinity_cores;
async_thread_params.clock = params.clock;
async_thread_params.logger = params.logger;
async_thread_params.logger = get_logger();
async_thread_params.exec_rate = params.hardware_info.rw_rate;
async_thread_params.print_warnings = info_.async_params.print_warnings;
RCLCPP_INFO(
Expand Down
4 changes: 3 additions & 1 deletion hardware_interface/src/resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -250,7 +250,9 @@ class ResourceStorage
hardware_interface::HardwareComponentParams component_params;
component_params.hardware_info = params.hardware_info;
component_params.clock = rm_clock_;
component_params.logger = rm_logger_;
component_params.logger = rm_logger_.get_child(
fmt::format(
"hardware_component.{}.{}", params.hardware_info.type, params.hardware_info.name));
component_params.executor = params.executor;
component_params.node_namespace = params.node_namespace;
RCLCPP_INFO(
Expand Down