Skip to content

Commit ce672da

Browse files
github-actions[bot]christophfroehlichsaikishor
authored
Bump version of pre-commit hooks (#1618)
Co-authored-by: christophfroehlich <3367244+christophfroehlich@users.noreply.github.com> Co-authored-by: Sai Kishor Kothakota <sai.kishor@pal-robotics.com>
1 parent d1844e6 commit ce672da

File tree

18 files changed

+243
-180
lines changed

18 files changed

+243
-180
lines changed

.pre-commit-config.yaml

Lines changed: 3 additions & 3 deletions
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"]

ackermann_steering_controller/test/test_ackermann_steering_controller.hpp

Lines changed: 32 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -150,48 +150,56 @@ class AckermannSteeringControllerFixture : public ::testing::Test
150150
command_itfs_.reserve(joint_command_values_.size());
151151
command_ifs.reserve(joint_command_values_.size());
152152

153-
command_itfs_.emplace_back(hardware_interface::CommandInterface(
154-
rear_wheels_names_[0], traction_interface_name_,
155-
&joint_command_values_[CMD_TRACTION_RIGHT_WHEEL]));
153+
command_itfs_.emplace_back(
154+
hardware_interface::CommandInterface(
155+
rear_wheels_names_[0], traction_interface_name_,
156+
&joint_command_values_[CMD_TRACTION_RIGHT_WHEEL]));
156157
command_ifs.emplace_back(command_itfs_.back());
157158

158-
command_itfs_.emplace_back(hardware_interface::CommandInterface(
159-
rear_wheels_names_[1], steering_interface_name_,
160-
&joint_command_values_[CMD_TRACTION_LEFT_WHEEL]));
159+
command_itfs_.emplace_back(
160+
hardware_interface::CommandInterface(
161+
rear_wheels_names_[1], steering_interface_name_,
162+
&joint_command_values_[CMD_TRACTION_LEFT_WHEEL]));
161163
command_ifs.emplace_back(command_itfs_.back());
162164

163-
command_itfs_.emplace_back(hardware_interface::CommandInterface(
164-
front_wheels_names_[0], steering_interface_name_,
165-
&joint_command_values_[CMD_STEER_RIGHT_WHEEL]));
165+
command_itfs_.emplace_back(
166+
hardware_interface::CommandInterface(
167+
front_wheels_names_[0], steering_interface_name_,
168+
&joint_command_values_[CMD_STEER_RIGHT_WHEEL]));
166169
command_ifs.emplace_back(command_itfs_.back());
167170

168-
command_itfs_.emplace_back(hardware_interface::CommandInterface(
169-
front_wheels_names_[1], steering_interface_name_,
170-
&joint_command_values_[CMD_STEER_LEFT_WHEEL]));
171+
command_itfs_.emplace_back(
172+
hardware_interface::CommandInterface(
173+
front_wheels_names_[1], steering_interface_name_,
174+
&joint_command_values_[CMD_STEER_LEFT_WHEEL]));
171175
command_ifs.emplace_back(command_itfs_.back());
172176

173177
std::vector<hardware_interface::LoanedStateInterface> state_ifs;
174178
state_itfs_.reserve(joint_state_values_.size());
175179
state_ifs.reserve(joint_state_values_.size());
176180

177-
state_itfs_.emplace_back(hardware_interface::StateInterface(
178-
rear_wheels_names_[0], traction_interface_name_,
179-
&joint_state_values_[STATE_TRACTION_RIGHT_WHEEL]));
181+
state_itfs_.emplace_back(
182+
hardware_interface::StateInterface(
183+
rear_wheels_names_[0], traction_interface_name_,
184+
&joint_state_values_[STATE_TRACTION_RIGHT_WHEEL]));
180185
state_ifs.emplace_back(state_itfs_.back());
181186

182-
state_itfs_.emplace_back(hardware_interface::StateInterface(
183-
rear_wheels_names_[1], traction_interface_name_,
184-
&joint_state_values_[STATE_TRACTION_LEFT_WHEEL]));
187+
state_itfs_.emplace_back(
188+
hardware_interface::StateInterface(
189+
rear_wheels_names_[1], traction_interface_name_,
190+
&joint_state_values_[STATE_TRACTION_LEFT_WHEEL]));
185191
state_ifs.emplace_back(state_itfs_.back());
186192

187-
state_itfs_.emplace_back(hardware_interface::StateInterface(
188-
front_wheels_names_[0], steering_interface_name_,
189-
&joint_state_values_[STATE_STEER_RIGHT_WHEEL]));
193+
state_itfs_.emplace_back(
194+
hardware_interface::StateInterface(
195+
front_wheels_names_[0], steering_interface_name_,
196+
&joint_state_values_[STATE_STEER_RIGHT_WHEEL]));
190197
state_ifs.emplace_back(state_itfs_.back());
191198

192-
state_itfs_.emplace_back(hardware_interface::StateInterface(
193-
front_wheels_names_[1], steering_interface_name_,
194-
&joint_state_values_[STATE_STEER_LEFT_WHEEL]));
199+
state_itfs_.emplace_back(
200+
hardware_interface::StateInterface(
201+
front_wheels_names_[1], steering_interface_name_,
202+
&joint_state_values_[STATE_STEER_LEFT_WHEEL]));
195203
state_ifs.emplace_back(state_itfs_.back());
196204

197205
controller_->assign_interfaces(std::move(command_ifs), std::move(state_ifs));

admittance_controller/src/admittance_controller.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -148,8 +148,9 @@ AdmittanceController::on_export_reference_interfaces()
148148
velocity_reference_.emplace_back(reference_interfaces_[index]);
149149
}
150150
const auto exported_prefix = std::string(get_node()->get_name()) + "/" + joint;
151-
chainable_command_interfaces.emplace_back(hardware_interface::CommandInterface(
152-
exported_prefix, interface, reference_interfaces_.data() + index));
151+
chainable_command_interfaces.emplace_back(
152+
hardware_interface::CommandInterface(
153+
exported_prefix, interface, reference_interfaces_.data() + index));
153154

154155
index++;
155156
}

admittance_controller/test/test_admittance_controller.cpp

Lines changed: 35 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -85,26 +85,30 @@ TEST_F(AdmittanceControllerTest, all_parameters_set_configure_success)
8585

8686
ASSERT_TRUE(!controller_->admittance_->parameters_.joints.empty());
8787
ASSERT_TRUE(controller_->admittance_->parameters_.joints.size() == joint_names_.size());
88-
ASSERT_TRUE(std::equal(
89-
controller_->admittance_->parameters_.joints.begin(),
90-
controller_->admittance_->parameters_.joints.end(), joint_names_.begin(), joint_names_.end()));
88+
ASSERT_TRUE(
89+
std::equal(
90+
controller_->admittance_->parameters_.joints.begin(),
91+
controller_->admittance_->parameters_.joints.end(), joint_names_.begin(),
92+
joint_names_.end()));
9193

9294
ASSERT_TRUE(!controller_->admittance_->parameters_.command_interfaces.empty());
9395
ASSERT_TRUE(
9496
controller_->admittance_->parameters_.command_interfaces.size() ==
9597
command_interface_types_.size());
96-
ASSERT_TRUE(std::equal(
97-
controller_->admittance_->parameters_.command_interfaces.begin(),
98-
controller_->admittance_->parameters_.command_interfaces.end(),
99-
command_interface_types_.begin(), command_interface_types_.end()));
98+
ASSERT_TRUE(
99+
std::equal(
100+
controller_->admittance_->parameters_.command_interfaces.begin(),
101+
controller_->admittance_->parameters_.command_interfaces.end(),
102+
command_interface_types_.begin(), command_interface_types_.end()));
100103

101104
ASSERT_TRUE(!controller_->admittance_->parameters_.state_interfaces.empty());
102105
ASSERT_TRUE(
103106
controller_->admittance_->parameters_.state_interfaces.size() == state_interface_types_.size());
104-
ASSERT_TRUE(std::equal(
105-
controller_->admittance_->parameters_.state_interfaces.begin(),
106-
controller_->admittance_->parameters_.state_interfaces.end(), state_interface_types_.begin(),
107-
state_interface_types_.end()));
107+
ASSERT_TRUE(
108+
std::equal(
109+
controller_->admittance_->parameters_.state_interfaces.begin(),
110+
controller_->admittance_->parameters_.state_interfaces.end(), state_interface_types_.begin(),
111+
state_interface_types_.end()));
108112

109113
ASSERT_EQ(controller_->admittance_->parameters_.ft_sensor.name, ft_sensor_name_);
110114
ASSERT_EQ(controller_->admittance_->parameters_.kinematics.base, ik_base_frame_);
@@ -114,36 +118,40 @@ TEST_F(AdmittanceControllerTest, all_parameters_set_configure_success)
114118
ASSERT_TRUE(
115119
controller_->admittance_->parameters_.admittance.selected_axes.size() ==
116120
admittance_selected_axes_.size());
117-
ASSERT_TRUE(std::equal(
118-
controller_->admittance_->parameters_.admittance.selected_axes.begin(),
119-
controller_->admittance_->parameters_.admittance.selected_axes.end(),
120-
admittance_selected_axes_.begin(), admittance_selected_axes_.end()));
121+
ASSERT_TRUE(
122+
std::equal(
123+
controller_->admittance_->parameters_.admittance.selected_axes.begin(),
124+
controller_->admittance_->parameters_.admittance.selected_axes.end(),
125+
admittance_selected_axes_.begin(), admittance_selected_axes_.end()));
121126

122127
ASSERT_TRUE(!controller_->admittance_->parameters_.admittance.mass.empty());
123128
ASSERT_TRUE(
124129
controller_->admittance_->parameters_.admittance.mass.size() == admittance_mass_.size());
125-
ASSERT_TRUE(std::equal(
126-
controller_->admittance_->parameters_.admittance.mass.begin(),
127-
controller_->admittance_->parameters_.admittance.mass.end(), admittance_mass_.begin(),
128-
admittance_mass_.end()));
130+
ASSERT_TRUE(
131+
std::equal(
132+
controller_->admittance_->parameters_.admittance.mass.begin(),
133+
controller_->admittance_->parameters_.admittance.mass.end(), admittance_mass_.begin(),
134+
admittance_mass_.end()));
129135

130136
ASSERT_TRUE(!controller_->admittance_->parameters_.admittance.damping_ratio.empty());
131137
ASSERT_TRUE(
132138
controller_->admittance_->parameters_.admittance.damping_ratio.size() ==
133139
admittance_damping_ratio_.size());
134-
ASSERT_TRUE(std::equal(
135-
controller_->admittance_->parameters_.admittance.damping_ratio.begin(),
136-
controller_->admittance_->parameters_.admittance.damping_ratio.end(),
137-
admittance_damping_ratio_.begin(), admittance_damping_ratio_.end()));
140+
ASSERT_TRUE(
141+
std::equal(
142+
controller_->admittance_->parameters_.admittance.damping_ratio.begin(),
143+
controller_->admittance_->parameters_.admittance.damping_ratio.end(),
144+
admittance_damping_ratio_.begin(), admittance_damping_ratio_.end()));
138145

139146
ASSERT_TRUE(!controller_->admittance_->parameters_.admittance.stiffness.empty());
140147
ASSERT_TRUE(
141148
controller_->admittance_->parameters_.admittance.stiffness.size() ==
142149
admittance_stiffness_.size());
143-
ASSERT_TRUE(std::equal(
144-
controller_->admittance_->parameters_.admittance.stiffness.begin(),
145-
controller_->admittance_->parameters_.admittance.stiffness.end(), admittance_stiffness_.begin(),
146-
admittance_stiffness_.end()));
150+
ASSERT_TRUE(
151+
std::equal(
152+
controller_->admittance_->parameters_.admittance.stiffness.begin(),
153+
controller_->admittance_->parameters_.admittance.stiffness.end(),
154+
admittance_stiffness_.begin(), admittance_stiffness_.end()));
147155
}
148156

149157
TEST_F(AdmittanceControllerTest, check_interfaces)

admittance_controller/test/test_admittance_controller.hpp

Lines changed: 9 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -176,8 +176,9 @@ class AdmittanceControllerTest : public ::testing::Test
176176

177177
for (auto i = 0u; i < joint_command_values_.size(); ++i)
178178
{
179-
command_itfs_.emplace_back(hardware_interface::CommandInterface(
180-
joint_names_[i], command_interface_types_[0], &joint_command_values_[i]));
179+
command_itfs_.emplace_back(
180+
hardware_interface::CommandInterface(
181+
joint_names_[i], command_interface_types_[0], &joint_command_values_[i]));
181182
command_ifs.emplace_back(command_itfs_.back());
182183
}
183184

@@ -191,8 +192,9 @@ class AdmittanceControllerTest : public ::testing::Test
191192

192193
for (auto i = 0u; i < joint_state_values_.size(); ++i)
193194
{
194-
state_itfs_.emplace_back(hardware_interface::StateInterface(
195-
joint_names_[i], state_interface_types_[0], &joint_state_values_[i]));
195+
state_itfs_.emplace_back(
196+
hardware_interface::StateInterface(
197+
joint_names_[i], state_interface_types_[0], &joint_state_values_[i]));
196198
state_ifs.emplace_back(state_itfs_.back());
197199
}
198200

@@ -201,8 +203,9 @@ class AdmittanceControllerTest : public ::testing::Test
201203

202204
for (auto i = 0u; i < fts_state_names_.size(); ++i)
203205
{
204-
state_itfs_.emplace_back(hardware_interface::StateInterface(
205-
ft_sensor_name_, fts_itf_names[i], &fts_state_values_[i]));
206+
state_itfs_.emplace_back(
207+
hardware_interface::StateInterface(
208+
ft_sensor_name_, fts_itf_names[i], &fts_state_values_[i]));
206209
state_ifs.emplace_back(state_itfs_.back());
207210
}
208211

bicycle_steering_controller/test/test_bicycle_steering_controller.hpp

Lines changed: 14 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -148,24 +148,30 @@ class BicycleSteeringControllerFixture : public ::testing::Test
148148
command_itfs_.reserve(joint_command_values_.size());
149149
command_ifs.reserve(joint_command_values_.size());
150150

151-
command_itfs_.emplace_back(hardware_interface::CommandInterface(
152-
rear_wheels_names_[0], traction_interface_name_, &joint_command_values_[CMD_TRACTION_WHEEL]));
151+
command_itfs_.emplace_back(
152+
hardware_interface::CommandInterface(
153+
rear_wheels_names_[0], traction_interface_name_,
154+
&joint_command_values_[CMD_TRACTION_WHEEL]));
153155
command_ifs.emplace_back(command_itfs_.back());
154156

155-
command_itfs_.emplace_back(hardware_interface::CommandInterface(
156-
front_wheels_names_[0], steering_interface_name_, &joint_command_values_[CMD_STEER_WHEEL]));
157+
command_itfs_.emplace_back(
158+
hardware_interface::CommandInterface(
159+
front_wheels_names_[0], steering_interface_name_, &joint_command_values_[CMD_STEER_WHEEL]));
157160
command_ifs.emplace_back(command_itfs_.back());
158161

159162
std::vector<hardware_interface::LoanedStateInterface> state_ifs;
160163
state_itfs_.reserve(joint_state_values_.size());
161164
state_ifs.reserve(joint_state_values_.size());
162165

163-
state_itfs_.emplace_back(hardware_interface::StateInterface(
164-
rear_wheels_names_[0], traction_interface_name_, &joint_state_values_[STATE_TRACTION_WHEEL]));
166+
state_itfs_.emplace_back(
167+
hardware_interface::StateInterface(
168+
rear_wheels_names_[0], traction_interface_name_,
169+
&joint_state_values_[STATE_TRACTION_WHEEL]));
165170
state_ifs.emplace_back(state_itfs_.back());
166171

167-
state_itfs_.emplace_back(hardware_interface::StateInterface(
168-
front_wheels_names_[0], steering_interface_name_, &joint_state_values_[STATE_STEER_AXIS]));
172+
state_itfs_.emplace_back(
173+
hardware_interface::StateInterface(
174+
front_wheels_names_[0], steering_interface_name_, &joint_state_values_[STATE_STEER_AXIS]));
169175
state_ifs.emplace_back(state_itfs_.back());
170176

171177
controller_->assign_interfaces(std::move(command_ifs), std::move(state_ifs));

diff_drive_controller/src/diff_drive_controller.cpp

Lines changed: 9 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -715,13 +715,15 @@ DiffDriveController::on_export_reference_interfaces()
715715
std::vector<hardware_interface::CommandInterface> reference_interfaces;
716716
reference_interfaces.reserve(reference_interfaces_.size());
717717

718-
reference_interfaces.push_back(hardware_interface::CommandInterface(
719-
get_node()->get_name() + std::string("/linear"), hardware_interface::HW_IF_VELOCITY,
720-
&reference_interfaces_[0]));
721-
722-
reference_interfaces.push_back(hardware_interface::CommandInterface(
723-
get_node()->get_name() + std::string("/angular"), hardware_interface::HW_IF_VELOCITY,
724-
&reference_interfaces_[1]));
718+
reference_interfaces.push_back(
719+
hardware_interface::CommandInterface(
720+
get_node()->get_name() + std::string("/linear"), hardware_interface::HW_IF_VELOCITY,
721+
&reference_interfaces_[0]));
722+
723+
reference_interfaces.push_back(
724+
hardware_interface::CommandInterface(
725+
get_node()->get_name() + std::string("/angular"), hardware_interface::HW_IF_VELOCITY,
726+
&reference_interfaces_[1]));
725727

726728
return reference_interfaces;
727729
}

force_torque_sensor_broadcaster/src/force_torque_sensor_broadcaster.cpp

Lines changed: 18 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -198,33 +198,39 @@ ForceTorqueSensorBroadcaster::on_export_state_interfaces()
198198
}
199199
if (!force_names[0].empty())
200200
{
201-
exported_state_interfaces.emplace_back(hardware_interface::StateInterface(
202-
export_prefix, force_names[0], &realtime_publisher_->msg_.wrench.force.x));
201+
exported_state_interfaces.emplace_back(
202+
hardware_interface::StateInterface(
203+
export_prefix, force_names[0], &realtime_publisher_->msg_.wrench.force.x));
203204
}
204205
if (!force_names[1].empty())
205206
{
206-
exported_state_interfaces.emplace_back(hardware_interface::StateInterface(
207-
export_prefix, force_names[1], &realtime_publisher_->msg_.wrench.force.y));
207+
exported_state_interfaces.emplace_back(
208+
hardware_interface::StateInterface(
209+
export_prefix, force_names[1], &realtime_publisher_->msg_.wrench.force.y));
208210
}
209211
if (!force_names[2].empty())
210212
{
211-
exported_state_interfaces.emplace_back(hardware_interface::StateInterface(
212-
export_prefix, force_names[2], &realtime_publisher_->msg_.wrench.force.z));
213+
exported_state_interfaces.emplace_back(
214+
hardware_interface::StateInterface(
215+
export_prefix, force_names[2], &realtime_publisher_->msg_.wrench.force.z));
213216
}
214217
if (!torque_names[0].empty())
215218
{
216-
exported_state_interfaces.emplace_back(hardware_interface::StateInterface(
217-
export_prefix, torque_names[0], &realtime_publisher_->msg_.wrench.torque.x));
219+
exported_state_interfaces.emplace_back(
220+
hardware_interface::StateInterface(
221+
export_prefix, torque_names[0], &realtime_publisher_->msg_.wrench.torque.x));
218222
}
219223
if (!torque_names[1].empty())
220224
{
221-
exported_state_interfaces.emplace_back(hardware_interface::StateInterface(
222-
export_prefix, torque_names[1], &realtime_publisher_->msg_.wrench.torque.y));
225+
exported_state_interfaces.emplace_back(
226+
hardware_interface::StateInterface(
227+
export_prefix, torque_names[1], &realtime_publisher_->msg_.wrench.torque.y));
223228
}
224229
if (!torque_names[2].empty())
225230
{
226-
exported_state_interfaces.emplace_back(hardware_interface::StateInterface(
227-
export_prefix, torque_names[2], &realtime_publisher_->msg_.wrench.torque.z));
231+
exported_state_interfaces.emplace_back(
232+
hardware_interface::StateInterface(
233+
export_prefix, torque_names[2], &realtime_publisher_->msg_.wrench.torque.z));
228234
}
229235
return exported_state_interfaces;
230236
}

0 commit comments

Comments
 (0)