Skip to content

Commit 3db79b9

Browse files
authored
Bump version of pre-commit hooks (backport #2156) (#2157)
1 parent 1db1d2d commit 3db79b9

26 files changed

+318
-219
lines changed

.pre-commit-config.yaml

+3-3
Original file line numberDiff line numberDiff line change
@@ -56,14 +56,14 @@ repos:
5656
args: ["--line-length=99"]
5757

5858
- repo: https://github.com/pycqa/flake8
59-
rev: 7.1.2
59+
rev: 7.2.0
6060
hooks:
6161
- id: flake8
6262
args: ["--extend-ignore=E501"]
6363

6464
# CPP hooks
6565
- repo: https://github.com/pre-commit/mirrors-clang-format
66-
rev: v19.1.7
66+
rev: v20.1.0
6767
hooks:
6868
- id: clang-format
6969
args: ['-fallback-style=none', '-i']
@@ -133,7 +133,7 @@ repos:
133133
exclude: CHANGELOG\.rst|\.(svg|pyc|drawio)$
134134

135135
- repo: https://github.com/python-jsonschema/check-jsonschema
136-
rev: 0.31.2
136+
rev: 0.32.1
137137
hooks:
138138
- id: check-github-workflows
139139
args: ["--verbose"]

controller_interface/test/test_chainable_controller_interface.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -68,8 +68,9 @@ class TestableChainableControllerInterface
6868
{
6969
std::vector<hardware_interface::CommandInterface> command_interfaces;
7070

71-
command_interfaces.push_back(hardware_interface::CommandInterface(
72-
name_prefix_of_reference_interfaces_, "test_itf", &reference_interfaces_[0]));
71+
command_interfaces.push_back(
72+
hardware_interface::CommandInterface(
73+
name_prefix_of_reference_interfaces_, "test_itf", &reference_interfaces_[0]));
7374

7475
return command_interfaces;
7576
}

controller_interface/test/test_force_torque_sensor.cpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -39,9 +39,10 @@ TEST_F(ForceTorqueSensorTest, validate_all_with_default_names)
3939
ASSERT_EQ(force_torque_sensor_->state_interfaces_.capacity(), size_);
4040

4141
// validate the default interface_names_
42-
ASSERT_TRUE(std::equal(
43-
force_torque_sensor_->interface_names_.begin(), force_torque_sensor_->interface_names_.end(),
44-
full_interface_names_.begin(), full_interface_names_.end()));
42+
ASSERT_TRUE(
43+
std::equal(
44+
force_torque_sensor_->interface_names_.begin(), force_torque_sensor_->interface_names_.end(),
45+
full_interface_names_.begin(), full_interface_names_.end()));
4546

4647
// get the interface names
4748
std::vector<std::string> interface_names = force_torque_sensor_->get_state_interface_names();

controller_interface/test/test_imu_sensor.cpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -38,9 +38,10 @@ TEST_F(IMUSensorTest, validate_all)
3838
ASSERT_EQ(imu_sensor_->state_interfaces_.capacity(), size_);
3939

4040
// validate the default interface_names_
41-
ASSERT_TRUE(std::equal(
42-
imu_sensor_->interface_names_.begin(), imu_sensor_->interface_names_.end(),
43-
full_interface_names_.begin(), full_interface_names_.end()));
41+
ASSERT_TRUE(
42+
std::equal(
43+
imu_sensor_->interface_names_.begin(), imu_sensor_->interface_names_.end(),
44+
full_interface_names_.begin(), full_interface_names_.end()));
4445

4546
// get the interface names
4647
std::vector<std::string> interface_names = imu_sensor_->get_state_interface_names();

controller_interface/test/test_pose_sensor.cpp

+4-3
Original file line numberDiff line numberDiff line change
@@ -36,9 +36,10 @@ TEST_F(PoseSensorTest, validate_all)
3636
ASSERT_EQ(pose_sensor_->state_interfaces_.capacity(), size_);
3737

3838
// Validate default interface_names_
39-
EXPECT_TRUE(std::equal(
40-
pose_sensor_->interface_names_.cbegin(), pose_sensor_->interface_names_.cend(),
41-
full_interface_names_.cbegin(), full_interface_names_.cend()));
39+
EXPECT_TRUE(
40+
std::equal(
41+
pose_sensor_->interface_names_.cbegin(), pose_sensor_->interface_names_.cend(),
42+
full_interface_names_.cbegin(), full_interface_names_.cend()));
4243

4344
// Get interface names
4445
std::vector<std::string> interface_names = pose_sensor_->get_state_interface_names();

controller_interface/test/test_semantic_component_interface.cpp

+8-6
Original file line numberDiff line numberDiff line change
@@ -67,9 +67,10 @@ TEST_F(SemanticComponentInterfaceTest, validate_custom_names)
6767

6868
// validate the interface_names_
6969
std::vector<std::string> interface_names = semantic_component_->get_state_interface_names();
70-
ASSERT_TRUE(std::equal(
71-
semantic_component_->interface_names_.begin(), semantic_component_->interface_names_.end(),
72-
interface_names.begin(), interface_names.end()));
70+
ASSERT_TRUE(
71+
std::equal(
72+
semantic_component_->interface_names_.begin(), semantic_component_->interface_names_.end(),
73+
interface_names.begin(), interface_names.end()));
7374

7475
ASSERT_EQ(interface_names.size(), size_);
7576
ASSERT_EQ(interface_names[0], semantic_component_->test_name_ + "/i5");
@@ -129,7 +130,8 @@ TEST_F(SemanticComponentInterfaceTest, validate_state_interfaces)
129130
ASSERT_EQ(semantic_component_->state_interfaces_.size(), 0u);
130131

131132
// validate that release_interfaces() does not touch interface_names_
132-
ASSERT_TRUE(std::equal(
133-
semantic_component_->interface_names_.begin(), semantic_component_->interface_names_.end(),
134-
interface_names.begin(), interface_names.end()));
133+
ASSERT_TRUE(
134+
std::equal(
135+
semantic_component_->interface_names_.begin(), semantic_component_->interface_names_.end(),
136+
interface_names.begin(), interface_names.end()));
135137
}

controller_manager/src/controller_manager.cpp

+6-4
Original file line numberDiff line numberDiff line change
@@ -272,8 +272,9 @@ ControllerManager::ControllerManager(
272272
: rclcpp::Node(manager_node_name, namespace_, options),
273273
resource_manager_(std::make_unique<hardware_interface::ResourceManager>()),
274274
executor_(executor),
275-
loader_(std::make_shared<pluginlib::ClassLoader<controller_interface::ControllerInterface>>(
276-
kControllerInterfaceNamespace, kControllerInterfaceClassName)),
275+
loader_(
276+
std::make_shared<pluginlib::ClassLoader<controller_interface::ControllerInterface>>(
277+
kControllerInterfaceNamespace, kControllerInterfaceClassName)),
277278
chainable_loader_(
278279
std::make_shared<pluginlib::ClassLoader<controller_interface::ChainableControllerInterface>>(
279280
kControllerInterfaceNamespace, kChainableControllerInterfaceClassName))
@@ -307,8 +308,9 @@ ControllerManager::ControllerManager(
307308
: rclcpp::Node(manager_node_name, namespace_, options),
308309
resource_manager_(std::move(resource_manager)),
309310
executor_(executor),
310-
loader_(std::make_shared<pluginlib::ClassLoader<controller_interface::ControllerInterface>>(
311-
kControllerInterfaceNamespace, kControllerInterfaceClassName)),
311+
loader_(
312+
std::make_shared<pluginlib::ClassLoader<controller_interface::ControllerInterface>>(
313+
kControllerInterfaceNamespace, kControllerInterfaceClassName)),
312314
chainable_loader_(
313315
std::make_shared<pluginlib::ClassLoader<controller_interface::ChainableControllerInterface>>(
314316
kControllerInterfaceNamespace, kChainableControllerInterfaceClassName))

controller_manager/test/test_chainable_controller/test_chainable_controller.cpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -156,8 +156,9 @@ TestChainableController::on_export_reference_interfaces()
156156

157157
for (size_t i = 0; i < reference_interface_names_.size(); ++i)
158158
{
159-
reference_interfaces.push_back(hardware_interface::CommandInterface(
160-
get_node()->get_name(), reference_interface_names_[i], &reference_interfaces_[i]));
159+
reference_interfaces.push_back(
160+
hardware_interface::CommandInterface(
161+
get_node()->get_name(), reference_interface_names_[i], &reference_interfaces_[i]));
161162
}
162163

163164
return reference_interfaces;

controller_manager/test/test_hardware_management_srvs.cpp

+14-10
Original file line numberDiff line numberDiff line change
@@ -69,12 +69,14 @@ class TestControllerManagerHWManagementSrvs : public TestControllerManagerSrvs
6969

7070
cm_->set_parameter(
7171
rclcpp::Parameter("robot_description", ros2_control_test_assets::minimal_robot_urdf));
72-
cm_->set_parameter(rclcpp::Parameter(
73-
"hardware_components_initial_state.unconfigured",
74-
std::vector<std::string>({TEST_SYSTEM_HARDWARE_NAME})));
75-
cm_->set_parameter(rclcpp::Parameter(
76-
"hardware_components_initial_state.inactive",
77-
std::vector<std::string>({TEST_SENSOR_HARDWARE_NAME})));
72+
cm_->set_parameter(
73+
rclcpp::Parameter(
74+
"hardware_components_initial_state.unconfigured",
75+
std::vector<std::string>({TEST_SYSTEM_HARDWARE_NAME})));
76+
cm_->set_parameter(
77+
rclcpp::Parameter(
78+
"hardware_components_initial_state.inactive",
79+
std::vector<std::string>({TEST_SENSOR_HARDWARE_NAME})));
7880

7981
std::string robot_description = "";
8082
cm_->get_parameter("robot_description", robot_description);
@@ -431,10 +433,12 @@ class TestControllerManagerHWManagementSrvsOldParameters
431433

432434
cm_->set_parameter(
433435
rclcpp::Parameter("robot_description", ros2_control_test_assets::minimal_robot_urdf));
434-
cm_->set_parameter(rclcpp::Parameter(
435-
"activate_components_on_start", std::vector<std::string>({TEST_ACTUATOR_HARDWARE_NAME})));
436-
cm_->set_parameter(rclcpp::Parameter(
437-
"configure_components_on_start", std::vector<std::string>({TEST_SENSOR_HARDWARE_NAME})));
436+
cm_->set_parameter(
437+
rclcpp::Parameter(
438+
"activate_components_on_start", std::vector<std::string>({TEST_ACTUATOR_HARDWARE_NAME})));
439+
cm_->set_parameter(
440+
rclcpp::Parameter(
441+
"configure_components_on_start", std::vector<std::string>({TEST_SENSOR_HARDWARE_NAME})));
438442

439443
std::string robot_description = "";
440444
cm_->get_parameter("robot_description", robot_description);

controller_manager/test/test_hardware_spawner.cpp

+7-5
Original file line numberDiff line numberDiff line change
@@ -152,9 +152,10 @@ class TestHardwareSpawnerWithoutRobotDescription
152152
: ControllerManagerFixture<controller_manager::ControllerManager>(""),
153153
RMServiceCaller(TEST_CM_NAME)
154154
{
155-
cm_->set_parameter(rclcpp::Parameter(
156-
"hardware_components_initial_state.unconfigured",
157-
std::vector<std::string>{"TestSystemHardware"}));
155+
cm_->set_parameter(
156+
rclcpp::Parameter(
157+
"hardware_components_initial_state.unconfigured",
158+
std::vector<std::string>{"TestSystemHardware"}));
158159
}
159160

160161
public:
@@ -272,8 +273,9 @@ TEST_F(TestHardwareSpawnerWithNamespacedCM, set_component_to_configured_state_cm
272273
256)
273274
<< "Should fail without defining the namespace";
274275
EXPECT_EQ(
275-
call_spawner("TestSystemHardware --configure -c test_controller_manager --ros-args -r "
276-
"__ns:=/foo_namespace"),
276+
call_spawner(
277+
"TestSystemHardware --configure -c test_controller_manager --ros-args -r "
278+
"__ns:=/foo_namespace"),
277279
0);
278280

279281
EXPECT_EQ(

controller_manager/test/test_spawner_unspawner.cpp

+6-4
Original file line numberDiff line numberDiff line change
@@ -225,8 +225,9 @@ TEST_F(TestLoadController, spawner_test_with_params_file_string_parameter)
225225
const std::string test_file_path = ament_index_cpp::get_package_prefix("controller_manager") +
226226
"/test/test_controller_spawner_with_type.yaml";
227227

228-
cm_->set_parameter(rclcpp::Parameter(
229-
"ctrl_with_parameters_and_type.type", test_controller::TEST_CONTROLLER_CLASS_NAME));
228+
cm_->set_parameter(
229+
rclcpp::Parameter(
230+
"ctrl_with_parameters_and_type.type", test_controller::TEST_CONTROLLER_CLASS_NAME));
230231
cm_->set_parameter(
231232
rclcpp::Parameter("ctrl_with_parameters_and_type.params_file", test_file_path));
232233

@@ -790,8 +791,9 @@ TEST_F(TestLoadControllerWithNamespacedCM, multi_ctrls_test_type_in_param)
790791
EXPECT_EQ(call_unspawner("ctrl_1 ctrl_2 ctrl_3 -c /foo_namespace/test_controller_manager"), 0);
791792
ASSERT_EQ(cm_->get_loaded_controllers().size(), 0ul) << "Controller should have been unloaded";
792793
EXPECT_EQ(
793-
call_spawner("ctrl_1 ctrl_2 ctrl_3 -c test_controller_manager --activate-as-group --ros-args "
794-
"-r __ns:=/foo_namespace"),
794+
call_spawner(
795+
"ctrl_1 ctrl_2 ctrl_3 -c test_controller_manager --activate-as-group --ros-args "
796+
"-r __ns:=/foo_namespace"),
795797
0);
796798
ASSERT_EQ(cm_->get_loaded_controllers().size(), 3ul) << "Controller should have been loaded";
797799
{

hardware_interface/include/hardware_interface/actuator_interface.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -83,8 +83,9 @@ class ActuatorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNod
8383
{
8484
public:
8585
ActuatorInterface()
86-
: lifecycle_state_(rclcpp_lifecycle::State(
87-
lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN))
86+
: lifecycle_state_(
87+
rclcpp_lifecycle::State(
88+
lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN))
8889
{
8990
}
9091

hardware_interface/include/hardware_interface/sensor_interface.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -68,8 +68,9 @@ class SensorInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
6868
{
6969
public:
7070
SensorInterface()
71-
: lifecycle_state_(rclcpp_lifecycle::State(
72-
lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN))
71+
: lifecycle_state_(
72+
rclcpp_lifecycle::State(
73+
lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN))
7374
{
7475
}
7576

hardware_interface/include/hardware_interface/system_interface.hpp

+3-2
Original file line numberDiff line numberDiff line change
@@ -85,8 +85,9 @@ class SystemInterface : public rclcpp_lifecycle::node_interfaces::LifecycleNodeI
8585
{
8686
public:
8787
SystemInterface()
88-
: lifecycle_state_(rclcpp_lifecycle::State(
89-
lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN))
88+
: lifecycle_state_(
89+
rclcpp_lifecycle::State(
90+
lifecycle_msgs::msg::State::PRIMARY_STATE_UNKNOWN, lifecycle_state_names::UNKNOWN))
9091
{
9192
}
9293

hardware_interface/src/actuator.cpp

+40-28
Original file line numberDiff line numberDiff line change
@@ -43,14 +43,16 @@ const rclcpp_lifecycle::State & Actuator::initialize(const HardwareInfo & actuat
4343
switch (impl_->on_init(actuator_info))
4444
{
4545
case CallbackReturn::SUCCESS:
46-
impl_->set_state(rclcpp_lifecycle::State(
47-
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
48-
lifecycle_state_names::UNCONFIGURED));
46+
impl_->set_state(
47+
rclcpp_lifecycle::State(
48+
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
49+
lifecycle_state_names::UNCONFIGURED));
4950
break;
5051
case CallbackReturn::FAILURE:
5152
case CallbackReturn::ERROR:
52-
impl_->set_state(rclcpp_lifecycle::State(
53-
lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, lifecycle_state_names::FINALIZED));
53+
impl_->set_state(
54+
rclcpp_lifecycle::State(
55+
lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, lifecycle_state_names::FINALIZED));
5456
break;
5557
}
5658
}
@@ -64,13 +66,15 @@ const rclcpp_lifecycle::State & Actuator::configure()
6466
switch (impl_->on_configure(impl_->get_state()))
6567
{
6668
case CallbackReturn::SUCCESS:
67-
impl_->set_state(rclcpp_lifecycle::State(
68-
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, lifecycle_state_names::INACTIVE));
69+
impl_->set_state(
70+
rclcpp_lifecycle::State(
71+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, lifecycle_state_names::INACTIVE));
6972
break;
7073
case CallbackReturn::FAILURE:
71-
impl_->set_state(rclcpp_lifecycle::State(
72-
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
73-
lifecycle_state_names::UNCONFIGURED));
74+
impl_->set_state(
75+
rclcpp_lifecycle::State(
76+
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
77+
lifecycle_state_names::UNCONFIGURED));
7478
break;
7579
case CallbackReturn::ERROR:
7680
impl_->set_state(error());
@@ -87,9 +91,10 @@ const rclcpp_lifecycle::State & Actuator::cleanup()
8791
switch (impl_->on_cleanup(impl_->get_state()))
8892
{
8993
case CallbackReturn::SUCCESS:
90-
impl_->set_state(rclcpp_lifecycle::State(
91-
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
92-
lifecycle_state_names::UNCONFIGURED));
94+
impl_->set_state(
95+
rclcpp_lifecycle::State(
96+
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
97+
lifecycle_state_names::UNCONFIGURED));
9398
break;
9499
case CallbackReturn::FAILURE:
95100
case CallbackReturn::ERROR:
@@ -109,8 +114,9 @@ const rclcpp_lifecycle::State & Actuator::shutdown()
109114
switch (impl_->on_shutdown(impl_->get_state()))
110115
{
111116
case CallbackReturn::SUCCESS:
112-
impl_->set_state(rclcpp_lifecycle::State(
113-
lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, lifecycle_state_names::FINALIZED));
117+
impl_->set_state(
118+
rclcpp_lifecycle::State(
119+
lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, lifecycle_state_names::FINALIZED));
114120
break;
115121
case CallbackReturn::FAILURE:
116122
case CallbackReturn::ERROR:
@@ -128,12 +134,14 @@ const rclcpp_lifecycle::State & Actuator::activate()
128134
switch (impl_->on_activate(impl_->get_state()))
129135
{
130136
case CallbackReturn::SUCCESS:
131-
impl_->set_state(rclcpp_lifecycle::State(
132-
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, lifecycle_state_names::ACTIVE));
137+
impl_->set_state(
138+
rclcpp_lifecycle::State(
139+
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, lifecycle_state_names::ACTIVE));
133140
break;
134141
case CallbackReturn::FAILURE:
135-
impl_->set_state(rclcpp_lifecycle::State(
136-
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, lifecycle_state_names::INACTIVE));
142+
impl_->set_state(
143+
rclcpp_lifecycle::State(
144+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, lifecycle_state_names::INACTIVE));
137145
break;
138146
case CallbackReturn::ERROR:
139147
impl_->set_state(error());
@@ -150,12 +158,14 @@ const rclcpp_lifecycle::State & Actuator::deactivate()
150158
switch (impl_->on_deactivate(impl_->get_state()))
151159
{
152160
case CallbackReturn::SUCCESS:
153-
impl_->set_state(rclcpp_lifecycle::State(
154-
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, lifecycle_state_names::INACTIVE));
161+
impl_->set_state(
162+
rclcpp_lifecycle::State(
163+
lifecycle_msgs::msg::State::PRIMARY_STATE_INACTIVE, lifecycle_state_names::INACTIVE));
155164
break;
156165
case CallbackReturn::FAILURE:
157-
impl_->set_state(rclcpp_lifecycle::State(
158-
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, lifecycle_state_names::ACTIVE));
166+
impl_->set_state(
167+
rclcpp_lifecycle::State(
168+
lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE, lifecycle_state_names::ACTIVE));
159169
break;
160170
case CallbackReturn::ERROR:
161171
impl_->set_state(error());
@@ -172,14 +182,16 @@ const rclcpp_lifecycle::State & Actuator::error()
172182
switch (impl_->on_error(impl_->get_state()))
173183
{
174184
case CallbackReturn::SUCCESS:
175-
impl_->set_state(rclcpp_lifecycle::State(
176-
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
177-
lifecycle_state_names::UNCONFIGURED));
185+
impl_->set_state(
186+
rclcpp_lifecycle::State(
187+
lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED,
188+
lifecycle_state_names::UNCONFIGURED));
178189
break;
179190
case CallbackReturn::FAILURE:
180191
case CallbackReturn::ERROR:
181-
impl_->set_state(rclcpp_lifecycle::State(
182-
lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, lifecycle_state_names::FINALIZED));
192+
impl_->set_state(
193+
rclcpp_lifecycle::State(
194+
lifecycle_msgs::msg::State::PRIMARY_STATE_FINALIZED, lifecycle_state_names::FINALIZED));
183195
break;
184196
}
185197
}

0 commit comments

Comments
 (0)