Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add logger and clock interfaces from ResourceManager to HardwareComponent interfaces #1585

Merged
merged 23 commits into from
Jul 8, 2024
Merged
Show file tree
Hide file tree
Changes from 19 commits
Commits
Show all changes
23 commits
Select commit Hold shift + click to select a range
cd7fe30
Add logging interface as an argument into the ResourceManager constru…
saikishor Jun 22, 2024
a424ec2
Add get_logger and get_clock methods in the ResourceManager and Resou…
saikishor Jun 22, 2024
806430e
Propagate the interfaces to the HW component
saikishor Jun 24, 2024
73cc794
Add the `init` API in the hardware interfaces to parse the logging an…
saikishor Jun 24, 2024
a391558
comment to avoid unused parameter warning
saikishor Jun 24, 2024
4dbcf0c
Add documentation to the get_logger and get_clock methods
saikishor Jun 24, 2024
3565f8b
remove the default nullptr args to the logging and clock interface
saikishor Jun 24, 2024
7760461
Consider the nullptr and return valid Logger and Clock
saikishor Jun 24, 2024
fe46906
Change RCUTILS logging to RCLCPP logging
saikishor Jun 24, 2024
e037d10
rename ResourceManager to resource_manager in the logger
saikishor Jun 24, 2024
b313af4
change the variables order for the vtable
saikishor Jun 25, 2024
578408d
Add rm_logger variable to avoid asking for logger every instance
saikishor Jun 25, 2024
1fdcbbb
remove NodeLoggingInterface and parse Logger directly
saikishor Jun 25, 2024
4eecf45
change the include headers of unused logging interface
saikishor Jun 25, 2024
2baf0b1
enable logger services for the controller_manager
saikishor Jun 25, 2024
812d103
Update Release Notes
saikishor Jun 25, 2024
4ff14e5
return shared pointer of clock instead of clock itself
saikishor Jun 27, 2024
5bc3c93
make the clock and logger interfaces mandatory arguments and fix tests
saikishor Jun 27, 2024
2bf8a1d
Merge branch 'master' into propagate/logger
saikishor Jul 4, 2024
038945c
add similar comment on the version conditioning
saikishor Jul 4, 2024
303c846
add the default rm_logger_ to the if-else as per MR suggestion
saikishor Jul 4, 2024
ec89bf5
print default value of the update_rate
saikishor Jul 4, 2024
9d72500
print default update rate in other instances as well
saikishor Jul 4, 2024
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 @@ -82,6 +82,13 @@ class ControllerManager : public rclcpp::Node
const std::string & node_namespace = "",
const rclcpp::NodeOptions & options = get_cm_node_options());

CONTROLLER_MANAGER_PUBLIC
destogl marked this conversation as resolved.
Show resolved Hide resolved
ControllerManager(
std::shared_ptr<rclcpp::Executor> executor, const std::string & urdf,
bool activate_all_hw_components, const std::string & manager_node_name = "controller_manager",
const std::string & node_namespace = "",
const rclcpp::NodeOptions & options = get_cm_node_options());

CONTROLLER_MANAGER_PUBLIC
virtual ~ControllerManager() = default;

Expand Down
40 changes: 38 additions & 2 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -180,15 +180,18 @@ rclcpp::NodeOptions get_cm_node_options()
// Required for getting types of controllers to be loaded via service call
node_options.allow_undeclared_parameters(true);
node_options.automatically_declare_parameters_from_overrides(true);
#if RCLCPP_VERSION_MAJOR >= 21
destogl marked this conversation as resolved.
Show resolved Hide resolved
node_options.enable_logger_service(true);
#endif
return node_options;
}

ControllerManager::ControllerManager(
std::shared_ptr<rclcpp::Executor> executor, const std::string & manager_node_name,
const std::string & node_namespace, const rclcpp::NodeOptions & options)
: rclcpp::Node(manager_node_name, node_namespace, options),
resource_manager_(
std::make_unique<hardware_interface::ResourceManager>(this->get_node_clock_interface())),
resource_manager_(std::make_unique<hardware_interface::ResourceManager>(
this->get_node_clock_interface(), this->get_node_logging_interface())),
diagnostics_updater_(this),
executor_(executor),
loader_(std::make_shared<pluginlib::ClassLoader<controller_interface::ControllerInterface>>(
Expand Down Expand Up @@ -230,6 +233,39 @@ ControllerManager::ControllerManager(
"Controllers Activity", this, &ControllerManager::controller_activity_diagnostic_callback);
}

ControllerManager::ControllerManager(
std::shared_ptr<rclcpp::Executor> executor, const std::string & urdf,
bool activate_all_hw_components, const std::string & manager_node_name,
const std::string & node_namespace, const rclcpp::NodeOptions & options)
: rclcpp::Node(manager_node_name, node_namespace, options),
update_rate_(get_parameter_or<int>("update_rate", 100)),
resource_manager_(std::make_unique<hardware_interface::ResourceManager>(
urdf, this->get_node_clock_interface(), this->get_node_logging_interface(),
activate_all_hw_components, update_rate_)),
diagnostics_updater_(this),
executor_(executor),
loader_(std::make_shared<pluginlib::ClassLoader<controller_interface::ControllerInterface>>(
kControllerInterfaceNamespace, kControllerInterfaceClassName)),
chainable_loader_(
std::make_shared<pluginlib::ClassLoader<controller_interface::ChainableControllerInterface>>(
kControllerInterfaceNamespace, kChainableControllerInterfaceClassName))
{
if (!get_parameter("update_rate", update_rate_))
{
RCLCPP_WARN(get_logger(), "'update_rate' parameter not set, using default value.");
saikishor marked this conversation as resolved.
Show resolved Hide resolved
}

if (is_resource_manager_initialized())
{
init_services();
}
subscribe_to_robot_description_topic();
destogl marked this conversation as resolved.
Show resolved Hide resolved

diagnostics_updater_.setHardwareID("ros2_control");
diagnostics_updater_.add(
"Controllers Activity", this, &ControllerManager::controller_activity_diagnostic_callback);
}

ControllerManager::ControllerManager(
std::unique_ptr<hardware_interface::ResourceManager> resource_manager,
std::shared_ptr<rclcpp::Executor> executor, const std::string & manager_node_name,
Expand Down
15 changes: 12 additions & 3 deletions controller_manager/test/controller_manager_test_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -74,7 +74,9 @@ class ControllerManagerFixture : public ::testing::Test
if (robot_description_.empty())
{
cm_ = std::make_shared<CtrlMgr>(
std::make_unique<hardware_interface::ResourceManager>(), executor_, TEST_CM_NAME);
std::make_unique<hardware_interface::ResourceManager>(
rm_node_->get_node_clock_interface(), rm_node_->get_node_logging_interface()),
executor_, TEST_CM_NAME);
}
else
{
Expand All @@ -83,7 +85,9 @@ class ControllerManagerFixture : public ::testing::Test
if (pass_urdf_as_parameter_)
{
cm_ = std::make_shared<CtrlMgr>(
std::make_unique<hardware_interface::ResourceManager>(robot_description_, true, true),
std::make_unique<hardware_interface::ResourceManager>(
robot_description_, rm_node_->get_node_clock_interface(),
rm_node_->get_node_logging_interface(), true, 100),
executor_, TEST_CM_NAME);
}
else
Expand All @@ -93,7 +97,9 @@ class ControllerManagerFixture : public ::testing::Test

// this is just a workaround to skip passing
cm_ = std::make_shared<CtrlMgr>(
std::make_unique<hardware_interface::ResourceManager>(), executor_, TEST_CM_NAME);
std::make_unique<hardware_interface::ResourceManager>(
rm_node_->get_node_clock_interface(), rm_node_->get_node_logging_interface()),
executor_, TEST_CM_NAME);
// mimic topic call
auto msg = std_msgs::msg::String();
msg.data = robot_description_;
Expand Down Expand Up @@ -158,6 +164,9 @@ class ControllerManagerFixture : public ::testing::Test
const std::string robot_description_;
const bool pass_urdf_as_parameter_;
rclcpp::Time time_;

protected:
rclcpp::Node::SharedPtr rm_node_ = std::make_shared<rclcpp::Node>("ResourceManager");
};

class TestControllerManagerSrvs
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,8 @@ class TestControllerManagerWithNamespace
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
cm_ = std::make_shared<controller_manager::ControllerManager>(
std::make_unique<hardware_interface::ResourceManager>(
ros2_control_test_assets::minimal_robot_urdf, true, true),
ros2_control_test_assets::minimal_robot_urdf, rm_node_->get_node_clock_interface(),
rm_node_->get_node_logging_interface(), true),
executor_, TEST_CM_NAME, TEST_NAMESPACE);
run_updater_ = false;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -111,7 +111,8 @@ class TestControllerChainingWithControllerManager
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
cm_ = std::make_shared<TestableControllerManager>(
std::make_unique<hardware_interface::ResourceManager>(
ros2_control_test_assets::diffbot_urdf, true, true),
ros2_control_test_assets::diffbot_urdf, rm_node_->get_node_clock_interface(),
rm_node_->get_node_logging_interface(), true),
executor_, TEST_CM_NAME);
run_updater_ = false;
}
Expand Down
6 changes: 2 additions & 4 deletions controller_manager/test/test_hardware_management_srvs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,8 +63,7 @@ class TestControllerManagerHWManagementSrvs : public TestControllerManagerSrvs
void SetUp() override
{
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
cm_ = std::make_shared<controller_manager::ControllerManager>(
std::make_unique<hardware_interface::ResourceManager>(), executor_, TEST_CM_NAME);
cm_ = std::make_shared<controller_manager::ControllerManager>(executor_, TEST_CM_NAME);
run_updater_ = false;

cm_->set_parameter(
Expand Down Expand Up @@ -369,8 +368,7 @@ class TestControllerManagerHWManagementSrvsWithoutParams
void SetUp() override
{
executor_ = std::make_shared<rclcpp::executors::SingleThreadedExecutor>();
cm_ = std::make_shared<controller_manager::ControllerManager>(
std::make_unique<hardware_interface::ResourceManager>(), executor_, TEST_CM_NAME);
cm_ = std::make_shared<controller_manager::ControllerManager>(executor_, TEST_CM_NAME);
run_updater_ = false;

// TODO(destogl): separate this to init_tests method where parameter can be set for each test
Expand Down
1 change: 1 addition & 0 deletions doc/release_notes/Jazzy.rst
Original file line number Diff line number Diff line change
Expand Up @@ -94,6 +94,7 @@ hardware_interface
</ros2_control>

* Soft limits are also parsed from the URDF into the ``HardwareInfo`` structure for the defined joints (`#1488 <https://github.com/ros-controls/ros2_control/pull/1488>`_)
* Access to logger and clock through ``get_logger`` and ``get_clock`` methods in ResourceManager and HardwareComponents ``Actuator``, ``Sensor`` and ``System`` (`#1585 <https://github.com/ros-controls/ros2_control/pull/1585>`_)

joint_limits
************
Expand Down
6 changes: 5 additions & 1 deletion hardware_interface/include/hardware_interface/actuator.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,8 @@
#include "hardware_interface/types/hardware_interface_return_values.hpp"
#include "hardware_interface/visibility_control.h"
#include "rclcpp/duration.hpp"
#include "rclcpp/logging.hpp"
#include "rclcpp/node_interfaces/node_clock_interface.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp_lifecycle/state.hpp"

Expand All @@ -44,7 +46,9 @@ class Actuator final
~Actuator() = default;

HARDWARE_INTERFACE_PUBLIC
const rclcpp_lifecycle::State & initialize(const HardwareInfo & actuator_info);
const rclcpp_lifecycle::State & initialize(
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 @@ -25,6 +25,8 @@
#include "hardware_interface/types/lifecycle_state_names.hpp"
#include "lifecycle_msgs/msg/state.hpp"
#include "rclcpp/duration.hpp"
#include "rclcpp/logging.hpp"
#include "rclcpp/node_interfaces/node_clock_interface.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
#include "rclcpp_lifecycle/state.hpp"
Expand Down Expand Up @@ -73,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"))
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Shouldn't we here use some better name? Or better yet, do we need this actually? As we always have to call init first.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

You need to define something, if not it complains with the following error. That's the reason, I declared basically the name of the class

 error: ‘rclcpp::Logger::Logger()’ is private within this context

{
}

Expand All @@ -88,15 +91,33 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod

virtual ~ActuatorInterface() = default;

/// Initialization of the hardware interface from data parsed from the robot's URDF.
/// Initialization of the hardware interface from data parsed from the robot's URDF and also the
/// clock and logger interfaces.
/**
* \param[in] hardware_info structure with data from URDF.
* \param[in] clock_interface pointer to the clock interface.
* \param[in] logger_interface pointer to the logger interface.
* \returns CallbackReturn::SUCCESS if required data are provided and can be parsed.
* \returns CallbackReturn::ERROR if any error happens or data are missing.
*/
virtual CallbackReturn on_init(const HardwareInfo & hardware_info)
CallbackReturn init(
const HardwareInfo & hardware_info, rclcpp::Logger logger,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface)
{
clock_interface_ = clock_interface;
actuator_logger_ = logger.get_child("hardware_component.actuator." + hardware_info.name);
info_ = hardware_info;
return on_init(hardware_info);
};

/// Initialization of the hardware interface from data parsed from the robot's URDF.
/**
* \param[in] hardware_info structure with data from URDF.
* \returns CallbackReturn::SUCCESS if required data are provided and can be parsed.
* \returns CallbackReturn::ERROR if any error happens or data are missing.
*/
virtual CallbackReturn on_init(const HardwareInfo & /*hardware_info*/)
{
return CallbackReturn::SUCCESS;
};

Expand Down Expand Up @@ -209,8 +230,24 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
void set_state(const rclcpp_lifecycle::State & new_state) { lifecycle_state_ = new_state; }

protected:
/// Get the logger of the ActuatorInterface.
/**
* \return logger of the ActuatorInterface.
*/
rclcpp::Logger get_logger() const { return actuator_logger_; }

/// Get the clock of the ActuatorInterface.
/**
* \return clock of the ActuatorInterface.
*/
rclcpp::Clock::SharedPtr get_clock() const { return clock_interface_->get_clock(); }

HardwareInfo info_;
rclcpp_lifecycle::State lifecycle_state_;

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

} // namespace hardware_interface
Expand Down
21 changes: 18 additions & 3 deletions hardware_interface/include/hardware_interface/resource_manager.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,8 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager
public:
/// Default constructor for the Resource Manager.
explicit ResourceManager(
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface = nullptr);
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface,
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_interface);

/// Constructor for the Resource Manager.
/**
Expand All @@ -67,8 +68,10 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager
* used for triggering async components.
*/
explicit ResourceManager(
const std::string & urdf, bool activate_all = false, const unsigned int update_rate = 100,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface = nullptr);
const std::string & urdf,
rclcpp::node_interfaces::NodeClockInterface::SharedPtr clock_interface,
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr logger_interface,
bool activate_all = false, const unsigned int update_rate = 100);

ResourceManager(const ResourceManager &) = delete;

Expand Down Expand Up @@ -408,6 +411,18 @@ class HARDWARE_INTERFACE_PUBLIC ResourceManager
bool state_interface_exists(const std::string & key) const;

protected:
/// Gets the logger for the resource manager
/**
* \return logger of the resource manager
*/
rclcpp::Logger get_logger() const;

/// Gets the clock for the resource manager
/**
* \return clock of the resource manager
*/
rclcpp::Clock::SharedPtr get_clock() const;

bool components_are_loaded_and_initialized_ = false;

mutable std::recursive_mutex resource_interfaces_lock_;
Expand Down
6 changes: 5 additions & 1 deletion hardware_interface/include/hardware_interface/sensor.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,8 @@
#include "hardware_interface/types/hardware_interface_return_values.hpp"
#include "hardware_interface/visibility_control.h"
#include "rclcpp/duration.hpp"
#include "rclcpp/logging.hpp"
#include "rclcpp/node_interfaces/node_clock_interface.hpp"
#include "rclcpp/time.hpp"
#include "rclcpp_lifecycle/state.hpp"

Expand All @@ -45,7 +47,9 @@ class Sensor final
~Sensor() = default;

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

HARDWARE_INTERFACE_PUBLIC
const rclcpp_lifecycle::State & configure();
Expand Down
Loading
Loading