Skip to content

Commit

Permalink
apply fixes.yaml
Browse files Browse the repository at this point in the history
Signed-off-by: Yutaka Kondo <[email protected]>
  • Loading branch information
youtalk committed May 2, 2024
1 parent bcbb1b9 commit 1c79907
Show file tree
Hide file tree
Showing 2 changed files with 14 additions and 21 deletions.
8 changes: 5 additions & 3 deletions lanelet2_extension_python/src/projection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,12 +31,14 @@ BOOST_PYTHON_MODULE(_lanelet2_extension_python_boost_python_projection)

bp::class_<
lanelet::projection::MGRSProjector, std::shared_ptr<lanelet::projection::MGRSProjector>,
bp::bases<lanelet::Projector>>("MGRSProjector", bp::init<lanelet::Origin>("origin"));
bp::bases<lanelet::Projector>>
mgrs_projector("MGRSProjector", bp::init<lanelet::Origin>("origin"));
bp::class_<
lanelet::projection::TransverseMercatorProjector,
std::shared_ptr<lanelet::projection::TransverseMercatorProjector>,
bp::bases<lanelet::Projector>>(
"TransverseMercatorProjector", bp::init<lanelet::Origin>("origin"));
bp::bases<lanelet::Projector>>
transverse_mercator_projector(
"TransverseMercatorProjector", bp::init<lanelet::Origin>("origin"));
}

// NOLINTEND(readability-identifier-naming)
27 changes: 9 additions & 18 deletions lanelet2_extension_python/src/utility.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -45,9 +45,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> lineStringWithWidthToPolygon(
lanelet::ConstPolygon3d poly{};
if (lanelet::utils::lineStringWithWidthToPolygon(linestring, &poly)) {
return poly;
} else {
return {};
}
return {};
}

lanelet::Optional<lanelet::ConstPolygon3d> lineStringToPolygon(
Expand All @@ -56,9 +55,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> lineStringToPolygon(
lanelet::ConstPolygon3d poly{};
if (lanelet::utils::lineStringToPolygon(linestring, &poly)) {
return poly;
} else {
return {};
}
return {};
}

lanelet::ArcCoordinates getArcCoordinates(
Expand Down Expand Up @@ -180,9 +178,8 @@ lanelet::Optional<lanelet::ConstLanelet> getLinkedLanelet(
if (lanelet::utils::query::getLinkedLanelet(
parking_space, all_road_lanelets, all_parking_lots, &linked_lanelet)) {
return linked_lanelet;
} else {
return {};
}
return {};
}

lanelet::Optional<lanelet::ConstLanelet> getLinkedLanelet(
Expand All @@ -192,9 +189,8 @@ lanelet::Optional<lanelet::ConstLanelet> getLinkedLanelet(
lanelet::ConstLanelet linked_lanelet;
if (lanelet::utils::query::getLinkedLanelet(parking_space, lanelet_map_ptr, &linked_lanelet)) {
return linked_lanelet;
} else {
return {};
}
return {};
}

lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
Expand All @@ -203,9 +199,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
lanelet::ConstPolygon3d linked_parking_lot;
if (lanelet::utils::query::getLinkedParkingLot(lanelet, all_parking_lots, &linked_parking_lot)) {
return linked_parking_lot;
} else {
return {};
}
return {};
}

lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
Expand All @@ -215,9 +210,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
if (lanelet::utils::query::getLinkedParkingLot(
current_position, all_parking_lots, &linked_parking_lot)) {
return linked_parking_lot;
} else {
return {};
}
return {};
}

lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
Expand All @@ -228,9 +222,8 @@ lanelet::Optional<lanelet::ConstPolygon3d> getLinkedParkingLot(
if (lanelet::utils::query::getLinkedParkingLot(
parking_space, all_parking_lots, &linked_parking_lot)) {
return linked_parking_lot;
} else {
return {};
}
return {};
}

lanelet::ConstLanelets getLaneletsWithinRange_point(
Expand Down Expand Up @@ -299,9 +292,8 @@ lanelet::Optional<lanelet::ConstLanelet> getClosestLanelet(
lanelet::ConstLanelet closest_lanelet{};
if (lanelet::utils::query::getClosestLanelet(lanelets, pose, &closest_lanelet)) {
return closest_lanelet;
} else {
return {};
}
return {};
}

lanelet::Optional<lanelet::ConstLanelet> getClosestLaneletWithConstrains(
Expand All @@ -323,9 +315,8 @@ lanelet::Optional<lanelet::ConstLanelet> getClosestLaneletWithConstrains(
if (lanelet::utils::query::getClosestLaneletWithConstrains(
lanelets, pose, &closest_lanelet, dist_threshold, yaw_threshold)) {
return closest_lanelet;
} else {
return {};
}
return {};
}

lanelet::ConstLanelets getCurrentLanelets_point(
Expand Down

0 comments on commit 1c79907

Please sign in to comment.