@@ -45,9 +45,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> lineStringWithWidthToPolygon(
45
45
lanelet::ConstPolygon3d poly{};
46
46
if (lanelet::utils::lineStringWithWidthToPolygon (linestring, &poly)) {
47
47
return poly;
48
- } else {
49
- return {};
50
48
}
49
+ return {};
51
50
}
52
51
53
52
lanelet::Optional<lanelet::ConstPolygon3d> lineStringToPolygon (
@@ -56,9 +55,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> lineStringToPolygon(
56
55
lanelet::ConstPolygon3d poly{};
57
56
if (lanelet::utils::lineStringToPolygon (linestring, &poly)) {
58
57
return poly;
59
- } else {
60
- return {};
61
58
}
59
+ return {};
62
60
}
63
61
64
62
lanelet::ArcCoordinates getArcCoordinates (
@@ -69,6 +67,7 @@ lanelet::ArcCoordinates getArcCoordinates(
69
67
serialized_msg.reserve (message_header_length + pose_byte.size ());
70
68
serialized_msg.get_rcl_serialized_message ().buffer_length = pose_byte.size ();
71
69
for (size_t i = 0 ; i < pose_byte.size (); ++i) {
70
+ // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
72
71
serialized_msg.get_rcl_serialized_message ().buffer [i] = pose_byte[i];
73
72
}
74
73
geometry_msgs::msg::Pose pose;
@@ -84,6 +83,7 @@ double getLaneletAngle(const lanelet::ConstLanelet & lanelet, const std::string
84
83
serialized_msg.reserve (message_header_length + point_byte.size ());
85
84
serialized_msg.get_rcl_serialized_message ().buffer_length = point_byte.size ();
86
85
for (size_t i = 0 ; i < point_byte.size (); ++i) {
86
+ // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
87
87
serialized_msg.get_rcl_serialized_message ().buffer [i] = point_byte[i];
88
88
}
89
89
geometry_msgs::msg::Point point;
@@ -100,6 +100,7 @@ bool isInLanelet(
100
100
serialized_msg.reserve (message_header_length + pose_byte.size ());
101
101
serialized_msg.get_rcl_serialized_message ().buffer_length = pose_byte.size ();
102
102
for (size_t i = 0 ; i < pose_byte.size (); ++i) {
103
+ // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
103
104
serialized_msg.get_rcl_serialized_message ().buffer [i] = pose_byte[i];
104
105
}
105
106
geometry_msgs::msg::Pose pose;
@@ -116,6 +117,7 @@ std::vector<double> getClosestCenterPose(
116
117
serialized_point_msg.reserve (message_header_length + search_point_byte.size ());
117
118
serialized_point_msg.get_rcl_serialized_message ().buffer_length = search_point_byte.size ();
118
119
for (size_t i = 0 ; i < search_point_byte.size (); ++i) {
120
+ // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
119
121
serialized_point_msg.get_rcl_serialized_message ().buffer [i] = search_point_byte[i];
120
122
}
121
123
geometry_msgs::msg::Point search_point;
@@ -137,6 +139,7 @@ double getLateralDistanceToCenterline(
137
139
serialized_msg.reserve (message_header_length + pose_byte.size ());
138
140
serialized_msg.get_rcl_serialized_message ().buffer_length = pose_byte.size ();
139
141
for (size_t i = 0 ; i < pose_byte.size (); ++i) {
142
+ // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
140
143
serialized_msg.get_rcl_serialized_message ().buffer [i] = pose_byte[i];
141
144
}
142
145
geometry_msgs::msg::Pose pose;
@@ -153,6 +156,7 @@ double getLateralDistanceToClosestLanelet(
153
156
serialized_msg.reserve (message_header_length + pose_byte.size ());
154
157
serialized_msg.get_rcl_serialized_message ().buffer_length = pose_byte.size ();
155
158
for (size_t i = 0 ; i < pose_byte.size (); ++i) {
159
+ // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
156
160
serialized_msg.get_rcl_serialized_message ().buffer [i] = pose_byte[i];
157
161
}
158
162
geometry_msgs::msg::Pose pose;
@@ -180,9 +184,8 @@ lanelet::Optional<lanelet::ConstLanelet> getLinkedLanelet(
180
184
if (lanelet::utils::query::getLinkedLanelet (
181
185
parking_space, all_road_lanelets, all_parking_lots, &linked_lanelet)) {
182
186
return linked_lanelet;
183
- } else {
184
- return {};
185
187
}
188
+ return {};
186
189
}
187
190
188
191
lanelet::Optional<lanelet::ConstLanelet> getLinkedLanelet (
@@ -192,9 +195,8 @@ lanelet::Optional<lanelet::ConstLanelet> getLinkedLanelet(
192
195
lanelet::ConstLanelet linked_lanelet;
193
196
if (lanelet::utils::query::getLinkedLanelet (parking_space, lanelet_map_ptr, &linked_lanelet)) {
194
197
return linked_lanelet;
195
- } else {
196
- return {};
197
198
}
199
+ return {};
198
200
}
199
201
200
202
lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot (
@@ -203,9 +205,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
203
205
lanelet::ConstPolygon3d linked_parking_lot;
204
206
if (lanelet::utils::query::getLinkedParkingLot (lanelet, all_parking_lots, &linked_parking_lot)) {
205
207
return linked_parking_lot;
206
- } else {
207
- return {};
208
208
}
209
+ return {};
209
210
}
210
211
211
212
lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot (
@@ -215,9 +216,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
215
216
if (lanelet::utils::query::getLinkedParkingLot (
216
217
current_position, all_parking_lots, &linked_parking_lot)) {
217
218
return linked_parking_lot;
218
- } else {
219
- return {};
220
219
}
220
+ return {};
221
221
}
222
222
223
223
lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot (
@@ -228,9 +228,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
228
228
if (lanelet::utils::query::getLinkedParkingLot (
229
229
parking_space, all_parking_lots, &linked_parking_lot)) {
230
230
return linked_parking_lot;
231
- } else {
232
- return {};
233
231
}
232
+ return {};
234
233
}
235
234
236
235
lanelet::ConstLanelets getLaneletsWithinRange_point (
@@ -241,6 +240,7 @@ lanelet::ConstLanelets getLaneletsWithinRange_point(
241
240
serialized_msg.reserve (message_header_length + point_byte.size ());
242
241
serialized_msg.get_rcl_serialized_message ().buffer_length = point_byte.size ();
243
242
for (size_t i = 0 ; i < point_byte.size (); ++i) {
243
+ // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
244
244
serialized_msg.get_rcl_serialized_message ().buffer [i] = point_byte[i];
245
245
}
246
246
geometry_msgs::msg::Point point;
@@ -258,6 +258,7 @@ lanelet::ConstLanelets getLaneChangeableNeighbors_point(
258
258
serialized_msg.reserve (message_header_length + point_byte.size ());
259
259
serialized_msg.get_rcl_serialized_message ().buffer_length = point_byte.size ();
260
260
for (size_t i = 0 ; i < point_byte.size (); ++i) {
261
+ // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
261
262
serialized_msg.get_rcl_serialized_message ().buffer [i] = point_byte[i];
262
263
}
263
264
geometry_msgs::msg::Point point;
@@ -275,6 +276,7 @@ lanelet::ConstLanelets getAllNeighbors_point(
275
276
serialized_msg.reserve (message_header_length + point_byte.size ());
276
277
serialized_msg.get_rcl_serialized_message ().buffer_length = point_byte.size ();
277
278
for (size_t i = 0 ; i < point_byte.size (); ++i) {
279
+ // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
278
280
serialized_msg.get_rcl_serialized_message ().buffer [i] = point_byte[i];
279
281
}
280
282
geometry_msgs::msg::Point point;
@@ -291,6 +293,7 @@ lanelet::Optional<lanelet::ConstLanelet> getClosestLanelet(
291
293
serialized_msg.reserve (message_header_length + pose_byte.size ());
292
294
serialized_msg.get_rcl_serialized_message ().buffer_length = pose_byte.size ();
293
295
for (size_t i = 0 ; i < pose_byte.size (); ++i) {
296
+ // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
294
297
serialized_msg.get_rcl_serialized_message ().buffer [i] = pose_byte[i];
295
298
}
296
299
geometry_msgs::msg::Pose pose;
@@ -299,9 +302,8 @@ lanelet::Optional<lanelet::ConstLanelet> getClosestLanelet(
299
302
lanelet::ConstLanelet closest_lanelet{};
300
303
if (lanelet::utils::query::getClosestLanelet (lanelets, pose, &closest_lanelet)) {
301
304
return closest_lanelet;
302
- } else {
303
- return {};
304
305
}
306
+ return {};
305
307
}
306
308
307
309
lanelet::Optional<lanelet::ConstLanelet> getClosestLaneletWithConstrains (
@@ -314,6 +316,7 @@ lanelet::Optional<lanelet::ConstLanelet> getClosestLaneletWithConstrains(
314
316
serialized_msg.reserve (message_header_length + pose_byte.size ());
315
317
serialized_msg.get_rcl_serialized_message ().buffer_length = pose_byte.size ();
316
318
for (size_t i = 0 ; i < pose_byte.size (); ++i) {
319
+ // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
317
320
serialized_msg.get_rcl_serialized_message ().buffer [i] = pose_byte[i];
318
321
}
319
322
geometry_msgs::msg::Pose pose;
@@ -323,9 +326,8 @@ lanelet::Optional<lanelet::ConstLanelet> getClosestLaneletWithConstrains(
323
326
if (lanelet::utils::query::getClosestLaneletWithConstrains (
324
327
lanelets, pose, &closest_lanelet, dist_threshold, yaw_threshold)) {
325
328
return closest_lanelet;
326
- } else {
327
- return {};
328
329
}
330
+ return {};
329
331
}
330
332
331
333
lanelet::ConstLanelets getCurrentLanelets_point (
@@ -336,6 +338,7 @@ lanelet::ConstLanelets getCurrentLanelets_point(
336
338
serialized_msg.reserve (message_header_length + point_byte.size ());
337
339
serialized_msg.get_rcl_serialized_message ().buffer_length = point_byte.size ();
338
340
for (size_t i = 0 ; i < point_byte.size (); ++i) {
341
+ // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
339
342
serialized_msg.get_rcl_serialized_message ().buffer [i] = point_byte[i];
340
343
}
341
344
geometry_msgs::msg::Point point;
@@ -354,6 +357,7 @@ lanelet::ConstLanelets getCurrentLanelets_pose(
354
357
serialized_msg.reserve (message_header_length + pose_byte.size ());
355
358
serialized_msg.get_rcl_serialized_message ().buffer_length = pose_byte.size ();
356
359
for (size_t i = 0 ; i < pose_byte.size (); ++i) {
360
+ // NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
357
361
serialized_msg.get_rcl_serialized_message ().buffer [i] = pose_byte[i];
358
362
}
359
363
geometry_msgs::msg::Pose pose;
@@ -368,6 +372,7 @@ lanelet::ConstLanelets getCurrentLanelets_pose(
368
372
369
373
// for handling functions with default arguments
370
374
// / utilities.cpp
375
+ // NOLINTBEGIN(google-explicit-constructor)
371
376
BOOST_PYTHON_FUNCTION_OVERLOADS (
372
377
generateFineCenterline_overload, lanelet::utils::generateFineCenterline, 1 , 2 )
373
378
BOOST_PYTHON_FUNCTION_OVERLOADS(
@@ -387,6 +392,7 @@ BOOST_PYTHON_FUNCTION_OVERLOADS(
387
392
getClosestLaneletWithConstrains_overload, ::getClosestLaneletWithConstrains, 2 , 4 )
388
393
BOOST_PYTHON_FUNCTION_OVERLOADS(
389
394
getPrecedingLaneletSequences_overload, lanelet::utils::query::getPrecedingLaneletSequences, 3 , 4 )
395
+ // NOLINTEND(google-explicit-constructor)
390
396
391
397
BOOST_PYTHON_MODULE(_lanelet2_extension_python_boost_python_utility)
392
398
{
0 commit comments