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

Refactor logging (backport #543) #619

Merged
merged 3 commits into from
Nov 13, 2024
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
5 changes: 3 additions & 2 deletions example_1/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -208,8 +208,9 @@ Tutorial steps

.. code-block:: shell

[RRBotSystemPositionOnlyHardware]: Got command 0.50000 for joint 0!
[RRBotSystemPositionOnlyHardware]: Got command 0.50000 for joint 1!
[ros2_control_node-1] [INFO] [1721763082.437870177] [controller_manager.resource_manager.hardware_component.system.RRBot]: Writing commands:
[ros2_control_node-1] 0.50 for joint 'joint2/position'
[ros2_control_node-1] 0.50 for joint 'joint1/position'

If you echo the ``/joint_states`` or ``/dynamic_joint_states`` topics you should now get similar values, namely the simulated states of the robot

Expand Down
18 changes: 18 additions & 0 deletions example_1/hardware/include/ros2_control_demo_example_1/rrbot.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@
#include "hardware_interface/hardware_info.hpp"
#include "hardware_interface/system_interface.hpp"
#include "hardware_interface/types/hardware_interface_return_values.hpp"
#include "rclcpp/clock.hpp"
#include "rclcpp/logger.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
#include "rclcpp_lifecycle/state.hpp"
Expand Down Expand Up @@ -56,12 +58,28 @@ class RRBotSystemPositionOnlyHardware : public hardware_interface::SystemInterfa
hardware_interface::return_type write(
const rclcpp::Time & time, const rclcpp::Duration & period) override;

/// Get the logger of the SystemInterface.
/**
* \return logger of the SystemInterface.
*/
rclcpp::Logger get_logger() const { return *logger_; }

/// Get the clock of the SystemInterface.
/**
* \return clock of the SystemInterface.
*/
rclcpp::Clock::SharedPtr get_clock() const { return clock_; }

private:
// Parameters for the RRBot simulation
double hw_start_sec_;
double hw_stop_sec_;
double hw_slowdown_;

// Objects for logging
std::shared_ptr<rclcpp::Logger> logger_;
rclcpp::Clock::SharedPtr clock_;

// Store the command for the simulated robot
std::vector<double> hw_commands_;
std::vector<double> hw_states_;
Expand Down
73 changes: 33 additions & 40 deletions example_1/hardware/rrbot.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,8 +16,11 @@

#include <chrono>
#include <cmath>
#include <iomanip>
#include <limits>
#include <memory>
#include <sstream>
#include <string>
#include <vector>

#include "hardware_interface/types/hardware_interface_type_values.hpp"
Expand All @@ -34,6 +37,9 @@ hardware_interface::CallbackReturn RRBotSystemPositionOnlyHardware::on_init(
{
return hardware_interface::CallbackReturn::ERROR;
}
logger_ = std::make_shared<rclcpp::Logger>(
rclcpp::get_logger("controller_manager.resource_manager.hardware_component.system.RRBot"));
clock_ = std::make_shared<rclcpp::Clock>(rclcpp::Clock());

// BEGIN: This part here is for exemplary purposes - Please do not copy to your production code
hw_start_sec_ = stod(info_.hardware_parameters["example_param_hw_start_duration_sec"]);
Expand All @@ -49,35 +55,32 @@ hardware_interface::CallbackReturn RRBotSystemPositionOnlyHardware::on_init(
if (joint.command_interfaces.size() != 1)
{
RCLCPP_FATAL(
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
"Joint '%s' has %zu command interfaces found. 1 expected.", joint.name.c_str(),
joint.command_interfaces.size());
get_logger(), "Joint '%s' has %zu command interfaces found. 1 expected.",
joint.name.c_str(), joint.command_interfaces.size());
return hardware_interface::CallbackReturn::ERROR;
}

if (joint.command_interfaces[0].name != hardware_interface::HW_IF_POSITION)
{
RCLCPP_FATAL(
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
"Joint '%s' have %s command interfaces found. '%s' expected.", joint.name.c_str(),
joint.command_interfaces[0].name.c_str(), hardware_interface::HW_IF_POSITION);
get_logger(), "Joint '%s' have %s command interfaces found. '%s' expected.",
joint.name.c_str(), joint.command_interfaces[0].name.c_str(),
hardware_interface::HW_IF_POSITION);
return hardware_interface::CallbackReturn::ERROR;
}

if (joint.state_interfaces.size() != 1)
{
RCLCPP_FATAL(
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
"Joint '%s' has %zu state interface. 1 expected.", joint.name.c_str(),
get_logger(), "Joint '%s' has %zu state interface. 1 expected.", joint.name.c_str(),
joint.state_interfaces.size());
return hardware_interface::CallbackReturn::ERROR;
}

if (joint.state_interfaces[0].name != hardware_interface::HW_IF_POSITION)
{
RCLCPP_FATAL(
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"),
"Joint '%s' have %s state interface. '%s' expected.", joint.name.c_str(),
get_logger(), "Joint '%s' have %s state interface. '%s' expected.", joint.name.c_str(),
joint.state_interfaces[0].name.c_str(), hardware_interface::HW_IF_POSITION);
return hardware_interface::CallbackReturn::ERROR;
}
Expand All @@ -90,15 +93,12 @@ hardware_interface::CallbackReturn RRBotSystemPositionOnlyHardware::on_configure
const rclcpp_lifecycle::State & /*previous_state*/)
{
// BEGIN: This part here is for exemplary purposes - Please do not copy to your production code
RCLCPP_INFO(
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), "Configuring ...please wait...");
RCLCPP_INFO(get_logger(), "Configuring ...please wait...");

for (int i = 0; i < hw_start_sec_; i++)
{
rclcpp::sleep_for(std::chrono::seconds(1));
RCLCPP_INFO(
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), "%.1f seconds left...",
hw_start_sec_ - i);
RCLCPP_INFO(get_logger(), "%.1f seconds left...", hw_start_sec_ - i);
}
// END: This part here is for exemplary purposes - Please do not copy to your production code

Expand All @@ -108,8 +108,7 @@ hardware_interface::CallbackReturn RRBotSystemPositionOnlyHardware::on_configure
hw_states_[i] = 0;
hw_commands_[i] = 0;
}

RCLCPP_INFO(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), "Successfully configured!");
RCLCPP_INFO(get_logger(), "Successfully configured!");

return hardware_interface::CallbackReturn::SUCCESS;
}
Expand Down Expand Up @@ -144,15 +143,12 @@ hardware_interface::CallbackReturn RRBotSystemPositionOnlyHardware::on_activate(
const rclcpp_lifecycle::State & /*previous_state*/)
{
// BEGIN: This part here is for exemplary purposes - Please do not copy to your production code
RCLCPP_INFO(
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), "Activating ...please wait...");
RCLCPP_INFO(get_logger(), "Activating ...please wait...");

for (int i = 0; i < hw_start_sec_; i++)
{
rclcpp::sleep_for(std::chrono::seconds(1));
RCLCPP_INFO(
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), "%.1f seconds left...",
hw_start_sec_ - i);
RCLCPP_INFO(get_logger(), "%.1f seconds left...", hw_start_sec_ - i);
}
// END: This part here is for exemplary purposes - Please do not copy to your production code

Expand All @@ -162,7 +158,7 @@ hardware_interface::CallbackReturn RRBotSystemPositionOnlyHardware::on_activate(
hw_commands_[i] = hw_states_[i];
}

RCLCPP_INFO(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), "Successfully activated!");
RCLCPP_INFO(get_logger(), "Successfully activated!");

return hardware_interface::CallbackReturn::SUCCESS;
}
Expand All @@ -171,18 +167,15 @@ hardware_interface::CallbackReturn RRBotSystemPositionOnlyHardware::on_deactivat
const rclcpp_lifecycle::State & /*previous_state*/)
{
// BEGIN: This part here is for exemplary purposes - Please do not copy to your production code
RCLCPP_INFO(
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), "Deactivating ...please wait...");
RCLCPP_INFO(get_logger(), "Deactivating ...please wait...");

for (int i = 0; i < hw_stop_sec_; i++)
{
rclcpp::sleep_for(std::chrono::seconds(1));
RCLCPP_INFO(
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), "%.1f seconds left...",
hw_stop_sec_ - i);
RCLCPP_INFO(get_logger(), "%.1f seconds left...", hw_stop_sec_ - i);
}

RCLCPP_INFO(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), "Successfully deactivated!");
RCLCPP_INFO(get_logger(), "Successfully deactivated!");
// END: This part here is for exemplary purposes - Please do not copy to your production code

return hardware_interface::CallbackReturn::SUCCESS;
Expand All @@ -192,17 +185,18 @@ hardware_interface::return_type RRBotSystemPositionOnlyHardware::read(
const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
{
// BEGIN: This part here is for exemplary purposes - Please do not copy to your production code
RCLCPP_INFO(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), "Reading...");
std::stringstream ss;
ss << "Reading states:";

for (uint i = 0; i < hw_states_.size(); i++)
{
// Simulate RRBot's movement
hw_states_[i] = hw_states_[i] + (hw_commands_[i] - hw_states_[i]) / hw_slowdown_;
RCLCPP_INFO(
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), "Got state %.5f for joint %d!",
hw_states_[i], i);

ss << std::fixed << std::setprecision(2) << std::endl
<< "\t" << hw_states_[i] << " for joint '" << info_.joints[i].name << "'";
}
RCLCPP_INFO(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), "Joints successfully read!");
RCLCPP_INFO_THROTTLE(get_logger(), *get_clock(), 500, "%s", ss.str().c_str());
// END: This part here is for exemplary purposes - Please do not copy to your production code

return hardware_interface::return_type::OK;
Expand All @@ -212,17 +206,16 @@ hardware_interface::return_type RRBotSystemPositionOnlyHardware::write(
const rclcpp::Time & /*time*/, const rclcpp::Duration & /*period*/)
{
// BEGIN: This part here is for exemplary purposes - Please do not copy to your production code
RCLCPP_INFO(rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), "Writing...");
std::stringstream ss;
ss << "Writing commands:";

for (uint i = 0; i < hw_commands_.size(); i++)
{
// Simulate sending commands to the hardware
RCLCPP_INFO(
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), "Got command %.5f for joint %d!",
hw_commands_[i], i);
ss << std::fixed << std::setprecision(2) << std::endl
<< "\t" << hw_commands_[i] << " for joint '" << info_.joints[i].name << "'";
}
RCLCPP_INFO(
rclcpp::get_logger("RRBotSystemPositionOnlyHardware"), "Joints successfully written!");
RCLCPP_INFO_THROTTLE(get_logger(), *get_clock(), 500, "%s", ss.str().c_str());
// END: This part here is for exemplary purposes - Please do not copy to your production code

return hardware_interface::return_type::OK;
Expand Down
5 changes: 3 additions & 2 deletions example_10/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -88,8 +88,9 @@ The *RRBot* URDF files can be found in the ``description/urdf`` folder.

.. code-block:: shell

[RRBotSystemWithGPIOHardware]: Got command 0.5 for GP output 0!
[RRBotSystemWithGPIOHardware]: Got command 0.7 for GP output 1!
[ros2_control_node-1] [INFO] [1721765648.271058850] [controller_manager.resource_manager.hardware_component.system.RRBot]: Writing commands:
[ros2_control_node-1] 0.50 for GPIO output '0'
[ros2_control_node-1] 0.70 for GPIO output '1'

7. Let's introspect the ros2_control hardware component. Calling

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,8 @@
#include "hardware_interface/hardware_info.hpp"
#include "hardware_interface/system_interface.hpp"
#include "hardware_interface/types/hardware_interface_return_values.hpp"
#include "rclcpp/clock.hpp"
#include "rclcpp/logger.hpp"
#include "rclcpp/macros.hpp"
#include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
#include "rclcpp_lifecycle/state.hpp"
Expand Down Expand Up @@ -56,8 +58,22 @@ class RRBotSystemWithGPIOHardware : public hardware_interface::SystemInterface
hardware_interface::return_type write(
const rclcpp::Time & time, const rclcpp::Duration & period) override;

/// Get the logger of the SystemInterface.
/**
* \return logger of the SystemInterface.
*/
rclcpp::Logger get_logger() const { return *logger_; }

/// Get the clock of the SystemInterface.
/**
* \return clock of the SystemInterface.
*/
rclcpp::Clock::SharedPtr get_clock() const { return clock_; }

private:
// Parameters for the RRBot simulation
// Objects for logging
std::shared_ptr<rclcpp::Logger> logger_;
rclcpp::Clock::SharedPtr clock_;

// Store the command and state interfaces for the simulated robot
std::vector<double> hw_commands_;
Expand Down
Loading
Loading