Skip to content

Commit

Permalink
Merge branch 'master' into mock_sensor_commands
Browse files Browse the repository at this point in the history
  • Loading branch information
bmagyar authored Sep 28, 2022
2 parents b88528d + 81b8df6 commit cc40fdc
Show file tree
Hide file tree
Showing 57 changed files with 2,307 additions and 382 deletions.
8 changes: 1 addition & 7 deletions .github/reviewer-lottery.yml
Original file line number Diff line number Diff line change
Expand Up @@ -14,29 +14,23 @@ groups:
reviewers: 5
usernames:
- rosterloh
- kellyprankin
- progtologist
- arne48
- DasRoteSkelett
- a10263790
- Serafadam
- harderthan
- jaron-l
- malapatiravi
- erickisos
- Briancbn
- TomoyaFujita2016
- homalozoa
- erickisos
- anfemosa
- jackcenter
- VX792
- mhubii
- livanov93
- aprotyas
- peterdavidfagan
- UsamaHamayun1
- duringhof
- bijoua29
- kasiceo
- lm2292
- mcbed
2 changes: 1 addition & 1 deletion .github/workflows/galactic-rhel-binary-build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ jobs:
runs-on: ubuntu-latest
env:
ROS_DISTRO: galactic
container: jaronl/ros:galactic-alma
container: ghcr.io/ros-controls/ros:${{ env.ROS_DISTRO }}-rhel
steps:
- uses: actions/checkout@v3
with:
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/humble-rhel-binary-build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ jobs:
runs-on: ubuntu-latest
env:
ROS_DISTRO: humble
container: jaronl/ros:humble-alma
container: ghcr.io/ros-controls/ros:${{ env.ROS_DISTRO }}-rhel
steps:
- uses: actions/checkout@v3
with:
Expand Down
2 changes: 1 addition & 1 deletion .github/workflows/rolling-rhel-binary-build.yml
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ jobs:
runs-on: ubuntu-latest
env:
ROS_DISTRO: rolling
container: jaronl/ros:rolling-alma
container: ghcr.io/ros-controls/ros:${{ env.ROS_DISTRO }}-rhel
steps:
- uses: actions/checkout@v3
with:
Expand Down
16 changes: 16 additions & 0 deletions controller_interface/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,22 @@
Changelog for package controller_interface
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

3.0.0 (2022-09-19)
------------------

2.15.0 (2022-09-19)
-------------------
* Remove autodeclare of parameters for controllers. (`#757 <https://github.com/ros-controls/ros2_control/issues/757>`_)
* Contributors: Denis Štogl

2.14.0 (2022-09-04)
-------------------
* Add doxygen comments (`#777 <https://github.com/ros-controls/ros2_control/issues/777>`_)
* Contributors: Bence Magyar, Denis Štogl

2.13.0 (2022-08-03)
-------------------

2.12.1 (2022-07-14)
-------------------

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,6 +40,14 @@ class ChainableControllerInterface : public ControllerInterfaceBase
CONTROLLER_INTERFACE_PUBLIC
virtual ~ChainableControllerInterface() = default;

/**
* Control step update. Command interfaces are updated based on on reference inputs and current states.
* **The method called in the (real-time) control loop.**
*
* \param[in] time The time at the start of this control loop iteration
* \param[in] period The measured time taken by the last control loop iteration
* \returns return_type::OK if update is successfully, otherwise return_type::ERROR.
*/
CONTROLLER_INTERFACE_PUBLIC
return_type update(const rclcpp::Time & time, const rclcpp::Duration & period) final;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,9 +72,37 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
CONTROLLER_INTERFACE_PUBLIC
virtual ~ControllerInterfaceBase() = default;

/// Get configuration for controller's required command interfaces.
/**
* Method used by the controller_manager to get the set of command interfaces used by the controller.
* Each controller can use individual method to determine interface names that in simples case
* have the following format: `<joint>/<interface>`.
* The method is called only in `inactive` or `active` state, i.e., `on_configure` has to be
* called first.
* The configuration is used to check if controller can be activated and to claim interfaces from
* hardware.
* The claimed interfaces are populated in the
* \ref ControllerInterfaceBase::command_interfaces_ "command_interfaces_" member.
*
* \returns configuration of command interfaces.
*/
CONTROLLER_INTERFACE_PUBLIC
virtual InterfaceConfiguration command_interface_configuration() const = 0;

/// Get configuration for controller's required state interfaces.
/**
* Method used by the controller_manager to get the set of state interface used by the controller.
* Each controller can use individual method to determine interface names that in simples case
* have the following format: `<joint>/<interface>`.
* The method is called only in `inactive` or `active` state, i.e., `on_configure` has to be
* called first.
* The configuration is used to check if controller can be activated and to claim interfaces from
* hardware.
* The claimed interfaces are populated in the
* \ref ControllerInterfaceBase::state_interface_ "state_interface_" member.
*
* \returns configuration of state interfaces.
*/
CONTROLLER_INTERFACE_PUBLIC
virtual InterfaceConfiguration state_interface_configuration() const = 0;

Expand All @@ -89,10 +117,7 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
CONTROLLER_INTERFACE_PUBLIC
virtual return_type init(
const std::string & controller_name, const std::string & namespace_ = "",
const rclcpp::NodeOptions & node_options =
rclcpp::NodeOptions()
.allow_undeclared_parameters(true)
.automatically_declare_parameters_from_overrides(true));
const rclcpp::NodeOptions & node_options = rclcpp::NodeOptions());

/// Custom configure method to read additional parameters for controller-nodes
/*
Expand All @@ -105,6 +130,14 @@ class ControllerInterfaceBase : public rclcpp_lifecycle::node_interfaces::Lifecy
CONTROLLER_INTERFACE_PUBLIC
virtual CallbackReturn on_init() = 0;

/**
* Control step update. Command interfaces are updated based on on reference inputs and current states.
* **The method called in the (real-time) control loop.**
*
* \param[in] time The time at the start of this control loop iteration
* \param[in] period The measured time taken by the last control loop iteration
* \returns return_type::OK if update is successfully, otherwise return_type::ERROR.
*/
CONTROLLER_INTERFACE_PUBLIC
virtual return_type update(const rclcpp::Time & time, const rclcpp::Duration & period) = 0;

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

3.0.0 (2022-09-19)
------------------

2.15.0 (2022-09-19)
-------------------

2.14.0 (2022-09-04)
-------------------
* Add doxygen comments (`#777 <https://github.com/ros-controls/ros2_control/issues/777>`_)
* Contributors: Bence Magyar, Denis Štogl

2.13.0 (2022-08-03)
-------------------
* Clang tidy: delete a redundant return (`#790 <https://github.com/ros-controls/ros2_control/issues/790>`_)
* Add chained controllers information in list controllers service #abi-braking (`#758 <https://github.com/ros-controls/ros2_control/issues/758>`_)
* add chained controllers in ros2controlcli
* remove controller_group from service
* added comments to ControllerState message
* added comments to ChainedConnection message
* spawner.py: Fix python logging on deprecation warning (`#787 <https://github.com/ros-controls/ros2_control/issues/787>`_)
* Add documentation for realtime permission (`#781 <https://github.com/ros-controls/ros2_control/issues/781>`_)
* Fix bug in spawner with getter for node's logger (`#776 <https://github.com/ros-controls/ros2_control/issues/776>`_)
* Contributors: Andy Zelenak, Felix Exner, Paul Gesel, Bijou Abraham

2.12.1 (2022-07-14)
-------------------
* Rename CM members from start/stop to activate/deactivate nomenclature. (`#756 <https://github.com/ros-controls/ros2_control/issues/756>`_)
Expand Down
10 changes: 9 additions & 1 deletion controller_manager/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -102,6 +102,14 @@ if(BUILD_TESTING)
target_link_libraries(test_controller_manager_with_namespace.cpp ${PROJECT_NAME} test_controller)
ament_target_dependencies(test_controller_manager_with_namespace.cpp ros2_control_test_assets)

ament_add_gmock(
test_controller_manager_hardware_error_handling
test/test_controller_manager_hardware_error_handling.cpp
)
target_include_directories(test_controller_manager_hardware_error_handling PRIVATE include)
target_link_libraries(test_controller_manager_hardware_error_handling ${PROJECT_NAME} test_controller)
ament_target_dependencies(test_controller_manager_hardware_error_handling ros2_control_test_assets)

ament_add_gmock(
test_load_controller
test/test_load_controller.cpp
Expand All @@ -125,7 +133,7 @@ if(BUILD_TESTING)
APPEND_ENV AMENT_PREFIX_PATH=${ament_index_build_path}_$<CONFIG>
)
target_include_directories(test_controller_manager_srvs PRIVATE include)
target_link_libraries(test_controller_manager_srvs ${PROJECT_NAME} test_controller)
target_link_libraries(test_controller_manager_srvs ${PROJECT_NAME} test_controller test_chainable_controller)
ament_target_dependencies(
test_controller_manager_srvs
controller_manager_msgs
Expand Down
17 changes: 10 additions & 7 deletions controller_manager/controller_manager/spawner.py
Original file line number Diff line number Diff line change
Expand Up @@ -112,10 +112,6 @@ def is_controller_loaded(node, controller_manager, controller_name):
return any(c.name == controller_name for c in controllers)


def make_absolute(name):
return name if name.startswith('/') else ('/' + name)


def main(args=None):

rclpy.init(args=args, signal_handler_options=SignalHandlerOptions.NO)
Expand All @@ -124,7 +120,7 @@ def main(args=None):
'controller_name', help='Name of the controller')
parser.add_argument(
'-c', '--controller-manager', help='Name of the controller manager ROS node',
default='/controller_manager', required=False)
default='controller_manager', required=False)
parser.add_argument(
'-p', '--param-file',
help='Controller param file to be loaded into controller node before configure',
Expand Down Expand Up @@ -153,7 +149,7 @@ def main(args=None):
command_line_args = rclpy.utilities.remove_ros_args(args=sys.argv)[1:]
args = parser.parse_args(command_line_args)
controller_name = args.controller_name
controller_manager_name = make_absolute(args.controller_manager)
controller_manager_name = args.controller_manager
param_file = args.param_file
controller_type = args.controller_type
controller_manager_timeout = args.controller_manager_timeout
Expand All @@ -162,6 +158,13 @@ def main(args=None):
raise FileNotFoundError(errno.ENOENT, os.strerror(errno.ENOENT), param_file)

node = Node('spawner_' + controller_name)
if not controller_manager_name.startswith('/'):
spawner_namespace = node.get_namespace()
if spawner_namespace != '/':
controller_manager_name = f"{spawner_namespace}/{controller_manager_name}"
else:
controller_manager_name = f"/{controller_manager_name}"

try:
if not wait_for_controller_manager(node, controller_manager_name,
controller_manager_timeout):
Expand Down Expand Up @@ -239,7 +242,7 @@ def main(args=None):
node.get_logger().info('Deactivated controller')

elif args.stopped:
node.get_logger.warn('"--stopped" flag is deprecated use "--inactive" instead')
node.get_logger().warn('"--stopped" flag is deprecated use "--inactive" instead')

ret = unload_controller(
node, controller_manager_name, controller_name)
Expand Down
26 changes: 23 additions & 3 deletions controller_manager/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -10,9 +10,29 @@ Determinism

For best performance when controlling hardware you want the controller manager to have as little jitter as possible in the main control loop.
The normal linux kernel is optimized for computational throughput and therefore is not well suited for hardware control.
The main thread of Controller Manager attempts to configure ``SCHED_FIFO`` with a priority of ``50``.
To enable this functionality install a RT kernel and run the Controller Manager with permissions to make syscalls to set its thread priorities.
The two easiest options for this are using the [Real-time Ubuntu 22.04 LTS Beta](https://ubuntu.com/blog/real-time-ubuntu-released) or [linux-image-rt-amd64](https://packages.debian.org/bullseye/linux-image-rt-amd64) on Debian Bullseye.
The two easiest kernel options are the `Real-time Ubuntu 22.04 LTS Beta <https://ubuntu.com/blog/real-time-ubuntu-released>`_ or `linux-image-rt-amd64 <https://packages.debian.org/bullseye/linux-image-rt-amd64>`_ on Debian Bullseye.

If you have a realtime kernel installed, the main thread of Controller Manager attempts to configure ``SCHED_FIFO`` with a priority of ``50``.
By default, the user does not have permission to set such a high priority.
To give the user such permissions, add a group named realtime and add the user controlling your robot to this group:

.. code-block:: console
$ sudo addgroup realtime
$ sudo usermod -a -G realtime $(whoami)
Afterwards, add the following limits to the realtime group in ``/etc/security/limits.conf``:

.. code-block:: console
@realtime soft rtprio 99
@realtime soft priority 99
@realtime soft memlock 102400
@realtime hard rtprio 99
@realtime hard priority 99
@realtime hard memlock 102400
The limits will be applied after you log out and in again.

Parameters
-----------
Expand Down
Loading

0 comments on commit cc40fdc

Please sign in to comment.