From 93816c52915589633dfceab1e7eaaef0bc6a0ef8 Mon Sep 17 00:00:00 2001 From: Yutaka Kondo Date: Thu, 2 May 2024 22:46:13 +0900 Subject: [PATCH] fix: fix clang-tidy errors (#4) --- .../build-and-test-differential.yaml | 19 ++++----- lanelet2_extension_python/src/projection.cpp | 8 ++-- lanelet2_extension_python/src/utility.cpp | 42 +++++++++++-------- 3 files changed, 38 insertions(+), 31 deletions(-) diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 1179857..ad9fc66 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -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 diff --git a/lanelet2_extension_python/src/projection.cpp b/lanelet2_extension_python/src/projection.cpp index 1f70a21..0c0ddbf 100644 --- a/lanelet2_extension_python/src/projection.cpp +++ b/lanelet2_extension_python/src/projection.cpp @@ -31,12 +31,14 @@ BOOST_PYTHON_MODULE(_lanelet2_extension_python_boost_python_projection) bp::class_< lanelet::projection::MGRSProjector, std::shared_ptr, - bp::bases>("MGRSProjector", bp::init("origin")); + bp::bases> + mgrs_projector("MGRSProjector", bp::init("origin")); bp::class_< lanelet::projection::TransverseMercatorProjector, std::shared_ptr, - bp::bases>( - "TransverseMercatorProjector", bp::init("origin")); + bp::bases> + transverse_mercator_projector( + "TransverseMercatorProjector", bp::init("origin")); } // NOLINTEND(readability-identifier-naming) diff --git a/lanelet2_extension_python/src/utility.cpp b/lanelet2_extension_python/src/utility.cpp index fdd612f..5acbc28 100644 --- a/lanelet2_extension_python/src/utility.cpp +++ b/lanelet2_extension_python/src/utility.cpp @@ -45,9 +45,8 @@ lanelet::Optional lineStringWithWidthToPolygon( lanelet::ConstPolygon3d poly{}; if (lanelet::utils::lineStringWithWidthToPolygon(linestring, &poly)) { return poly; - } else { - return {}; } + return {}; } lanelet::Optional lineStringToPolygon( @@ -56,9 +55,8 @@ lanelet::Optional lineStringToPolygon( lanelet::ConstPolygon3d poly{}; if (lanelet::utils::lineStringToPolygon(linestring, &poly)) { return poly; - } else { - return {}; } + return {}; } lanelet::ArcCoordinates getArcCoordinates( @@ -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; @@ -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; @@ -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; @@ -116,6 +117,7 @@ std::vector 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; @@ -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; @@ -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; @@ -180,9 +184,8 @@ lanelet::Optional getLinkedLanelet( if (lanelet::utils::query::getLinkedLanelet( parking_space, all_road_lanelets, all_parking_lots, &linked_lanelet)) { return linked_lanelet; - } else { - return {}; } + return {}; } lanelet::Optional getLinkedLanelet( @@ -192,9 +195,8 @@ lanelet::Optional 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 getLinkedParkingLot( @@ -203,9 +205,8 @@ lanelet::Optional 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 getLinkedParkingLot( @@ -215,9 +216,8 @@ lanelet::Optional getLinkedParkingLot( if (lanelet::utils::query::getLinkedParkingLot( current_position, all_parking_lots, &linked_parking_lot)) { return linked_parking_lot; - } else { - return {}; } + return {}; } lanelet::Optional getLinkedParkingLot( @@ -228,9 +228,8 @@ lanelet::Optional 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( @@ -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; @@ -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; @@ -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; @@ -291,6 +293,7 @@ lanelet::Optional 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; @@ -299,9 +302,8 @@ lanelet::Optional getClosestLanelet( lanelet::ConstLanelet closest_lanelet{}; if (lanelet::utils::query::getClosestLanelet(lanelets, pose, &closest_lanelet)) { return closest_lanelet; - } else { - return {}; } + return {}; } lanelet::Optional getClosestLaneletWithConstrains( @@ -314,6 +316,7 @@ lanelet::Optional 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; @@ -323,9 +326,8 @@ lanelet::Optional getClosestLaneletWithConstrains( if (lanelet::utils::query::getClosestLaneletWithConstrains( lanelets, pose, &closest_lanelet, dist_threshold, yaw_threshold)) { return closest_lanelet; - } else { - return {}; } + return {}; } lanelet::ConstLanelets getCurrentLanelets_point( @@ -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; @@ -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; @@ -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( @@ -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(_lanelet2_extension_python_boost_python_utility) {