Skip to content

Commit

Permalink
Add logger service description (#3477)
Browse files Browse the repository at this point in the history
* Add logger service description

Signed-off-by: Barry Xu <[email protected]>
Co-authored-by: Chris Lalancette <[email protected]>
  • Loading branch information
Barry-Xu-2018 and clalancette authored Jul 13, 2023
1 parent 81fd8c6 commit c60d0e1
Showing 1 changed file with 72 additions and 12 deletions.
84 changes: 72 additions & 12 deletions source/Tutorials/Demos/Logging-and-logger-configuration.rst
Original file line number Diff line number Diff line change
Expand Up @@ -232,26 +232,86 @@ See `the source code <https://github.com/ros2/demos/blob/{REPOS_FILE_BRANCH}/log
Logger level configuration: externally
--------------------------------------

In the future there will be a generalized approach to external configuration of loggers at runtime (similar to how `rqt_logger_level <https://wiki.ros.org/rqt_logger_level>`__ in ROS 1 allows logger configuration via remote procedural calls).
**This concept is not yet officially supported in ROS 2.**
In the meantime, this demo provides an **example** service that can be called externally to request configuration of logger levels for known names of loggers in the process.
ROS 2 nodes have services available to configure the logging level externally at runtime.
These services are disabled by default.
The following code shows how to enable the logger service while creating the node.

The demo previously started is already running this example service.
To set the level of the demo's logger back to ``INFO``\ , call the service with:
.. tabs::

.. code-block:: bash
.. group-tab:: Linux

.. code-block:: C++

ros2 service call /config_logger logging_demo/srv/ConfigLogger "{logger_name: 'logger_usage_demo', level: INFO}"
// Create a node with logger service enabled
auto node = std::make_shared<rclcpp::Node>("NodeWithLoggerService", rclcpp::NodeOptions().enable_logger_service(true))

This service call will work on any logger that is running in the process provided that you know its name.
This includes the loggers in the ROS 2 core, such as ``rcl`` (the common client library package).
To enable debug logging for ``rcl``, call:
.. group-tab:: Python

.. code-block:: python
# Create a node with logger service enabled
node = Node('NodeWithLoggerService', enable_logger_service=True)
If you run one of the nodes as configured above, you will find 2 services when running ``ros2 service list``:

.. code-block:: bash
ros2 service call /config_logger logging_demo/srv/ConfigLogger "{logger_name: 'rcl', level: DEBUG}"
$ ros2 service list
...
/NodeWithLoggerService/get_logger_levels
/NodeWithLoggerService/set_logger_levels
...
* get_logger_levels

Use this service to get logger levels for specified logger names.

Run ``ros2 service call`` to get logger levels for ``NodeWithLoggerService`` and ``rcl``.

.. code-block:: bash
$ ros2 service call /NodeWithLoggerService/get_logger_levels rcl_interfaces/srv/GetLoggerLevels '{names: ["NodeWithLoggerService", "rcl"]}'
requester: making request: rcl_interfaces.srv.GetLoggerLevels_Request(names=['NodeWithLoggerService', 'rcl'])
response:
rcl_interfaces.srv.GetLoggerLevels_Response(levels=[rcl_interfaces.msg.LoggerLevel(name='NodeWithLoggerService', level=0), rcl_interfaces.msg.LoggerLevel(name='rcl', level=0)])
* set_logger_levels

Use this service to set logger levels for specified logger names.

Run ``ros2 service call`` to set logger levels for ``NodeWithLoggerService`` and ``rcl``.

.. code-block:: bash
$ ros2 service call /NodeWithLoggerService/set_logger_levels rcl_interfaces/srv/SetLoggerLevels '{levels: [{name: "NodeWithLoggerService", level: 20}, {name: "rcl", level: 10}]}'
requester: making request: rcl_interfaces.srv.SetLoggerLevels_Request(levels=[rcl_interfaces.msg.LoggerLevel(name='NodeWithLoggerService', level=20), rcl_interfaces.msg.LoggerLevel(name='rcl', level=10)])
response:
rcl_interfaces.srv.SetLoggerLevels_Response(results=[rcl_interfaces.msg.SetLoggerLevelsResult(successful=True, reason=''), rcl_interfaces.msg.SetLoggerLevelsResult(successful=True, reason='')])
There is also demo code showing how to set or get the logger level via the logger service.

* rclcpp: `demo code <https://github.com/ros2/demos/tree/{REPOS_FILE_BRANCH}/demo_nodes_cpp/src/logging/use_logger_service.cpp>`__

.. code-block:: bash
$ ros2 run demo_nodes_cpp use_logger_service
* rclpy: `demo code <https://github.com/ros2/demos/tree/{REPOS_FILE_BRANCH}/demo_nodes_py/demo_nodes_py/logging/use_logger_service.py>`__

.. code-block:: bash
$ ros2 run demo_nodes_py use_logger_service
.. warning::

You should see debug output from ``rcl`` start to show.
Currently, there is a limitation that ``get_logger_levels`` and ``set_logger_levels`` services are not thread-safe.
This means that you need to ensure that only one thread is calling the services at a time.
Please see the details in https://github.com/ros2/rcutils/issues/397

Using the logger config component
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
Expand Down

0 comments on commit c60d0e1

Please sign in to comment.