Skip to content

Commit

Permalink
Merge remote-tracking branch 'upstream/main' into add-autoware-prefix
Browse files Browse the repository at this point in the history
  • Loading branch information
youtalk committed May 2, 2024
2 parents 894c857 + 93816c5 commit 8f2c8bc
Show file tree
Hide file tree
Showing 3 changed files with 38 additions and 31 deletions.
19 changes: 9 additions & 10 deletions .github/workflows/build-and-test-differential.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -80,13 +80,12 @@ jobs:
**/*.cpp
**/*.hpp
# TODO(youtalk): Comment in after fixing clang-tidy error
# - name: Run clang-tidy
# if: ${{ steps.get-modified-files.outputs.all_changed_files != '' }}
# uses: autowarefoundation/autoware-github-actions/clang-tidy@v1
# with:
# rosdistro: humble
# target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }}
# target-files: ${{ steps.get-modified-files.outputs.all_changed_files }}
# clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/main/.clang-tidy
# build-depends-repos: build_depends.repos
- name: Run clang-tidy
if: ${{ steps.get-modified-files.outputs.all_changed_files != '' }}
uses: autowarefoundation/autoware-github-actions/clang-tidy@v1
with:
rosdistro: humble
target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }}
target-files: ${{ steps.get-modified-files.outputs.all_changed_files }}
clang-tidy-config-url: https://raw.githubusercontent.com/autowarefoundation/autoware/main/.clang-tidy
build-depends-repos: build_depends.repos
8 changes: 5 additions & 3 deletions autoware_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(_autoware_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)
42 changes: 24 additions & 18 deletions autoware_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 All @@ -69,6 +67,7 @@ lanelet::ArcCoordinates getArcCoordinates(
serialized_msg.reserve(message_header_length + pose_byte.size());
serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size();
for (size_t i = 0; i < pose_byte.size(); ++i) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
}
geometry_msgs::msg::Pose pose;
Expand All @@ -84,6 +83,7 @@ double getLaneletAngle(const lanelet::ConstLanelet & lanelet, const std::string
serialized_msg.reserve(message_header_length + point_byte.size());
serialized_msg.get_rcl_serialized_message().buffer_length = point_byte.size();
for (size_t i = 0; i < point_byte.size(); ++i) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i];
}
geometry_msgs::msg::Point point;
Expand All @@ -100,6 +100,7 @@ bool isInLanelet(
serialized_msg.reserve(message_header_length + pose_byte.size());
serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size();
for (size_t i = 0; i < pose_byte.size(); ++i) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
}
geometry_msgs::msg::Pose pose;
Expand All @@ -116,6 +117,7 @@ std::vector<double> getClosestCenterPose(
serialized_point_msg.reserve(message_header_length + search_point_byte.size());
serialized_point_msg.get_rcl_serialized_message().buffer_length = search_point_byte.size();
for (size_t i = 0; i < search_point_byte.size(); ++i) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
serialized_point_msg.get_rcl_serialized_message().buffer[i] = search_point_byte[i];
}
geometry_msgs::msg::Point search_point;
Expand All @@ -137,6 +139,7 @@ double getLateralDistanceToCenterline(
serialized_msg.reserve(message_header_length + pose_byte.size());
serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size();
for (size_t i = 0; i < pose_byte.size(); ++i) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
}
geometry_msgs::msg::Pose pose;
Expand All @@ -153,6 +156,7 @@ double getLateralDistanceToClosestLanelet(
serialized_msg.reserve(message_header_length + pose_byte.size());
serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size();
for (size_t i = 0; i < pose_byte.size(); ++i) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
}
geometry_msgs::msg::Pose pose;
Expand Down Expand Up @@ -180,9 +184,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 +195,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 +205,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 +216,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 +228,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 All @@ -241,6 +240,7 @@ lanelet::ConstLanelets getLaneletsWithinRange_point(
serialized_msg.reserve(message_header_length + point_byte.size());
serialized_msg.get_rcl_serialized_message().buffer_length = point_byte.size();
for (size_t i = 0; i < point_byte.size(); ++i) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i];
}
geometry_msgs::msg::Point point;
Expand All @@ -258,6 +258,7 @@ lanelet::ConstLanelets getLaneChangeableNeighbors_point(
serialized_msg.reserve(message_header_length + point_byte.size());
serialized_msg.get_rcl_serialized_message().buffer_length = point_byte.size();
for (size_t i = 0; i < point_byte.size(); ++i) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i];
}
geometry_msgs::msg::Point point;
Expand All @@ -275,6 +276,7 @@ lanelet::ConstLanelets getAllNeighbors_point(
serialized_msg.reserve(message_header_length + point_byte.size());
serialized_msg.get_rcl_serialized_message().buffer_length = point_byte.size();
for (size_t i = 0; i < point_byte.size(); ++i) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i];
}
geometry_msgs::msg::Point point;
Expand All @@ -291,6 +293,7 @@ lanelet::Optional<lanelet::ConstLanelet> getClosestLanelet(
serialized_msg.reserve(message_header_length + pose_byte.size());
serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size();
for (size_t i = 0; i < pose_byte.size(); ++i) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
}
geometry_msgs::msg::Pose pose;
Expand All @@ -299,9 +302,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 @@ -314,6 +316,7 @@ lanelet::Optional<lanelet::ConstLanelet> getClosestLaneletWithConstrains(
serialized_msg.reserve(message_header_length + pose_byte.size());
serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size();
for (size_t i = 0; i < pose_byte.size(); ++i) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
}
geometry_msgs::msg::Pose pose;
Expand All @@ -323,9 +326,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 All @@ -336,6 +338,7 @@ lanelet::ConstLanelets getCurrentLanelets_point(
serialized_msg.reserve(message_header_length + point_byte.size());
serialized_msg.get_rcl_serialized_message().buffer_length = point_byte.size();
for (size_t i = 0; i < point_byte.size(); ++i) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
serialized_msg.get_rcl_serialized_message().buffer[i] = point_byte[i];
}
geometry_msgs::msg::Point point;
Expand All @@ -354,6 +357,7 @@ lanelet::ConstLanelets getCurrentLanelets_pose(
serialized_msg.reserve(message_header_length + pose_byte.size());
serialized_msg.get_rcl_serialized_message().buffer_length = pose_byte.size();
for (size_t i = 0; i < pose_byte.size(); ++i) {
// NOLINTNEXTLINE(cppcoreguidelines-pro-bounds-pointer-arithmetic)
serialized_msg.get_rcl_serialized_message().buffer[i] = pose_byte[i];
}
geometry_msgs::msg::Pose pose;
Expand All @@ -368,6 +372,7 @@ lanelet::ConstLanelets getCurrentLanelets_pose(

// for handling functions with default arguments
/// utilities.cpp
// NOLINTBEGIN(google-explicit-constructor)
BOOST_PYTHON_FUNCTION_OVERLOADS(
generateFineCenterline_overload, lanelet::utils::generateFineCenterline, 1, 2)
BOOST_PYTHON_FUNCTION_OVERLOADS(
Expand All @@ -387,6 +392,7 @@ BOOST_PYTHON_FUNCTION_OVERLOADS(
getClosestLaneletWithConstrains_overload, ::getClosestLaneletWithConstrains, 2, 4)
BOOST_PYTHON_FUNCTION_OVERLOADS(
getPrecedingLaneletSequences_overload, lanelet::utils::query::getPrecedingLaneletSequences, 3, 4)
// NOLINTEND(google-explicit-constructor)

BOOST_PYTHON_MODULE(_autoware_lanelet2_extension_python_boost_python_utility)
{
Expand Down

0 comments on commit 8f2c8bc

Please sign in to comment.