Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -38,17 +38,30 @@
from ros2param.api import call_set_parameters


# from https://stackoverflow.com/a/287944
import os
import sys


def _color_enabled():
"""Respect RCUTILS_COLORIZED_OUTPUT: 0=off, 1=on, unset=auto-detect TTY."""
env = os.getenv("RCUTILS_COLORIZED_OUTPUT")
if env == "0":
return False
if env == "1":
return True
return sys.stdout.isatty()


class bcolors:
MAGENTA = "\033[95m"
OKBLUE = "\033[94m"
OKCYAN = "\033[96m"
OKGREEN = "\033[92m"
WARNING = "\033[93m"
FAIL = "\033[91m"
ENDC = "\033[0m"
BOLD = "\033[1m"
UNDERLINE = "\033[4m"
MAGENTA = "\033[95m" if _color_enabled() else ""
OKBLUE = "\033[94m" if _color_enabled() else ""
OKCYAN = "\033[96m" if _color_enabled() else ""
OKGREEN = "\033[92m" if _color_enabled() else ""
WARNING = "\033[93m" if _color_enabled() else ""
FAIL = "\033[91m" if _color_enabled() else ""
ENDC = "\033[0m" if _color_enabled() else ""
BOLD = "\033[1m" if _color_enabled() else ""
UNDERLINE = "\033[4m" if _color_enabled() else ""


class ServiceNotFoundError(Exception):
Expand Down
14 changes: 10 additions & 4 deletions controller_manager/controller_manager/hardware_spawner.py
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,8 @@
from controller_manager import (
list_hardware_components,
set_hardware_component_state,
bcolors,
)
from controller_manager.controller_manager_services import ServiceNotFoundError
from controller_manager.controller_manager_services import ServiceNotFoundError, bcolors

from lifecycle_msgs.msg import State
import rclpy
Expand Down Expand Up @@ -93,7 +92,11 @@ def configure_component(node, controller_manager_name, component_to_configure):
inactive_state.id = State.PRIMARY_STATE_INACTIVE
inactive_state.label = "inactive"
handle_set_component_state_service_call(
node, controller_manager_name, component_to_configure, inactive_state, "configured"
node,
controller_manager_name,
component_to_configure,
inactive_state,
"configured",
)


Expand Down Expand Up @@ -154,7 +157,10 @@ def main(args=None):
try:
for hardware_component in hardware_components:
if not is_hardware_component_loaded(
node, controller_manager_name, hardware_component, controller_manager_timeout
node,
controller_manager_name,
hardware_component,
controller_manager_timeout,
):
node.get_logger().warning(
f"{bcolors.WARNING}Hardware Component is not loaded - state can not be changed.{bcolors.ENDC}"
Expand Down
6 changes: 3 additions & 3 deletions controller_manager/controller_manager/spawner.py
Original file line number Diff line number Diff line change
Expand Up @@ -28,10 +28,9 @@
unload_controller,
set_controller_parameters,
set_controller_parameters_from_param_files,
bcolors,
)
from controller_manager_msgs.srv import SwitchController
from controller_manager.controller_manager_services import ServiceNotFoundError
from controller_manager.controller_manager_services import ServiceNotFoundError, bcolors

from filelock import Timeout, FileLock
import rclpy
Expand All @@ -51,7 +50,8 @@ def combine_name_and_namespace(name_and_namespace):
def find_node_and_namespace(node, full_node_name):
node_names_and_namespaces = node.get_node_names_and_namespaces()
return first_match(
node_names_and_namespaces, lambda n: combine_name_and_namespace(n) == full_node_name
node_names_and_namespaces,
lambda n: combine_name_and_namespace(n) == full_node_name,
)


Expand Down
11 changes: 11 additions & 0 deletions controller_manager/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -494,3 +494,14 @@ The ``time`` argument in the ``read`` and ``write`` methods of the hardware comp
The ``period`` argument in the ``read``, ``update`` and ``write`` methods is calculated using the trigger clock of type ``RCL_STEADY_TIME`` so it is always monotonic.

The reason behind using different clocks is to avoid the issues related to the affect of system time changes in the realtime loops. The ``ros2_control_node`` now also detects the overruns caused by the system time changes and longer execution times of the controllers and hardware components. The controller manager will print a warning message if the controller or hardware component misses the update cycle due to the system time changes or longer execution times.

Color Output Handling
^^^^^^^^^^^^^^^^^^^^^

The helper scripts (``spawner`` and ``hardware_spawner``) now use an environment-aware ``bcolors`` class.
The color output automatically adapts to the environment:

* ``RCUTILS_COLORIZED_OUTPUT=0`` -> disables color output
* ``RCUTILS_COLORIZED_OUTPUT=1`` -> forces color output
* Unset -> automatically detects TTY and enables color only in interactive
terminals
3 changes: 3 additions & 0 deletions doc/release_notes.rst
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,8 @@ controller_manager
* The controller manager now supports switching (activating and deactivating) controllers in both realtime and non-realtime modes. This is controlled by the parameter ``activate_asap`` of the ``switch_controllers`` service (`#2452 <https://github.com/ros-controls/ros2_control/pull/2453>`_).
* The spawner now supports two new arguments ``--switch-asap`` and ``--no-switch-asap`` to control the behaviour of the spawner when switching controllers to be in realtime loop (or) non-realtime loop. By default, it is set to ``--no-switch-asap`` because when activating multiple controllers at same time might affect the realtime loop performance (`#2452 <https://github.com/ros-controls/ros2_control/pull/2453>`_).
* New parameters ``overruns.manage`` and ``overruns.print_warnings`` were added to control the behavior of the controller manager/ros2_control_node when overruns occur (`#2546 <https://github.com/ros-controls/ros2_control/pull/2546/files>`_).
* The ``bcolors`` class now respects the ``RCUTILS_COLORIZED_OUTPUT`` environment
variable to automatically disable colors in non-TTY and CI environments.


hardware_interface
Expand All @@ -32,6 +34,7 @@ ros2controlcli
**************
* The CLI verbs ``list_hardware_components`` and ``list_hardware_interfaces`` will now show the data type used by the internal Command and State interfaces (`#2204 <https://github.com/ros-controls/ros2_control/pull/2204>`_).


transmission_interface
**********************
* The ``simple_transmission`` and ``differential_transmission`` now also support the ``force`` interface (`#2588 <https://github.com/ros-controls/ros2_control/pull/2588>`_).