@@ -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 (
@@ -180,9 +178,8 @@ lanelet::Optional<lanelet::ConstLanelet> getLinkedLanelet(
180
178
if (lanelet::utils::query::getLinkedLanelet (
181
179
parking_space, all_road_lanelets, all_parking_lots, &linked_lanelet)) {
182
180
return linked_lanelet;
183
- } else {
184
- return {};
185
181
}
182
+ return {};
186
183
}
187
184
188
185
lanelet::Optional<lanelet::ConstLanelet> getLinkedLanelet (
@@ -192,9 +189,8 @@ lanelet::Optional<lanelet::ConstLanelet> getLinkedLanelet(
192
189
lanelet::ConstLanelet linked_lanelet;
193
190
if (lanelet::utils::query::getLinkedLanelet (parking_space, lanelet_map_ptr, &linked_lanelet)) {
194
191
return linked_lanelet;
195
- } else {
196
- return {};
197
192
}
193
+ return {};
198
194
}
199
195
200
196
lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot (
@@ -203,9 +199,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
203
199
lanelet::ConstPolygon3d linked_parking_lot;
204
200
if (lanelet::utils::query::getLinkedParkingLot (lanelet, all_parking_lots, &linked_parking_lot)) {
205
201
return linked_parking_lot;
206
- } else {
207
- return {};
208
202
}
203
+ return {};
209
204
}
210
205
211
206
lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot (
@@ -215,9 +210,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
215
210
if (lanelet::utils::query::getLinkedParkingLot (
216
211
current_position, all_parking_lots, &linked_parking_lot)) {
217
212
return linked_parking_lot;
218
- } else {
219
- return {};
220
213
}
214
+ return {};
221
215
}
222
216
223
217
lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot (
@@ -228,9 +222,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
228
222
if (lanelet::utils::query::getLinkedParkingLot (
229
223
parking_space, all_parking_lots, &linked_parking_lot)) {
230
224
return linked_parking_lot;
231
- } else {
232
- return {};
233
225
}
226
+ return {};
234
227
}
235
228
236
229
lanelet::ConstLanelets getLaneletsWithinRange_point (
@@ -299,9 +292,8 @@ lanelet::Optional<lanelet::ConstLanelet> getClosestLanelet(
299
292
lanelet::ConstLanelet closest_lanelet{};
300
293
if (lanelet::utils::query::getClosestLanelet (lanelets, pose, &closest_lanelet)) {
301
294
return closest_lanelet;
302
- } else {
303
- return {};
304
295
}
296
+ return {};
305
297
}
306
298
307
299
lanelet::Optional<lanelet::ConstLanelet> getClosestLaneletWithConstrains (
@@ -323,9 +315,8 @@ lanelet::Optional<lanelet::ConstLanelet> getClosestLaneletWithConstrains(
323
315
if (lanelet::utils::query::getClosestLaneletWithConstrains (
324
316
lanelets, pose, &closest_lanelet, dist_threshold, yaw_threshold)) {
325
317
return closest_lanelet;
326
- } else {
327
- return {};
328
318
}
319
+ return {};
329
320
}
330
321
331
322
lanelet::ConstLanelets getCurrentLanelets_point (
0 commit comments