Skip to content

Commit 93816c5

Browse files
authored
fix: fix clang-tidy errors (#4)
1 parent 4da99cf commit 93816c5

File tree

3 files changed

+38
-31
lines changed

3 files changed

+38
-31
lines changed

.github/workflows/build-and-test-differential.yaml

+9-10
Original file line numberDiff line numberDiff line change
@@ -80,13 +80,12 @@ jobs:
8080
**/*.cpp
8181
**/*.hpp
8282
83-
# TODO(youtalk): Comment in after fixing clang-tidy error
84-
# - name: Run clang-tidy
85-
# if: ${{ steps.get-modified-files.outputs.all_changed_files != '' }}
86-
# uses: autowarefoundation/autoware-github-actions/clang-tidy@v1
87-
# with:
88-
# rosdistro: humble
89-
# target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }}
90-
# target-files: ${{ steps.get-modified-files.outputs.all_changed_files }}
91-
# clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/main/.clang-tidy
92-
# build-depends-repos: build_depends.repos
83+
- name: Run clang-tidy
84+
if: ${{ steps.get-modified-files.outputs.all_changed_files != '' }}
85+
uses: autowarefoundation/autoware-github-actions/clang-tidy@v1
86+
with:
87+
rosdistro: humble
88+
target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }}
89+
target-files: ${{ steps.get-modified-files.outputs.all_changed_files }}
90+
clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/main/.clang-tidy
91+
build-depends-repos: build_depends.repos

lanelet2_extension_python/src/projection.cpp

+5-3
Original file line numberDiff line numberDiff line change
@@ -31,12 +31,14 @@ BOOST_PYTHON_MODULE(_lanelet2_extension_python_boost_python_projection)
3131

3232
bp::class_<
3333
lanelet::projection::MGRSProjector, std::shared_ptr<lanelet::projection::MGRSProjector>,
34-
bp::bases<lanelet::Projector>>("MGRSProjector", bp::init<lanelet::Origin>("origin"));
34+
bp::bases<lanelet::Projector>>
35+
mgrs_projector("MGRSProjector", bp::init<lanelet::Origin>("origin"));
3536
bp::class_<
3637
lanelet::projection::TransverseMercatorProjector,
3738
std::shared_ptr<lanelet::projection::TransverseMercatorProjector>,
38-
bp::bases<lanelet::Projector>>(
39-
"TransverseMercatorProjector", bp::init<lanelet::Origin>("origin"));
39+
bp::bases<lanelet::Projector>>
40+
transverse_mercator_projector(
41+
"TransverseMercatorProjector", bp::init<lanelet::Origin>("origin"));
4042
}
4143

4244
// NOLINTEND(readability-identifier-naming)

lanelet2_extension_python/src/utility.cpp

+24-18
Original file line numberDiff line numberDiff line change
@@ -45,9 +45,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> lineStringWithWidthToPolygon(
4545
lanelet::ConstPolygon3d poly{};
4646
if (lanelet::utils::lineStringWithWidthToPolygon(linestring, &poly)) {
4747
return poly;
48-
} else {
49-
return {};
5048
}
49+
return {};
5150
}
5251

5352
lanelet::Optional<lanelet::ConstPolygon3d> lineStringToPolygon(
@@ -56,9 +55,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> lineStringToPolygon(
5655
lanelet::ConstPolygon3d poly{};
5756
if (lanelet::utils::lineStringToPolygon(linestring, &poly)) {
5857
return poly;
59-
} else {
60-
return {};
6158
}
59+
return {};
6260
}
6361

6462
lanelet::ArcCoordinates getArcCoordinates(
@@ -69,6 +67,7 @@ lanelet::ArcCoordinates getArcCoordinates(
6967
serialized_msg.reserve(message_header_length + pose_byte.size());
7068
serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size();
7169
for (size_t i = 0; i < pose_byte.size(); ++i) {
70+
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
7271
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
7372
}
7473
geometry_msgs::msg::Pose pose;
@@ -84,6 +83,7 @@ double getLaneletAngle(const lanelet::ConstLanelet & lanelet, const std::string
8483
serialized_msg.reserve(message_header_length + point_byte.size());
8584
serialized_msg.get_rcl_serialized_message().buffer_length = point_byte.size();
8685
for (size_t i = 0; i < point_byte.size(); ++i) {
86+
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
8787
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i];
8888
}
8989
geometry_msgs::msg::Point point;
@@ -100,6 +100,7 @@ bool isInLanelet(
100100
serialized_msg.reserve(message_header_length + pose_byte.size());
101101
serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size();
102102
for (size_t i = 0; i < pose_byte.size(); ++i) {
103+
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
103104
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
104105
}
105106
geometry_msgs::msg::Pose pose;
@@ -116,6 +117,7 @@ std::vector<double> getClosestCenterPose(
116117
serialized_point_msg.reserve(message_header_length + search_point_byte.size());
117118
serialized_point_msg.get_rcl_serialized_message().buffer_length = search_point_byte.size();
118119
for (size_t i = 0; i < search_point_byte.size(); ++i) {
120+
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
119121
serialized_point_msg.get_rcl_serialized_message().buffer[i] = search_point_byte[i];
120122
}
121123
geometry_msgs::msg::Point search_point;
@@ -137,6 +139,7 @@ double getLateralDistanceToCenterline(
137139
serialized_msg.reserve(message_header_length + pose_byte.size());
138140
serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size();
139141
for (size_t i = 0; i < pose_byte.size(); ++i) {
142+
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
140143
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
141144
}
142145
geometry_msgs::msg::Pose pose;
@@ -153,6 +156,7 @@ double getLateralDistanceToClosestLanelet(
153156
serialized_msg.reserve(message_header_length + pose_byte.size());
154157
serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size();
155158
for (size_t i = 0; i < pose_byte.size(); ++i) {
159+
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
156160
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
157161
}
158162
geometry_msgs::msg::Pose pose;
@@ -180,9 +184,8 @@ lanelet::Optional<lanelet::ConstLanelet> getLinkedLanelet(
180184
if (lanelet::utils::query::getLinkedLanelet(
181185
parking_space, all_road_lanelets, all_parking_lots, &linked_lanelet)) {
182186
return linked_lanelet;
183-
} else {
184-
return {};
185187
}
188+
return {};
186189
}
187190

188191
lanelet::Optional<lanelet::ConstLanelet> getLinkedLanelet(
@@ -192,9 +195,8 @@ lanelet::Optional<lanelet::ConstLanelet> getLinkedLanelet(
192195
lanelet::ConstLanelet linked_lanelet;
193196
if (lanelet::utils::query::getLinkedLanelet(parking_space, lanelet_map_ptr, &linked_lanelet)) {
194197
return linked_lanelet;
195-
} else {
196-
return {};
197198
}
199+
return {};
198200
}
199201

200202
lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
@@ -203,9 +205,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
203205
lanelet::ConstPolygon3d linked_parking_lot;
204206
if (lanelet::utils::query::getLinkedParkingLot(lanelet, all_parking_lots, &linked_parking_lot)) {
205207
return linked_parking_lot;
206-
} else {
207-
return {};
208208
}
209+
return {};
209210
}
210211

211212
lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
@@ -215,9 +216,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
215216
if (lanelet::utils::query::getLinkedParkingLot(
216217
current_position, all_parking_lots, &linked_parking_lot)) {
217218
return linked_parking_lot;
218-
} else {
219-
return {};
220219
}
220+
return {};
221221
}
222222

223223
lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
@@ -228,9 +228,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
228228
if (lanelet::utils::query::getLinkedParkingLot(
229229
parking_space, all_parking_lots, &linked_parking_lot)) {
230230
return linked_parking_lot;
231-
} else {
232-
return {};
233231
}
232+
return {};
234233
}
235234

236235
lanelet::ConstLanelets getLaneletsWithinRange_point(
@@ -241,6 +240,7 @@ lanelet::ConstLanelets getLaneletsWithinRange_point(
241240
serialized_msg.reserve(message_header_length + point_byte.size());
242241
serialized_msg.get_rcl_serialized_message().buffer_length = point_byte.size();
243242
for (size_t i = 0; i < point_byte.size(); ++i) {
243+
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
244244
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i];
245245
}
246246
geometry_msgs::msg::Point point;
@@ -258,6 +258,7 @@ lanelet::ConstLanelets getLaneChangeableNeighbors_point(
258258
serialized_msg.reserve(message_header_length + point_byte.size());
259259
serialized_msg.get_rcl_serialized_message().buffer_length = point_byte.size();
260260
for (size_t i = 0; i < point_byte.size(); ++i) {
261+
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
261262
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i];
262263
}
263264
geometry_msgs::msg::Point point;
@@ -275,6 +276,7 @@ lanelet::ConstLanelets getAllNeighbors_point(
275276
serialized_msg.reserve(message_header_length + point_byte.size());
276277
serialized_msg.get_rcl_serialized_message().buffer_length = point_byte.size();
277278
for (size_t i = 0; i < point_byte.size(); ++i) {
279+
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
278280
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i];
279281
}
280282
geometry_msgs::msg::Point point;
@@ -291,6 +293,7 @@ lanelet::Optional<lanelet::ConstLanelet> getClosestLanelet(
291293
serialized_msg.reserve(message_header_length + pose_byte.size());
292294
serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size();
293295
for (size_t i = 0; i < pose_byte.size(); ++i) {
296+
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
294297
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
295298
}
296299
geometry_msgs::msg::Pose pose;
@@ -299,9 +302,8 @@ lanelet::Optional<lanelet::ConstLanelet> getClosestLanelet(
299302
lanelet::ConstLanelet closest_lanelet{};
300303
if (lanelet::utils::query::getClosestLanelet(lanelets, pose, &closest_lanelet)) {
301304
return closest_lanelet;
302-
} else {
303-
return {};
304305
}
306+
return {};
305307
}
306308

307309
lanelet::Optional<lanelet::ConstLanelet> getClosestLaneletWithConstrains(
@@ -314,6 +316,7 @@ lanelet::Optional<lanelet::ConstLanelet> getClosestLaneletWithConstrains(
314316
serialized_msg.reserve(message_header_length + pose_byte.size());
315317
serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size();
316318
for (size_t i = 0; i < pose_byte.size(); ++i) {
319+
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
317320
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
318321
}
319322
geometry_msgs::msg::Pose pose;
@@ -323,9 +326,8 @@ lanelet::Optional<lanelet::ConstLanelet> getClosestLaneletWithConstrains(
323326
if (lanelet::utils::query::getClosestLaneletWithConstrains(
324327
lanelets, pose, &closest_lanelet, dist_threshold, yaw_threshold)) {
325328
return closest_lanelet;
326-
} else {
327-
return {};
328329
}
330+
return {};
329331
}
330332

331333
lanelet::ConstLanelets getCurrentLanelets_point(
@@ -336,6 +338,7 @@ lanelet::ConstLanelets getCurrentLanelets_point(
336338
serialized_msg.reserve(message_header_length + point_byte.size());
337339
serialized_msg.get_rcl_serialized_message().buffer_length = point_byte.size();
338340
for (size_t i = 0; i < point_byte.size(); ++i) {
341+
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
339342
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i];
340343
}
341344
geometry_msgs::msg::Point point;
@@ -354,6 +357,7 @@ lanelet::ConstLanelets getCurrentLanelets_pose(
354357
serialized_msg.reserve(message_header_length + pose_byte.size());
355358
serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size();
356359
for (size_t i = 0; i < pose_byte.size(); ++i) {
360+
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
357361
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
358362
}
359363
geometry_msgs::msg::Pose pose;
@@ -368,6 +372,7 @@ lanelet::ConstLanelets getCurrentLanelets_pose(
368372

369373
// for handling functions with default arguments
370374
/// utilities.cpp
375+
// NOLINTBEGIN(google-explicit-constructor)
371376
BOOST_PYTHON_FUNCTION_OVERLOADS(
372377
generateFineCenterline_overload, lanelet::utils::generateFineCenterline, 1, 2)
373378
BOOST_PYTHON_FUNCTION_OVERLOADS(
@@ -387,6 +392,7 @@ BOOST_PYTHON_FUNCTION_OVERLOADS(
387392
getClosestLaneletWithConstrains_overload, ::getClosestLaneletWithConstrains, 2, 4)
388393
BOOST_PYTHON_FUNCTION_OVERLOADS(
389394
getPrecedingLaneletSequences_overload, lanelet::utils::query::getPrecedingLaneletSequences, 3, 4)
395+
// NOLINTEND(google-explicit-constructor)
390396

391397
BOOST_PYTHON_MODULE(_lanelet2_extension_python_boost_python_utility)
392398
{

0 commit comments

Comments
 (0)