Skip to content

Commit

Permalink
remove NodeLoggingInterface and parse Logger directly
Browse files Browse the repository at this point in the history
  • Loading branch information
saikishor committed Jun 25, 2024
1 parent 67fd09c commit 812243c
Show file tree
Hide file tree
Showing 11 changed files with 55 additions and 85 deletions.
5 changes: 2 additions & 3 deletions hardware_interface/include/hardware_interface/actuator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -47,9 +47,8 @@ class Actuator final

HARDWARE_INTERFACE_PUBLIC
const rclcpp_lifecycle::State & initialize(
const HardwareInfo & actuator_info,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface,
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_interface);
const HardwareInfo & actuator_info, rclcpp::Logger logger,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface);

HARDWARE_INTERFACE_PUBLIC
const rclcpp_lifecycle::State & configure();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,8 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
public:
ActuatorInterface()
: lifecycle_state_(rclcpp_lifecycle::State(
lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN))
lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN)),
actuator_logger_(rclcpp::get_logger("actuator_interface"))
{
}

Expand All @@ -100,12 +101,11 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
* \returns CallbackReturn::ERROR if any error happens or data are missing.
*/
CallbackReturn init(
const HardwareInfo & hardware_info,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface,
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_interface)
const HardwareInfo & hardware_info, rclcpp::Logger logger,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
{
clock_interface_ = clock_interface;
logger_interface_ = logger_interface;
actuator_logger_ = logger.get_child("hardware_component.actuator." + hardware_info.name);
info_ = hardware_info;
return on_init(hardware_info);
};
Expand Down Expand Up @@ -234,18 +234,7 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
/**
* \return logger of the ActuatorInterface.
*/
rclcpp::Logger get_logger() const
{
if (logger_interface_)
{
return logger_interface_->get_logger().get_child(
"resource_manager.hardware_component.actuator." + info_.name);
}
else
{
return rclcpp::get_logger("resource_manager.hardware_component.actuator." + info_.name);
}
}
rclcpp::Logger get_logger() const { return actuator_logger_; }

/// Get the clock of the ActuatorInterface.
/**
Expand All @@ -268,7 +257,7 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod

private:
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface_;
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_interface_;
rclcpp::Logger actuator_logger_;
};

} // namespace hardware_interface
Expand Down
5 changes: 2 additions & 3 deletions hardware_interface/include/hardware_interface/sensor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,9 +48,8 @@ class Sensor final

HARDWARE_INTERFACE_PUBLIC
const rclcpp_lifecycle::State & initialize(
const HardwareInfo & sensor_info,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface,
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_interface);
const HardwareInfo & sensor_info, rclcpp::Logger logger,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface);

HARDWARE_INTERFACE_PUBLIC
const rclcpp_lifecycle::State & configure();
Expand Down
25 changes: 7 additions & 18 deletions hardware_interface/include/hardware_interface/sensor_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,8 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
public:
SensorInterface()
: lifecycle_state_(rclcpp_lifecycle::State(
lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN))
lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN)),
sensor_logger_(rclcpp::get_logger("sensor_interface"))
{
}

Expand All @@ -100,12 +101,11 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
* \returns CallbackReturn::ERROR if any error happens or data are missing.
*/
CallbackReturn init(
const HardwareInfo & hardware_info,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface,
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_interface)
const HardwareInfo & hardware_info, rclcpp::Logger logger,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
{
clock_interface_ = clock_interface;
logger_interface_ = logger_interface;
sensor_logger_ = logger.get_child("hardware_component.sensor." + hardware_info.name);
info_ = hardware_info;
return on_init(hardware_info);
};
Expand Down Expand Up @@ -173,18 +173,7 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
/**
* \return logger of the SensorInterface.
*/
rclcpp::Logger get_logger() const
{
if (logger_interface_)
{
return logger_interface_->get_logger().get_child(
"resource_manager.hardware_component.sensor." + info_.name);
}
else
{
return rclcpp::get_logger("resource_manager.hardware_component.sensor." + info_.name);
}
}
rclcpp::Logger get_logger() const { return sensor_logger_; }

/// Get the clock of the SensorInterface.
/**
Expand All @@ -207,7 +196,7 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI

private:
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface_;
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_interface_;
rclcpp::Logger sensor_logger_;
};

} // namespace hardware_interface
Expand Down
5 changes: 2 additions & 3 deletions hardware_interface/include/hardware_interface/system.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,9 +48,8 @@ class System final

HARDWARE_INTERFACE_PUBLIC
const rclcpp_lifecycle::State & initialize(
const HardwareInfo & system_info,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface,
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_interface);
const HardwareInfo & system_info, rclcpp::Logger logger,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface);

HARDWARE_INTERFACE_PUBLIC
const rclcpp_lifecycle::State & configure();
Expand Down
25 changes: 7 additions & 18 deletions hardware_interface/include/hardware_interface/system_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,8 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
public:
SystemInterface()
: lifecycle_state_(rclcpp_lifecycle::State(
lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN))
lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN)),
system_logger_(rclcpp::get_logger("system_interface"))
{
}

Expand All @@ -101,12 +102,11 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
* \returns CallbackReturn::ERROR if any error happens or data are missing.
*/
CallbackReturn init(
const HardwareInfo & hardware_info,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface,
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_interface)
const HardwareInfo & hardware_info, rclcpp::Logger logger,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
{
clock_interface_ = clock_interface;
logger_interface_ = logger_interface;
system_logger_ = logger.get_child("hardware_component.system." + hardware_info.name);
info_ = hardware_info;
return on_init(hardware_info);
};
Expand Down Expand Up @@ -235,18 +235,7 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
/**
* \return logger of the SystemInterface.
*/
rclcpp::Logger get_logger() const
{
if (logger_interface_)
{
return logger_interface_->get_logger().get_child(
"resource_manager.hardware_component.system." + info_.name);
}
else
{
return rclcpp::get_logger("resource_manager.hardware_component.system." + info_.name);
}
}
rclcpp::Logger get_logger() const { return system_logger_; }

/// Get the clock of the SystemInterface.
/**
Expand All @@ -269,7 +258,7 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI

private:
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface_;
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_interface_;
rclcpp::Logger system_logger_;
};

} // namespace hardware_interface
Expand Down
7 changes: 3 additions & 4 deletions hardware_interface/src/actuator.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -37,13 +37,12 @@ using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
Actuator::Actuator(std::unique_ptr<ActuatorInterface> impl) : impl_(std::move(impl)) {}

const rclcpp_lifecycle::State & Actuator::initialize(
const HardwareInfo & actuator_info,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface,
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_interface)
const HardwareInfo & actuator_info, rclcpp::Logger logger,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
{
if (impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN)
{
switch (impl_->init(actuator_info, clock_interface, logger_interface))
switch (impl_->init(actuator_info, logger, clock_interface))
{
case CallbackReturn::SUCCESS:
impl_->set_state(rclcpp_lifecycle::State(
Expand Down
2 changes: 1 addition & 1 deletion hardware_interface/src/resource_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -182,7 +182,7 @@ class ResourceStorage
try
{
const rclcpp_lifecycle::State new_state =
hardware.initialize(hardware_info, clock_interface_, logger_interface_);
hardware.initialize(hardware_info, rm_logger_, clock_interface_);
result = new_state.id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED;

if (result)
Expand Down
7 changes: 3 additions & 4 deletions hardware_interface/src/sensor.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,13 +35,12 @@ using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
Sensor::Sensor(std::unique_ptr<SensorInterface> impl) : impl_(std::move(impl)) {}

const rclcpp_lifecycle::State & Sensor::initialize(
const HardwareInfo & sensor_info,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface,
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_interface)
const HardwareInfo & sensor_info, rclcpp::Logger logger,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
{
if (impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN)
{
switch (impl_->init(sensor_info, clock_interface, logger_interface))
switch (impl_->init(sensor_info, logger, clock_interface))
{
case CallbackReturn::SUCCESS:
impl_->set_state(rclcpp_lifecycle::State(
Expand Down
7 changes: 3 additions & 4 deletions hardware_interface/src/system.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,13 +35,12 @@ using CallbackReturn = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface
System::System(std::unique_ptr<SystemInterface> impl) : impl_(std::move(impl)) {}

const rclcpp_lifecycle::State & System::initialize(
const HardwareInfo & system_info,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface,
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_interface)
const HardwareInfo & system_info, rclcpp::Logger logger,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
{
if (impl_->get_state().id() == lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN)
{
switch (impl_->init(system_info, clock_interface, logger_interface))
switch (impl_->init(system_info, logger, clock_interface))
{
case CallbackReturn::SUCCESS:
impl_->set_state(rclcpp_lifecycle::State(
Expand Down
27 changes: 18 additions & 9 deletions hardware_interface/test/test_component_interfaces.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -425,7 +425,8 @@ TEST(TestComponentInterfaces, dummy_actuator)
hardware_interface::Actuator actuator_hw(std::make_unique<test_components::DummyActuator>());

hardware_interface::HardwareInfo mock_hw_info{};
auto state = actuator_hw.initialize(mock_hw_info, nullptr, nullptr);
rclcpp::Logger logger = rclcpp::get_logger("test_actuator_components");
auto state = actuator_hw.initialize(mock_hw_info, logger, nullptr);
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

Expand Down Expand Up @@ -515,7 +516,8 @@ TEST(TestComponentInterfaces, dummy_sensor)
hardware_interface::Sensor sensor_hw(std::make_unique<test_components::DummySensor>());

hardware_interface::HardwareInfo mock_hw_info{};
auto state = sensor_hw.initialize(mock_hw_info, nullptr, nullptr);
rclcpp::Logger logger = rclcpp::get_logger("test_sensor_components");
auto state = sensor_hw.initialize(mock_hw_info, logger, nullptr);
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

Expand Down Expand Up @@ -546,7 +548,8 @@ TEST(TestComponentInterfaces, dummy_system)
hardware_interface::System system_hw(std::make_unique<test_components::DummySystem>());

hardware_interface::HardwareInfo mock_hw_info{};
auto state = system_hw.initialize(mock_hw_info, nullptr, nullptr);
rclcpp::Logger logger = rclcpp::get_logger("test_system_components");
auto state = system_hw.initialize(mock_hw_info, logger, nullptr);
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

Expand Down Expand Up @@ -670,7 +673,8 @@ TEST(TestComponentInterfaces, dummy_command_mode_system)
hardware_interface::System system_hw(
std::make_unique<test_components::DummySystemPreparePerform>());
hardware_interface::HardwareInfo mock_hw_info{};
auto state = system_hw.initialize(mock_hw_info, nullptr, nullptr);
rclcpp::Logger logger = rclcpp::get_logger("test_system_components");
auto state = system_hw.initialize(mock_hw_info, logger, nullptr);
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

Expand Down Expand Up @@ -701,7 +705,8 @@ TEST(TestComponentInterfaces, dummy_actuator_read_error_behavior)
hardware_interface::Actuator actuator_hw(std::make_unique<test_components::DummyActuator>());

hardware_interface::HardwareInfo mock_hw_info{};
auto state = actuator_hw.initialize(mock_hw_info, nullptr, nullptr);
rclcpp::Logger logger = rclcpp::get_logger("test_actuator_components");
auto state = actuator_hw.initialize(mock_hw_info, logger, nullptr);
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

Expand Down Expand Up @@ -760,7 +765,8 @@ TEST(TestComponentInterfaces, dummy_actuator_write_error_behavior)
hardware_interface::Actuator actuator_hw(std::make_unique<test_components::DummyActuator>());

hardware_interface::HardwareInfo mock_hw_info{};
auto state = actuator_hw.initialize(mock_hw_info, nullptr, nullptr);
rclcpp::Logger logger = rclcpp::get_logger("test_actuator_components");
auto state = actuator_hw.initialize(mock_hw_info, logger, nullptr);
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

Expand Down Expand Up @@ -819,7 +825,8 @@ TEST(TestComponentInterfaces, dummy_sensor_read_error_behavior)
hardware_interface::Sensor sensor_hw(std::make_unique<test_components::DummySensor>());

hardware_interface::HardwareInfo mock_hw_info{};
auto state = sensor_hw.initialize(mock_hw_info, nullptr, nullptr);
rclcpp::Logger logger = rclcpp::get_logger("test_sensor_components");
auto state = sensor_hw.initialize(mock_hw_info, logger, nullptr);

auto state_interfaces = sensor_hw.export_state_interfaces();
// Updated because is is INACTIVE
Expand Down Expand Up @@ -883,7 +890,8 @@ TEST(TestComponentInterfaces, dummy_system_read_error_behavior)
hardware_interface::System system_hw(std::make_unique<test_components::DummySystem>());

hardware_interface::HardwareInfo mock_hw_info{};
auto state = system_hw.initialize(mock_hw_info, nullptr, nullptr);
rclcpp::Logger logger = rclcpp::get_logger("test_system_components");
auto state = system_hw.initialize(mock_hw_info, logger, nullptr);
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

Expand Down Expand Up @@ -947,7 +955,8 @@ TEST(TestComponentInterfaces, dummy_system_write_error_behavior)
hardware_interface::System system_hw(std::make_unique<test_components::DummySystem>());

hardware_interface::HardwareInfo mock_hw_info{};
auto state = system_hw.initialize(mock_hw_info, nullptr, nullptr);
rclcpp::Logger logger = rclcpp::get_logger("test_system_components");
auto state = system_hw.initialize(mock_hw_info, logger, nullptr);
EXPECT_EQ(lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED, state.id());
EXPECT_EQ(hardware_interface::lifecycle_state_names::UNCONFIGURED, state.label());

Expand Down

0 comments on commit 812243c

Please sign in to comment.