From 6a9193caf71c98786a1d7606303e00621ea16bc2 Mon Sep 17 00:00:00 2001 From: Maxime CLEMENT Date: Wed, 9 Aug 2023 18:09:28 +0900 Subject: [PATCH] Rename multi* into multi_* Signed-off-by: Maxime CLEMENT --- .../drivable_area_expansion.hpp | 2 +- .../utils/drivable_area_expansion/expansion.hpp | 14 +++++++------- .../utils/drivable_area_expansion/footprints.hpp | 4 ++-- .../utils/drivable_area_expansion/map_utils.hpp | 2 +- .../utils/drivable_area_expansion/types.hpp | 6 +++--- 5 files changed, 14 insertions(+), 14 deletions(-) diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/drivable_area_expansion.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/drivable_area_expansion.hpp index eadfb72a42afa..53ef91473fe24 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/drivable_area_expansion.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/drivable_area_expansion.hpp @@ -40,7 +40,7 @@ void expandDrivableArea( /// @param[in] expansion_polygons polygons to add to the drivable area /// @return expanded drivable area polygon polygon_t createExpandedDrivableAreaPolygon( - const PathWithLaneId & path, const multipolygon_t & expansion_polygons); + const PathWithLaneId & path, const multi_polygon_t & expansion_polygons); /// @brief Update the drivable area of the given path with the given polygon /// @details this function splits the polygon into a left and right bound and sets it in the path diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/expansion.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/expansion.hpp index 33bccf90ffbe8..70cc8a8bc5925 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/expansion.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/expansion.hpp @@ -36,7 +36,7 @@ namespace drivable_area_expansion /// @return distance limit double calculateDistanceLimit( const linestring_t & base_ls, const polygon_t & expansion_polygon, - const multilinestring_t & limit_lines); + const multi_linestring_t & limit_lines); /// @brief Calculate the distance limit required for the polygon to not cross the limit polygons. /// @details Calculate the minimum distance from base_ls to an intersection of limit_polygons and @@ -47,7 +47,7 @@ double calculateDistanceLimit( /// @return distance limit double calculateDistanceLimit( const linestring_t & base_ls, const polygon_t & expansion_polygon, - const multipolygon_t & limit_polygons); + const multi_polygon_t & limit_polygons); /// @brief Create a polygon from a base line with a given expansion distance /// @param[in] base_ls base linestring from which the polygon is created @@ -64,9 +64,9 @@ polygon_t createExpansionPolygon( /// @param[in] uncrossable_lines lines that should not be crossed by the expanded drivable area /// @param[in] params expansion parameters /// @return expansion polygons -multipolygon_t createExpansionPolygons( - const PathWithLaneId & path, const multipolygon_t & path_footprints, - const multipolygon_t & predicted_paths, const multilinestring_t & uncrossable_lines, +multi_polygon_t createExpansionPolygons( + const PathWithLaneId & path, const multi_polygon_t & path_footprints, + const multi_polygon_t & predicted_paths, const multi_linestring_t & uncrossable_lines, const DrivableAreaExpansionParameters & params); /// @brief Create polygons for the area where the drivable area should be expanded @@ -76,9 +76,9 @@ multipolygon_t createExpansionPolygons( /// @param[in] predicted_paths polygons of the dynamic objects' predicted paths /// @param[in] params expansion parameters /// @return expansion polygons -multipolygon_t createExpansionLaneletPolygons( +multi_polygon_t createExpansionLaneletPolygons( const lanelet::ConstLanelets & path_lanes, const route_handler::RouteHandler & route_handler, - const multipolygon_t & path_footprints, const multipolygon_t & predicted_paths, + const multi_polygon_t & path_footprints, const multi_polygon_t & predicted_paths, const DrivableAreaExpansionParameters & params); } // namespace drivable_area_expansion diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/footprints.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/footprints.hpp index 25f061affaa48..e5e1c76f2521f 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/footprints.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/footprints.hpp @@ -55,7 +55,7 @@ polygon_t createFootprint(const geometry_msgs::msg::Pose & pose, const polygon_t /// @param [in] objects objects from which to create polygons /// @param[in] params expansion parameters containing extra offsets to add to the dynamic objects /// @return footprint polygons of the object's predicted paths -multipolygon_t createObjectFootprints( +multi_polygon_t createObjectFootprints( const autoware_auto_perception_msgs::msg::PredictedObjects & objects, const DrivableAreaExpansionParameters & params); @@ -63,7 +63,7 @@ multipolygon_t createObjectFootprints( /// @param[in] path the path for which to create a footprint /// @param[in] params expansion parameters defining how to create the footprint /// @return footprint polygons of the path -multipolygon_t createPathFootprints( +multi_polygon_t createPathFootprints( const PathWithLaneId & path, const DrivableAreaExpansionParameters & params); } // namespace drivable_area_expansion #endif // BEHAVIOR_PATH_PLANNER__UTILS__DRIVABLE_AREA_EXPANSION__FOOTPRINTS_HPP_ diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/map_utils.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/map_utils.hpp index 33c4cc8a0eff3..4524bd2be2299 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/map_utils.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/map_utils.hpp @@ -28,7 +28,7 @@ namespace drivable_area_expansion /// @param[in] lanelet_map lanelet map /// @param[in] uncrossable_types types that cannot be crossed /// @return the uncrossable linestrings -multilinestring_t extractUncrossableLines( +multi_linestring_t extractUncrossableLines( const lanelet::LaneletMap & lanelet_map, const std::vector & uncrossable_types); /// @brief Determine if the given linestring has one of the given types diff --git a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/types.hpp b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/types.hpp index e56ef4961589d..daabfa97598fd 100644 --- a/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/types.hpp +++ b/planning/behavior_path_planner/include/behavior_path_planner/utils/drivable_area_expansion/types.hpp @@ -30,13 +30,13 @@ using autoware_auto_planning_msgs::msg::PathWithLaneId; using geometry_msgs::msg::Point; using point_t = tier4_autoware_utils::Point2d; -using multipoint_t = tier4_autoware_utils::MultiPoint2d; +using multi_point_t = tier4_autoware_utils::MultiPoint2d; using polygon_t = tier4_autoware_utils::Polygon2d; using ring_t = tier4_autoware_utils::LinearRing2d; -using multipolygon_t = tier4_autoware_utils::MultiPolygon2d; +using multi_polygon_t = tier4_autoware_utils::MultiPolygon2d; using segment_t = tier4_autoware_utils::Segment2d; using linestring_t = tier4_autoware_utils::LineString2d; -using multilinestring_t = tier4_autoware_utils::MultiLineString2d; +using multi_linestring_t = tier4_autoware_utils::MultiLineString2d; struct PointDistance {