Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Codeformat from new pre-commit config #1433

Merged
merged 2 commits into from
Mar 11, 2024
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
12 changes: 4 additions & 8 deletions controller_manager/test/test_controller_manager_srvs.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
};
Expand Down Expand Up @@ -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);
};
Expand Down Expand Up @@ -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);
};
Expand Down Expand Up @@ -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);
};
Expand Down
3 changes: 1 addition & 2 deletions controller_manager/test/test_spawner_unspawner.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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";

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down
9 changes: 3 additions & 6 deletions joint_limits/include/joint_limits/joint_limits.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
Expand Down
46 changes: 17 additions & 29 deletions rqt_controller_manager/rqt_controller_manager/controller_manager.py
Original file line number Diff line number Diff line change
Expand Up @@ -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")
Expand All @@ -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)

Expand Down Expand Up @@ -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()

Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand All @@ -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))

Expand Down Expand Up @@ -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 ""


Expand All @@ -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)]
Loading