From 591b06cdd2c949bc0ce82680d9025261634762fb Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Christoph=20Fr=C3=B6hlich?= Date: Mon, 11 Mar 2024 19:27:56 +0100 Subject: [PATCH] Codeformat from new pre-commit config (#1433) --- .../test/test_controller_manager_srvs.cpp | 12 ++--- .../test/test_spawner_unspawner.cpp | 3 +- .../test_force_torque_sensor.cpp | 3 +- .../include/joint_limits/joint_limits.hpp | 9 ++-- .../controller_manager.py | 46 +++++++------------ 5 files changed, 26 insertions(+), 47 deletions(-) diff --git a/controller_manager/test/test_controller_manager_srvs.cpp b/controller_manager/test/test_controller_manager_srvs.cpp index 1895cf588d..f42c155e6d 100644 --- a/controller_manager/test/test_controller_manager_srvs.cpp +++ b/controller_manager/test/test_controller_manager_srvs.cpp @@ -832,8 +832,7 @@ TEST_F(TestControllerManagerSrvs, list_sorted_complex_chained_controllers) auto get_ctrl_pos = [result](const std::string & controller_name) -> int64_t { auto it = std::find_if( - result->controller.begin(), result->controller.end(), - [controller_name](auto itf) + result->controller.begin(), result->controller.end(), [controller_name](auto itf) { return (itf.name.find(controller_name) != std::string::npos); }); return std::distance(result->controller.begin(), it); }; @@ -1044,8 +1043,7 @@ TEST_F(TestControllerManagerSrvs, list_sorted_independent_chained_controllers) auto get_ctrl_pos = [result](const std::string & controller_name) -> int64_t { auto it = std::find_if( - result->controller.begin(), result->controller.end(), - [controller_name](auto itf) + result->controller.begin(), result->controller.end(), [controller_name](auto itf) { return (itf.name.find(controller_name) != std::string::npos); }); return std::distance(result->controller.begin(), it); }; @@ -1321,8 +1319,7 @@ TEST_F(TestControllerManagerSrvs, list_large_number_of_controllers_with_chains) auto get_ctrl_pos = [result](const std::string & controller_name) -> int64_t { auto it = std::find_if( - result->controller.begin(), result->controller.end(), - [controller_name](auto itf) + result->controller.begin(), result->controller.end(), [controller_name](auto itf) { return (itf.name.find(controller_name) != std::string::npos); }); return std::distance(result->controller.begin(), it); }; @@ -1546,8 +1543,7 @@ TEST_F(TestControllerManagerSrvs, list_sorted_large_chained_controller_tree) auto get_ctrl_pos = [result](const std::string & controller_name) -> int64_t { auto it = std::find_if( - result->controller.begin(), result->controller.end(), - [controller_name](auto itf) + result->controller.begin(), result->controller.end(), [controller_name](auto itf) { return (itf.name.find(controller_name) != std::string::npos); }); return std::distance(result->controller.begin(), it); }; diff --git a/controller_manager/test/test_spawner_unspawner.cpp b/controller_manager/test/test_spawner_unspawner.cpp index 1ecc3164b8..3b774035aa 100644 --- a/controller_manager/test/test_spawner_unspawner.cpp +++ b/controller_manager/test/test_spawner_unspawner.cpp @@ -264,8 +264,7 @@ TEST_F(TestLoadController, unload_on_kill) // Launch spawner with unload on kill // timeout command will kill it after the specified time with signal SIGINT std::stringstream ss; - ss << "timeout --signal=INT 5 " - << "ros2 run controller_manager spawner " + ss << "timeout --signal=INT 5 " << "ros2 run controller_manager spawner " << "ctrl_3 -c test_controller_manager -t " << std::string(test_controller::TEST_CONTROLLER_CLASS_NAME) << " --unload-on-kill"; diff --git a/hardware_interface/test/test_hardware_components/test_force_torque_sensor.cpp b/hardware_interface/test/test_hardware_components/test_force_torque_sensor.cpp index d226e08fd9..47b19f9769 100644 --- a/hardware_interface/test/test_hardware_components/test_force_torque_sensor.cpp +++ b/hardware_interface/test/test_hardware_components/test_force_torque_sensor.cpp @@ -43,8 +43,7 @@ class TestForceTorqueSensor : public SensorInterface { if ( std::find_if( - state_interfaces.begin(), state_interfaces.end(), - [&ft_key](const auto & interface_info) + state_interfaces.begin(), state_interfaces.end(), [&ft_key](const auto & interface_info) { return interface_info.name == ft_key; }) == state_interfaces.end()) { return CallbackReturn::ERROR; diff --git a/joint_limits/include/joint_limits/joint_limits.hpp b/joint_limits/include/joint_limits/joint_limits.hpp index 809bfd777b..f9944a85b1 100644 --- a/joint_limits/include/joint_limits/joint_limits.hpp +++ b/joint_limits/include/joint_limits/joint_limits.hpp @@ -128,14 +128,11 @@ struct SoftJointLimits { std::stringstream ss_output; - ss_output << " soft position limits: " - << "[" << min_position << ", " << max_position << "]\n"; + ss_output << " soft position limits: " << "[" << min_position << ", " << max_position << "]\n"; - ss_output << " k-position: " - << "[" << k_position << "]\n"; + ss_output << " k-position: " << "[" << k_position << "]\n"; - ss_output << " k-velocity: " - << "[" << k_velocity << "]\n"; + ss_output << " k-velocity: " << "[" << k_velocity << "]\n"; return ss_output.str(); } diff --git a/rqt_controller_manager/rqt_controller_manager/controller_manager.py b/rqt_controller_manager/rqt_controller_manager/controller_manager.py index b69b4449f8..371eefd845 100644 --- a/rqt_controller_manager/rqt_controller_manager/controller_manager.py +++ b/rqt_controller_manager/rqt_controller_manager/controller_manager.py @@ -60,8 +60,7 @@ def __init__(self, context): # Pop-up that displays controller information self._popup_widget = QWidget() ui_file = os.path.join( - get_package_share_directory( - "rqt_controller_manager"), "resource", "controller_info.ui" + get_package_share_directory("rqt_controller_manager"), "resource", "controller_info.ui" ) loadUi(ui_file, self._popup_widget) self._popup_widget.setObjectName("ControllerInfoUi") @@ -72,8 +71,7 @@ def __init__(self, context): # plugin at once, these lines add number to make it easy to # tell from pane to pane. if context.serial_number() > 1: - self._widget.setWindowTitle( - f"{self._widget.windowTitle()} {context.serial_number()}") + self._widget.setWindowTitle(f"{self._widget.windowTitle()} {context.serial_number()}") # Add widget to the user interface context.add_widget(self._widget) @@ -108,15 +106,13 @@ def __init__(self, context): # Timer for controller manager updates self._update_cm_list_timer = QTimer(self) - self._update_cm_list_timer.setInterval( - int(1000.0 / self._cm_update_freq)) + self._update_cm_list_timer.setInterval(int(1000.0 / self._cm_update_freq)) self._update_cm_list_timer.timeout.connect(self._update_cm_list) self._update_cm_list_timer.start() # Timer for running controller updates self._update_ctrl_list_timer = QTimer(self) - self._update_ctrl_list_timer.setInterval( - int(1000.0 / self._cm_update_freq)) + self._update_ctrl_list_timer.setInterval(int(1000.0 / self._cm_update_freq)) self._update_ctrl_list_timer.timeout.connect(self._update_controllers) self._update_ctrl_list_timer.start() @@ -145,8 +141,7 @@ def restore_settings(self, plugin_settings, instance_settings): pass def _update_cm_list(self): - update_combo(self._widget.cm_combo, - _list_controller_managers(self._node)) + update_combo(self._widget.cm_combo, _list_controller_managers(self._node)) def _on_cm_change(self, cm_name): self._cm_name = cm_name @@ -186,8 +181,7 @@ def _list_controllers(self): for name in _get_parameter_controller_names(self._node, self._cm_name): add_ctrl = all(name != ctrl.name for ctrl in controllers) if add_ctrl: - type_str = _get_controller_type( - self._node, self._cm_name, name) + type_str = _get_controller_type(self._node, self._cm_name, name) uninit_ctrl = ControllerState(name=name, type=type_str) controllers.append(uninit_ctrl) return controllers @@ -211,26 +205,19 @@ def _on_ctrl_menu(self, pos): # Show context menu menu = QMenu(self._widget.table_view) if ctrl.state == "active": - action_deactivate = menu.addAction( - self._icons["inactive"], "Deactivate") - action_kill = menu.addAction( - self._icons["finalized"], "Deactivate and Unload") + action_deactivate = menu.addAction(self._icons["inactive"], "Deactivate") + action_kill = menu.addAction(self._icons["finalized"], "Deactivate and Unload") elif ctrl.state == "inactive": action_activate = menu.addAction(self._icons["active"], "Activate") - action_unload = menu.addAction( - self._icons["unconfigured"], "Unload") + action_unload = menu.addAction(self._icons["unconfigured"], "Unload") elif ctrl.state == "unconfigured": - action_configure = menu.addAction( - self._icons["inactive"], "Configure") - action_spawn = menu.addAction( - self._icons["active"], "Configure and Activate") + action_configure = menu.addAction(self._icons["inactive"], "Configure") + action_spawn = menu.addAction(self._icons["active"], "Configure and Activate") else: # Controller isn't loaded action_load = menu.addAction(self._icons["unconfigured"], "Load") - action_configure = menu.addAction( - self._icons["inactive"], "Load and Configure") - action_activate = menu.addAction( - self._icons["active"], "Load, Configure and Activate") + action_configure = menu.addAction(self._icons["inactive"], "Load and Configure") + action_activate = menu.addAction(self._icons["active"], "Load, Configure and Activate") action = menu.exec_(self._widget.table_view.mapToGlobal(pos)) @@ -403,8 +390,7 @@ def _get_controller_type(node, node_name, ctrl_name): @return Controller type @rtype str """ - response = call_get_parameters( - node=node, node_name=node_name, parameter_names=[ctrl_name]) + response = call_get_parameters(node=node, node_name=node_name, parameter_names=[ctrl_name]) return response.values[0].string_value if response.values else "" @@ -430,7 +416,9 @@ def _get_parameter_controller_names(node, node_name): suffix = ".type" # @note: The versions conditioning is added here to support the source-compatibility with Humble try: - return [n[: -len(suffix)] for n in parameter_names.result().result.names if n.endswith(suffix)] + return [ + n[: -len(suffix)] for n in parameter_names.result().result.names if n.endswith(suffix) + ] finally: # for humble, ros2param < 0.20.0 return [n[: -len(suffix)] for n in parameter_names if n.endswith(suffix)]