Skip to content

Commit 591b06c

Browse files
Codeformat from new pre-commit config (ros-controls#1433)
1 parent fd385f4 commit 591b06c

File tree

5 files changed

+26
-47
lines changed

5 files changed

+26
-47
lines changed

controller_manager/test/test_controller_manager_srvs.cpp

Lines changed: 4 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -832,8 +832,7 @@ TEST_F(TestControllerManagerSrvs, list_sorted_complex_chained_controllers)
832832
auto get_ctrl_pos = [result](const std::string & controller_name) -> int64_t
833833
{
834834
auto it = std::find_if(
835-
result->controller.begin(), result->controller.end(),
836-
[controller_name](auto itf)
835+
result->controller.begin(), result->controller.end(), [controller_name](auto itf)
837836
{ return (itf.name.find(controller_name) != std::string::npos); });
838837
return std::distance(result->controller.begin(), it);
839838
};
@@ -1044,8 +1043,7 @@ TEST_F(TestControllerManagerSrvs, list_sorted_independent_chained_controllers)
10441043
auto get_ctrl_pos = [result](const std::string & controller_name) -> int64_t
10451044
{
10461045
auto it = std::find_if(
1047-
result->controller.begin(), result->controller.end(),
1048-
[controller_name](auto itf)
1046+
result->controller.begin(), result->controller.end(), [controller_name](auto itf)
10491047
{ return (itf.name.find(controller_name) != std::string::npos); });
10501048
return std::distance(result->controller.begin(), it);
10511049
};
@@ -1321,8 +1319,7 @@ TEST_F(TestControllerManagerSrvs, list_large_number_of_controllers_with_chains)
13211319
auto get_ctrl_pos = [result](const std::string & controller_name) -> int64_t
13221320
{
13231321
auto it = std::find_if(
1324-
result->controller.begin(), result->controller.end(),
1325-
[controller_name](auto itf)
1322+
result->controller.begin(), result->controller.end(), [controller_name](auto itf)
13261323
{ return (itf.name.find(controller_name) != std::string::npos); });
13271324
return std::distance(result->controller.begin(), it);
13281325
};
@@ -1546,8 +1543,7 @@ TEST_F(TestControllerManagerSrvs, list_sorted_large_chained_controller_tree)
15461543
auto get_ctrl_pos = [result](const std::string & controller_name) -> int64_t
15471544
{
15481545
auto it = std::find_if(
1549-
result->controller.begin(), result->controller.end(),
1550-
[controller_name](auto itf)
1546+
result->controller.begin(), result->controller.end(), [controller_name](auto itf)
15511547
{ return (itf.name.find(controller_name) != std::string::npos); });
15521548
return std::distance(result->controller.begin(), it);
15531549
};

controller_manager/test/test_spawner_unspawner.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -264,8 +264,7 @@ TEST_F(TestLoadController, unload_on_kill)
264264
// Launch spawner with unload on kill
265265
// timeout command will kill it after the specified time with signal SIGINT
266266
std::stringstream ss;
267-
ss << "timeout --signal=INT 5 "
268-
<< "ros2 run controller_manager spawner "
267+
ss << "timeout --signal=INT 5 " << "ros2 run controller_manager spawner "
269268
<< "ctrl_3 -c test_controller_manager -t "
270269
<< std::string(test_controller::TEST_CONTROLLER_CLASS_NAME) << " --unload-on-kill";
271270

hardware_interface/test/test_hardware_components/test_force_torque_sensor.cpp

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -43,8 +43,7 @@ class TestForceTorqueSensor : public SensorInterface
4343
{
4444
if (
4545
std::find_if(
46-
state_interfaces.begin(), state_interfaces.end(),
47-
[&ft_key](const auto & interface_info)
46+
state_interfaces.begin(), state_interfaces.end(), [&ft_key](const auto & interface_info)
4847
{ return interface_info.name == ft_key; }) == state_interfaces.end())
4948
{
5049
return CallbackReturn::ERROR;

joint_limits/include/joint_limits/joint_limits.hpp

Lines changed: 3 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -128,14 +128,11 @@ struct SoftJointLimits
128128
{
129129
std::stringstream ss_output;
130130

131-
ss_output << " soft position limits: "
132-
<< "[" << min_position << ", " << max_position << "]\n";
131+
ss_output << " soft position limits: " << "[" << min_position << ", " << max_position << "]\n";
133132

134-
ss_output << " k-position: "
135-
<< "[" << k_position << "]\n";
133+
ss_output << " k-position: " << "[" << k_position << "]\n";
136134

137-
ss_output << " k-velocity: "
138-
<< "[" << k_velocity << "]\n";
135+
ss_output << " k-velocity: " << "[" << k_velocity << "]\n";
139136

140137
return ss_output.str();
141138
}

rqt_controller_manager/rqt_controller_manager/controller_manager.py

Lines changed: 17 additions & 29 deletions
Original file line numberDiff line numberDiff line change
@@ -60,8 +60,7 @@ def __init__(self, context):
6060
# Pop-up that displays controller information
6161
self._popup_widget = QWidget()
6262
ui_file = os.path.join(
63-
get_package_share_directory(
64-
"rqt_controller_manager"), "resource", "controller_info.ui"
63+
get_package_share_directory("rqt_controller_manager"), "resource", "controller_info.ui"
6564
)
6665
loadUi(ui_file, self._popup_widget)
6766
self._popup_widget.setObjectName("ControllerInfoUi")
@@ -72,8 +71,7 @@ def __init__(self, context):
7271
# plugin at once, these lines add number to make it easy to
7372
# tell from pane to pane.
7473
if context.serial_number() > 1:
75-
self._widget.setWindowTitle(
76-
f"{self._widget.windowTitle()} {context.serial_number()}")
74+
self._widget.setWindowTitle(f"{self._widget.windowTitle()} {context.serial_number()}")
7775
# Add widget to the user interface
7876
context.add_widget(self._widget)
7977

@@ -108,15 +106,13 @@ def __init__(self, context):
108106

109107
# Timer for controller manager updates
110108
self._update_cm_list_timer = QTimer(self)
111-
self._update_cm_list_timer.setInterval(
112-
int(1000.0 / self._cm_update_freq))
109+
self._update_cm_list_timer.setInterval(int(1000.0 / self._cm_update_freq))
113110
self._update_cm_list_timer.timeout.connect(self._update_cm_list)
114111
self._update_cm_list_timer.start()
115112

116113
# Timer for running controller updates
117114
self._update_ctrl_list_timer = QTimer(self)
118-
self._update_ctrl_list_timer.setInterval(
119-
int(1000.0 / self._cm_update_freq))
115+
self._update_ctrl_list_timer.setInterval(int(1000.0 / self._cm_update_freq))
120116
self._update_ctrl_list_timer.timeout.connect(self._update_controllers)
121117
self._update_ctrl_list_timer.start()
122118

@@ -145,8 +141,7 @@ def restore_settings(self, plugin_settings, instance_settings):
145141
pass
146142

147143
def _update_cm_list(self):
148-
update_combo(self._widget.cm_combo,
149-
_list_controller_managers(self._node))
144+
update_combo(self._widget.cm_combo, _list_controller_managers(self._node))
150145

151146
def _on_cm_change(self, cm_name):
152147
self._cm_name = cm_name
@@ -186,8 +181,7 @@ def _list_controllers(self):
186181
for name in _get_parameter_controller_names(self._node, self._cm_name):
187182
add_ctrl = all(name != ctrl.name for ctrl in controllers)
188183
if add_ctrl:
189-
type_str = _get_controller_type(
190-
self._node, self._cm_name, name)
184+
type_str = _get_controller_type(self._node, self._cm_name, name)
191185
uninit_ctrl = ControllerState(name=name, type=type_str)
192186
controllers.append(uninit_ctrl)
193187
return controllers
@@ -211,26 +205,19 @@ def _on_ctrl_menu(self, pos):
211205
# Show context menu
212206
menu = QMenu(self._widget.table_view)
213207
if ctrl.state == "active":
214-
action_deactivate = menu.addAction(
215-
self._icons["inactive"], "Deactivate")
216-
action_kill = menu.addAction(
217-
self._icons["finalized"], "Deactivate and Unload")
208+
action_deactivate = menu.addAction(self._icons["inactive"], "Deactivate")
209+
action_kill = menu.addAction(self._icons["finalized"], "Deactivate and Unload")
218210
elif ctrl.state == "inactive":
219211
action_activate = menu.addAction(self._icons["active"], "Activate")
220-
action_unload = menu.addAction(
221-
self._icons["unconfigured"], "Unload")
212+
action_unload = menu.addAction(self._icons["unconfigured"], "Unload")
222213
elif ctrl.state == "unconfigured":
223-
action_configure = menu.addAction(
224-
self._icons["inactive"], "Configure")
225-
action_spawn = menu.addAction(
226-
self._icons["active"], "Configure and Activate")
214+
action_configure = menu.addAction(self._icons["inactive"], "Configure")
215+
action_spawn = menu.addAction(self._icons["active"], "Configure and Activate")
227216
else:
228217
# Controller isn't loaded
229218
action_load = menu.addAction(self._icons["unconfigured"], "Load")
230-
action_configure = menu.addAction(
231-
self._icons["inactive"], "Load and Configure")
232-
action_activate = menu.addAction(
233-
self._icons["active"], "Load, Configure and Activate")
219+
action_configure = menu.addAction(self._icons["inactive"], "Load and Configure")
220+
action_activate = menu.addAction(self._icons["active"], "Load, Configure and Activate")
234221

235222
action = menu.exec_(self._widget.table_view.mapToGlobal(pos))
236223

@@ -403,8 +390,7 @@ def _get_controller_type(node, node_name, ctrl_name):
403390
@return Controller type
404391
@rtype str
405392
"""
406-
response = call_get_parameters(
407-
node=node, node_name=node_name, parameter_names=[ctrl_name])
393+
response = call_get_parameters(node=node, node_name=node_name, parameter_names=[ctrl_name])
408394
return response.values[0].string_value if response.values else ""
409395

410396

@@ -430,7 +416,9 @@ def _get_parameter_controller_names(node, node_name):
430416
suffix = ".type"
431417
# @note: The versions conditioning is added here to support the source-compatibility with Humble
432418
try:
433-
return [n[: -len(suffix)] for n in parameter_names.result().result.names if n.endswith(suffix)]
419+
return [
420+
n[: -len(suffix)] for n in parameter_names.result().result.names if n.endswith(suffix)
421+
]
434422
finally:
435423
# for humble, ros2param < 0.20.0
436424
return [n[: -len(suffix)] for n in parameter_names if n.endswith(suffix)]

0 commit comments

Comments
 (0)