Skip to content

Commit

Permalink
Merge branch 'master' into add-checks-if-hw-initialized
Browse files Browse the repository at this point in the history
  • Loading branch information
bmagyar authored Jul 2, 2023
2 parents 04d6c1f + 185fbea commit 863cee9
Show file tree
Hide file tree
Showing 31 changed files with 375 additions and 112 deletions.
12 changes: 12 additions & 0 deletions .github/workflows/ci-check-docs.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
name: Check Docs

on:
workflow_dispatch:
pull_request:

jobs:
check-docs:
name: Check Docs
uses: ros-controls/control.ros.org/.github/workflows/reusable-sphinx-check-single-version.yml@master
with:
ROS2_CONTROL_PR: ${{ github.ref }}
3 changes: 3 additions & 0 deletions controller_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package controller_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.15.0 (2023-06-23)
-------------------

3.14.0 (2023-06-14)
-------------------
* Add -Wconversion flag to protect future developments (`#1053 <https://github.com/ros-controls/ros2_control/issues/1053>`_)
Expand Down
2 changes: 1 addition & 1 deletion controller_interface/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>controller_interface</name>
<version>3.14.0</version>
<version>3.15.0</version>
<description>Description of controller_interface</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
Expand Down
6 changes: 6 additions & 0 deletions controller_manager/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,12 @@
Changelog for package controller_manager
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.15.0 (2023-06-23)
-------------------
* Enable setting of initial state in HW compoments (`#1046 <https://github.com/ros-controls/ros2_control/issues/1046>`_)
* [CM] Improve output when using robot description topic and give output about correct topic even remapped. (`#1059 <https://github.com/ros-controls/ros2_control/issues/1059>`_)
* Contributors: Dr. Denis

3.14.0 (2023-06-14)
-------------------
* Add -Wconversion flag to protect future developments (`#1053 <https://github.com/ros-controls/ros2_control/issues/1053>`_)
Expand Down
119 changes: 119 additions & 0 deletions controller_manager/doc/controller_chaining.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,119 @@
:github_url: https://github.com/ros-controls/ros2_control/blob/{REPOS_FILE_BRANCH}/controller_manager/doc/controller_chaining.rst

.. _controller_chaining:

Controller Chaining / Cascade Control
======================================

This document proposes a minimal-viable-implementation of serial controller chaining as described in `Chaining Controllers design document <https://github.com/ros-controls/roadmap/blob/master/design_drafts/controller_chaining.md>`__.
Cascade control is a specific type of controller chaining.


Scope of the Document and Background Knowledge
-------------------------------------------------------

This approach focuses only on serial chaining of controllers and tries to reuse existing mechanisms for it.
It focuses on `inputs and outputs of a controller <https://github.com/ros-controls/roadmap/blob/master/design_drafts/controller_chaining.md#input--outputs-of-a-controller>`__ and their management in the controller manager.
The concept of `controller groups <https://github.com/ros-controls/roadmap/blob/master/design_drafts/controller_chaining.md#controller-group>`__ will be introduced only for clarity reasons, and its only meaning is that controllers in that group can be updated in arbitrary order.
This doesn't mean that the controller groups as described `in the controller chaining document <https://github.com/ros-controls/roadmap/blob/master/design_drafts/controller_chaining.md#controller-group>`__ will not be introduced and used in the future.
Nevertheless, the author is convinced that this would add only unnecessary complexity at this stage, although in the long term they *could* provide clearer structure and interfaces.

Motivation, Purpose and Use
---------------------------------

To describe the intent of this document, lets focus on the simple yet sufficient example `Example 2 from 'controllers_chaining' design docs <https://github.com/ros-controls/roadmap/blob/master/design_drafts/controller_chaining.md#example-2>`__:

.. image:: images/chaining_example2.png
:alt: Example2


In this example, we want to chain 'position_tracking' controller with 'diff_drive_controller' and two PID controllers.
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:

1. When a robot is started, we want to check if motor velocity control is working properly and therefore only PID controllers are activated.
At this stage we can control the input of PID controller also externally using topics.
However, these controllers also provide virtual interfaces, so we can chain them.
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.


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.

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.

As an example, PID controllers export one virtual interface ``pid_reference`` and stop their subscriber ``<controller_name>/pid_reference`` when used in chained mode. 'diff_drive_controller' controller exports list of virtual interfaces ``<controller_name>/v_x``, ``<controller_name>/v_y``, and ``<controller_name>/w_z``, and stops subscribers from topics ``<controller_name>/cmd_vel`` and ``<controller_name>/cmd_vel_unstamped``. Its publishers can continue running.

Inner Resource Management
^^^^^^^^^^^^^^^^^^^^^^^^^^^^

After configuring a chainable controller, controller manager calls ``input_interface_configuration`` method and takes ownership over controller's input 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``).

Activation and Deactivation Chained Controllers
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

Controller Manager has an additional parameter that describes how controllers are chained.
In the first version, the parameter-structure would have some semantic meaning embedded into it, as follows:


.. code-block:: yaml
controller_manager:
ros__parameters:
chained_controllers:
- parallel_group_1:
- controller1_1
- controller1_2
- parallel_group_2:
- controller2_1
- parallel_group_3:
- controller3_1
- controller3_2
- controller3_3
...
- parallel_group_N:
- controllerN_1
- ...
- controllerN_M
This structure is motivated by ``filter_chain`` structure from `ros/filters repository <https://github.com/ros/filters/tree/ros2>`__, see `this file for implementation <https://github.com/ros/filters/blob/ros2/include/filters/filter_chain.hpp>`__.

This structure is stored internally by controller manager into an ordered map (``std::map<std::string, std::vector<std::string>>``) with group name as key.
When a controller should be deactivated, the controller manager deactivates all the controllers in the preceding groups first.
All other controllers from the group stay active, as well as all controllers in the following groups.
NOTE: In the future this could be done more intelligently, i.e., deactivate only controllers in the preceding groups that actually precede the controller that should be deactivated.

On the other hand, the controller should be manually activated in the reverse order, i.e., from the those closer to the hardware toward those preceding them.


Debugging outputs
----------------------------

Flag ``unavailable`` on reference interface does not provide much information about anything at the moment. So don't get confused by it. The reason we have it are internal implementation reasons irelevant for the usage.


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``.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
28 changes: 17 additions & 11 deletions controller_manager/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -39,21 +39,27 @@ The limits will be applied after you log out and in again.
Parameters
-----------

activate_components_on_start (optional; list<string>; default: empty)
Define which hardware components should be activated when controller manager is started.
hardware_components_initial_state
Map of parameters for controlled lifecycle management of hardware components.
The names of the components are defined as attribute of ``<ros2_control>``-tag in ``robot_description``.
All other components will stay ``UNCONFIGURED``.
If this and ``configure_components_on_start`` are empty, all available components will be activated.
If this or ``configure_components_on_start`` are not empty, any component not in either list will be in unconfigured state.
Hardware components found in ``robot_description``, but without explicit state definition will be immediately activated.
Detailed explanation of each parameter is given below.
The full structure of the map is given in the following example:

.. code-block:: yaml
configure_components_on_start (optional; list<string>; default: empty)
Define which hardware components should be configured when controller manager is started.
The names of the components are defined as attribute of ``<ros2_control>``-tag in ``robot_description``.
All other components will stay ``UNCONFIGURED``.
If this and ``activate_components_on_start`` are empty, all available components will be activated.
If this or ``activate_components_on_start`` are not empty, any component not in either list will be in unconfigured state.
hardware_components_initial_state:
unconfigured:
- "arm1"
- "arm2"
inactive:
- "base3"
hardware_components_initial_state.unconfigured (optional; list<string>; default: empty)
Defines which hardware components will be only loaded immediately when controller manager is started.

hardware_components_initial_state.inactive (optional; list<string>; default: empty)
Defines which hardware components will be configured immediately when controller manager is started.

robot_description (mandatory; string)
String with the URDF string as robot description.
Expand Down
2 changes: 1 addition & 1 deletion controller_manager/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="2">
<name>controller_manager</name>
<version>3.14.0</version>
<version>3.15.0</version>
<description>Description of controller_manager</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
Expand Down
98 changes: 77 additions & 21 deletions controller_manager/src/controller_manager.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -245,46 +245,102 @@ void ControllerManager::init_resource_manager(const std::string & robot_descript
// TODO(destogl): manage this when there is an error - CM should not die because URDF is wrong...
resource_manager_->load_urdf(robot_description);

// Get all components and if they are not defined in parameters activate them automatically
auto components_to_activate = resource_manager_->get_components_status();

using lifecycle_msgs::msg::State;

auto set_components_to_state =
[&](const std::string & parameter_name, rclcpp_lifecycle::State state)
{
std::vector<std::string> components_to_set = std::vector<std::string>({});
if (get_parameter(parameter_name, components_to_set))
{
for (const auto & component : components_to_set)
{
if (component.empty())
{
continue;
}
if (components_to_activate.find(component) == components_to_activate.end())
{
RCLCPP_WARN(
get_logger(), "Hardware component '%s' is unknown, therefore not set in '%s' state.",
component.c_str(), state.label().c_str());
}
else
{
RCLCPP_INFO(
get_logger(), "Setting component '%s' to '%s' state.", component.c_str(),
state.label().c_str());
resource_manager_->set_component_state(component, state);
components_to_activate.erase(component);
}
}
}
};

// unconfigured (loaded only)
set_components_to_state(
"hardware_components_initial_state.unconfigured",
rclcpp_lifecycle::State(
State::PRIMARY_STATE_UNCONFIGURED, hardware_interface::lifecycle_state_names::UNCONFIGURED));

// inactive (configured)
// BEGIN: Keep old functionality on for backwards compatibility (Remove at the end of 2023)
std::vector<std::string> configure_components_on_start = std::vector<std::string>({});
if (get_parameter("configure_components_on_start", configure_components_on_start))
get_parameter("configure_components_on_start", configure_components_on_start);
if (!configure_components_on_start.empty())
{
RCLCPP_WARN(
get_logger(),
"[Deprecated]: Usage of parameter \"configure_components_on_start\" is deprecated. Use "
"hardware_spawner instead.");
rclcpp_lifecycle::State inactive_state(
State::PRIMARY_STATE_INACTIVE, hardware_interface::lifecycle_state_names::INACTIVE);
for (const auto & component : configure_components_on_start)
{
resource_manager_->set_component_state(component, inactive_state);
}
"Parameter 'configure_components_on_start' is deprecated. "
"Use 'hardware_interface_state_after_start.inactive' instead, to set component's initial "
"state to 'inactive'. Don't use this parameters in combination with the new "
"'hardware_interface_state_after_start' parameter structure.");
set_components_to_state(
"configure_components_on_start",
rclcpp_lifecycle::State(
State::PRIMARY_STATE_INACTIVE, hardware_interface::lifecycle_state_names::INACTIVE));
}
// END: Keep old functionality on humble backwards compatibility (Remove at the end of 2023)
else
{
set_components_to_state(
"hardware_components_initial_state.inactive",
rclcpp_lifecycle::State(
State::PRIMARY_STATE_INACTIVE, hardware_interface::lifecycle_state_names::INACTIVE));
}

// BEGIN: Keep old functionality on for backwards compatibility (Remove at the end of 2023)
std::vector<std::string> activate_components_on_start = std::vector<std::string>({});
if (get_parameter("activate_components_on_start", activate_components_on_start))
get_parameter("activate_components_on_start", activate_components_on_start);
rclcpp_lifecycle::State active_state(
State::PRIMARY_STATE_ACTIVE, hardware_interface::lifecycle_state_names::ACTIVE);
if (!activate_components_on_start.empty())
{
RCLCPP_WARN_STREAM(
RCLCPP_WARN(
get_logger(),
"[Deprecated]: Usage of parameter \"activate_components_on_start\" is deprecated. Use "
"hardware_spawner instead.");
"Parameter 'activate_components_on_start' is deprecated. "
"Components are activated per default. Don't use this parameters in combination with the new "
"'hardware_interface_state_after_start' parameter structure.");
rclcpp_lifecycle::State active_state(
State::PRIMARY_STATE_ACTIVE, hardware_interface::lifecycle_state_names::ACTIVE);
for (const auto & component : activate_components_on_start)
{
resource_manager_->set_component_state(component, active_state);
}
}
// if both parameter are empty or non-existing preserve behavior where all components are
// activated per default
if (configure_components_on_start.empty() && activate_components_on_start.empty())
// END: Keep old functionality on humble for backwards compatibility (Remove at the end of 2023)
else
{
RCLCPP_WARN_STREAM(
get_logger(),
"[Deprecated]: Automatic activation of all hardware components will not be supported in the "
"future anymore. Use hardware_spawner instead.");
resource_manager_->activate_all_components();
// activate all other components
for (const auto & [component, state] : components_to_activate)
{
rclcpp_lifecycle::State active_state(
State::PRIMARY_STATE_ACTIVE, hardware_interface::lifecycle_state_names::ACTIVE);
resource_manager_->set_component_state(component, active_state);
}
}
}

Expand Down
Loading

0 comments on commit 863cee9

Please sign in to comment.