Skip to content

Commit

Permalink
Merge branch 'master' into set_chained_controller_interfaces_as_avail…
Browse files Browse the repository at this point in the history
…able
  • Loading branch information
bmagyar authored Aug 26, 2023
2 parents 9191939 + c122455 commit 888ab07
Show file tree
Hide file tree
Showing 24 changed files with 111 additions and 51 deletions.
5 changes: 5 additions & 0 deletions controller_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,11 @@
Changelog for package controller_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.18.0 (2023-08-17)
-------------------
* add a broadcaster for range sensor (`#1091 <https://github.com/ros-controls/ros2_control/issues/1091>`_)
* Contributors: flochre

3.17.0 (2023-08-07)
-------------------

Expand Down
60 changes: 60 additions & 0 deletions controller_interface/include/semantic_components/range_sensor.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,60 @@
// Copyright 2023 flochre
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef SEMANTIC_COMPONENTS__RANGE_SENSOR_HPP_
#define SEMANTIC_COMPONENTS__RANGE_SENSOR_HPP_

#include <limits>
#include <string>
#include <vector>

#include "semantic_components/semantic_component_interface.hpp"
#include "sensor_msgs/msg/range.hpp"

namespace semantic_components
{
class RangeSensor : public SemanticComponentInterface<sensor_msgs::msg::Range>
{
public:
explicit RangeSensor(const std::string & name) : SemanticComponentInterface(name, 1)
{
interface_names_.emplace_back(name_ + "/" + "range");
}

virtual ~RangeSensor() = default;

/**
* Return Range reported by a sensor
*
* \return value of the range in meters
*/
float get_range() { return state_interfaces_[0].get().get_value(); }

/// Return Range message with range in meters
/**
* Constructs and return a Range message from the current values.
* \return Range message from values;
*/
bool get_values_as_message(sensor_msgs::msg::Range & message)
{
// update the message values
message.range = get_range();

return true;
}
};

} // namespace semantic_components

#endif // SEMANTIC_COMPONENTS__RANGE_SENSOR_HPP_
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.17.0</version>
<version>3.18.0</version>
<description>Description of controller_interface</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
Expand Down
5 changes: 5 additions & 0 deletions controller_manager/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,11 @@
Changelog for package controller_manager
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.18.0 (2023-08-17)
-------------------
* Controller sorting and proper execution in a chain (Fixes `#853 <https://github.com/ros-controls/ros2_control/issues/853>`_) (`#1063 <https://github.com/ros-controls/ros2_control/issues/1063>`_)
* Contributors: Sai Kishor Kothakota, Christoph Fröhlich, Dr Denis, Bence Magyar

3.17.0 (2023-08-07)
-------------------
* [CM] Fixes the issue with individual controller's update rate (`#1082 <https://github.com/ros-controls/ros2_control/issues/1082>`_)
Expand Down
44 changes: 5 additions & 39 deletions controller_manager/doc/controller_chaining.rst
Original file line number Diff line number Diff line change
Expand Up @@ -63,48 +63,14 @@ After configuring a chainable controller, controller manager calls ``input_inter
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.
Chained controllers must be activated and deactivated together or in the proper order.
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.


Debugging outputs
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.17.0</version>
<version>3.18.0</version>
<description>Description of controller_manager</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
Expand Down
3 changes: 3 additions & 0 deletions controller_manager_msgs/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package controller_manager_msgs
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.18.0 (2023-08-17)
-------------------

3.17.0 (2023-08-07)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion controller_manager_msgs/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_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>controller_manager_msgs</name>
<version>3.17.0</version>
<version>3.18.0</version>
<description>Messages and services for the controller manager.</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
Expand Down
3 changes: 3 additions & 0 deletions hardware_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package hardware_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.18.0 (2023-08-17)
-------------------

3.17.0 (2023-08-07)
-------------------
* Add checks if hardware is initialized. (`#1054 <https://github.com/ros-controls/ros2_control/issues/1054>`_)
Expand Down
2 changes: 1 addition & 1 deletion hardware_interface/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="2">
<name>hardware_interface</name>
<version>3.17.0</version>
<version>3.18.0</version>
<description>ros2_control hardware interface</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
Expand Down
3 changes: 3 additions & 0 deletions joint_limits/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package joint_limits
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.18.0 (2023-08-17)
-------------------

3.17.0 (2023-08-07)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion joint_limits/package.xml
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
<package format="3">
<name>joint_limits</name>
<version>3.17.0</version>
<version>3.18.0</version>
<description>Interfaces for handling of joint limits for controllers or hardware.</description>

<maintainer email="[email protected]">Bence Magyar</maintainer>
Expand Down
3 changes: 3 additions & 0 deletions ros2_control/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package ros2_control
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.18.0 (2023-08-17)
-------------------

3.17.0 (2023-08-07)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion ros2_control/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package format="3">
<name>ros2_control</name>
<version>3.17.0</version>
<version>3.18.0</version>
<description>Metapackage for ROS2 control related packages</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
Expand Down
3 changes: 3 additions & 0 deletions ros2_control_test_assets/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package ros2_control_test_assets
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.18.0 (2023-08-17)
-------------------

3.17.0 (2023-08-07)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion ros2_control_test_assets/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_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>ros2_control_test_assets</name>
<version>3.17.0</version>
<version>3.18.0</version>
<description>The package provides shared test resources for ros2_control stack
</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
Expand Down
3 changes: 3 additions & 0 deletions ros2controlcli/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package ros2controlcli
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.18.0 (2023-08-17)
-------------------

3.17.0 (2023-08-07)
-------------------
* Add info where the pdf is saved to view_controller_chains (`#1094 <https://github.com/ros-controls/ros2_control/issues/1094>`_)
Expand Down
2 changes: 1 addition & 1 deletion ros2controlcli/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>ros2controlcli</name>
<version>3.17.0</version>
<version>3.18.0</version>
<description>
The ROS 2 command line tools for ROS2 Control.
</description>
Expand Down
2 changes: 1 addition & 1 deletion ros2controlcli/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

setup(
name=package_name,
version="3.17.0",
version="3.18.0",
packages=find_packages(exclude=["test"]),
data_files=[
("share/" + package_name, ["package.xml"]),
Expand Down
3 changes: 3 additions & 0 deletions rqt_controller_manager/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package rqt_controller_manager
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.18.0 (2023-08-17)
-------------------

3.17.0 (2023-08-07)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion rqt_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_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>rqt_controller_manager</name>
<version>3.17.0</version>
<version>3.18.0</version>
<description>Graphical frontend for interacting with the controller manager.</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
Expand Down
2 changes: 1 addition & 1 deletion rqt_controller_manager/setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@

setup(
name=package_name,
version="3.17.0",
version="3.18.0",
packages=[package_name],
data_files=[
("share/ament_index/resource_index/packages", ["resource/" + package_name]),
Expand Down
3 changes: 3 additions & 0 deletions transmission_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,9 @@
Changelog for package transmission_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.18.0 (2023-08-17)
-------------------

3.17.0 (2023-08-07)
-------------------

Expand Down
2 changes: 1 addition & 1 deletion transmission_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_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>transmission_interface</name>
<version>3.17.0</version>
<version>3.18.0</version>
<description>transmission_interface contains data structures for representing mechanical transmissions, methods for propagating values between actuator and joint spaces and tooling to support this.</description>
<maintainer email="[email protected]">Bence Magyar</maintainer>
<maintainer email="[email protected]">Denis Štogl</maintainer>
Expand Down

0 comments on commit 888ab07

Please sign in to comment.