Skip to content

Commit

Permalink
Add documentation and release note about exporting state interfaces f…
Browse files Browse the repository at this point in the history
…rom controllers
  • Loading branch information
saikishor committed May 13, 2024
1 parent 13a1fcd commit 96eced7
Show file tree
Hide file tree
Showing 3 changed files with 24 additions and 9 deletions.
30 changes: 21 additions & 9 deletions controller_manager/doc/controller_chaining.rst
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ To describe the intent of this document, lets focus on the simple yet sufficient
:alt: Example2


In this example, we want to chain 'position_tracking' controller with 'diff_drive_controller' and two PID controllers.
In this example, we want to chain 'position_tracking' controller with 'diff_drive_controller' and two PID controllers as well as the 'robot_localization' controller.
Let's now imagine a use-case where we don't only want to run all those controllers as a group, but also flexibly add preceding steps.
This means the following:

Expand All @@ -37,20 +37,30 @@ This means the following:
2. Then "diff_drive_controller" is activated and attaches itself to the virtual input interfaces of PID controllers.
PID controllers also get informed that they are working in chained mode and therefore disable their external interface through subscriber.
Now we check if kinematics of differential robot is running properly.
3. After that, "position_tracking" can be activated and attached to "diff_drive_controller" that disables its external interfaces.
4. If any of the controllers is deactivated, also all preceding controllers are deactivated.
3. Once the 'diff_drive_controller' is activated, it exposes the 'odom' state interfaces that is used by 'odom_publisher' as well as 'sensor_fusion' controllers.
The 'odom_publisher' controller is activated and attaches itself to the exported 'odom' state interfaces of 'diff_drive_controller'.
The 'sensor_fusion' controller is activated and attaches itself to the exported 'odom' state interfaces of 'diff_drive_controller' along with the 'imu' state interfaces.
4. Once the 'sensor_fusion' controller is activated, it exposes the 'odom' state interfaces that is used by 'robot_localization' controller.
The 'robot_localization' controller is activated and attaches itself to the 'odom' state interfaces of 'sensor_fusion' controller.
Once activated, the 'robot_localization' controller exposes the 'actual_pose' state interfaces that is used by 'position_tracking' controller.
5. After that, "position_tracking" can be activated and attached to "diff_drive_controller" that disables its external interfaces and to the 'robot_localization' controller which provides the 'actual_pose' state interface.
6. If any of the controllers is deactivated, also all preceding controllers needs to be deactivated.

.. note::

Only the controllers that exposes the reference interfaces are switched to chained mode, when their reference interfaces are used by other controllers. When their reference interfaces are not used by the other controllers, they are switched back to get references from the subscriber.
However, the controllers that exposes the state interfaces are not triggered to chained mode, when their state interfaces are used by other controllers.

Implementation
--------------

A Controller Base-Class: ChainableController
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

A ``ChainableController`` extends ``ControllerInterface`` class with ``virtual InterfaceConfiguration input_interface_configuration() const = 0`` method.
This method should implement for each controller that **can be preceded** by another controller exporting all the input interfaces.
For simplicity reasons, it is assumed for now that controller's all input interfaces are used.
Therefore, do not try to implement any exclusive combinations of input interfaces, but rather write multiple controllers if you need exclusivity.
A ``ChainableController`` extends ``ControllerInterface`` class with ``virtual std::vector<hardware_interface::CommandInterface> export_reference_interfaces() = 0`` method as well as ``virtual std::vector<hardware_interface::StateInterface> export_state_interfaces() = 0`` method.
This method should implement for each controller that **can be preceded** by another controller exporting all the reference/state interfaces.
For simplicity reasons, it is assumed for now that controller's all reference interfaces are used by other controller. However, the state interfaces exported by the controller, can be used by multieple controllers at the same time and with the combination they want.
Therefore, do not try to implement any exclusive combinations of reference interfaces, but rather write multiple controllers if you need exclusivity.

The ``ChainableController`` base class implements ``void set_chained_mode(bool activate)`` that sets an internal flag that a controller is used by another controller (in chained mode) and calls ``virtual void on_set_chained_mode(bool activate) = 0`` that implements controller's specific actions when chained modes is activated or deactivated, e.g., deactivating subscribers.

Expand All @@ -59,7 +69,7 @@ As an example, PID controllers export one virtual interface ``pid_reference`` an
Inner Resource Management
^^^^^^^^^^^^^^^^^^^^^^^^^^^^

After configuring a chainable controller, controller manager calls ``input_interface_configuration`` method and takes ownership over controller's input interfaces.
After configuring a chainable controller, controller manager calls ``export_reference_interfaces`` and ``export_state_interfaces`` method and takes ownership over controller's exported reference/state interfaces.
This is the same process as done by ``ResourceManager`` and hardware interfaces.
Controller manager maintains "claimed" status of interface in a vector (the same as done in ``ResourceManager``).

Expand All @@ -71,6 +81,8 @@ Chained controllers must be activated and deactivated together or in the proper
This means you must first activate all following controllers to have the preceding one activated.
For the deactivation there is the inverse rule - all preceding controllers have to be deactivated before the following controller is deactivated.
One can also think of it as an actual chain, you can not add a chain link or break the chain in the middle.
The chained controllers can also be activated when parsed as in a single list through the fields ``activate_controllers`` or ``deactivate_controllers`` in the ``switch_controllers`` service provided by the controller_manager.
The controller_manager ``spawner`` can also be used to activate all the controllers of the chain in a single call, by parsing the argument ``--activate-as-group``.


Debugging outputs
Expand All @@ -84,4 +96,4 @@ Debugging outputs
Closing remarks
----------------------------

- Maybe addition of the new controller's type ``ChainableController`` is not necessary. It would also be feasible to add implementation of ``input_interface_configuration()`` method into ``ControllerInterface`` class with default result ``interface_configuration_type::NONE``.
- Maybe addition of the new controller's type ``ChainableController`` is not necessary. It would also be feasible to add implementation of ``export_reference_interfaces()`` and ``export_state_interfaces()`` method into ``ControllerInterface`` class with default result ``interface_configuration_type::NONE``.
Binary file modified controller_manager/doc/images/chaining_example2.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
3 changes: 3 additions & 0 deletions doc/release_notes/Jazzy.rst
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,9 @@ For details see the controller_manager section.
* Pass URDF to controllers on init (`#1088 <https://github.com/ros-controls/ros2_control/pull/1088>`_).
* Pass controller manager update rate on the init of the controller interface (`#1141 <https://github.com/ros-controls/ros2_control/pull/1141>`_)
* A method to get node options to setup the controller node #api-breaking (`#1169 <https://github.com/ros-controls/ros2_control/pull/1169>`_)
* Export state interfaces from the chainable controller #api-breaking (`#1021 <https://github.com/ros-controls/ros2_control/pull/1021>`_)

* All chainable controllers must implement the method ``export_state_interfaces`` to export the state interfaces, similar to ``export_reference_interfaces`` method that is exporting the reference interfaces.

controller_manager
******************
Expand Down

0 comments on commit 96eced7

Please sign in to comment.