From b0220b37fcceb542e56d7f9dbb49e7c17fba2e96 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" Date: Fri, 7 Mar 2025 21:36:34 +0900 Subject: [PATCH 1/6] feat(autoware_utils_geometry): split package Signed-off-by: Takagi, Isamu --- autoware_utils/README.md | 97 ------------------- autoware_utils_geometry/CMakeLists.txt | 25 +++++ autoware_utils_geometry/README.md | 87 +++++++++++++++++ .../geometry/alt_geometry.hpp | 8 +- .../geometry/boost_geometry.hpp | 6 +- .../geometry/boost_polygon_utils.hpp | 8 +- .../geometry/ear_clipping.hpp | 8 +- .../geometry/geometry.hpp | 19 ++-- .../geometry/gjk_2d.hpp | 8 +- .../geometry/pose_deviation.hpp | 6 +- .../geometry/random_concave_polygon.hpp | 8 +- .../geometry/random_convex_polygon.hpp | 8 +- .../geometry/sat_2d.hpp | 8 +- .../msg/covariance.hpp | 6 +- .../autoware_utils_geometry/msg/operation.hpp | 6 +- autoware_utils_geometry/package.xml | 29 ++++++ .../src/geometry/alt_geometry.cpp | 2 +- .../src/geometry/boost_polygon_utils.cpp | 4 +- .../src/geometry/ear_clipping.cpp | 2 +- .../src/geometry/geometry.cpp | 4 +- .../src/geometry/gjk_2d.cpp | 4 +- .../src/geometry/pose_deviation.cpp | 6 +- .../src/geometry/random_concave_polygon.cpp | 4 +- .../src/geometry/random_convex_polygon.cpp | 2 +- .../src/geometry/sat_2d.cpp | 2 +- .../src/msg/operation.cpp | 10 +- .../test/cases/msg/operation.cpp | 17 ++++ autoware_utils_geometry/test/main.cpp | 21 ++++ 28 files changed, 249 insertions(+), 166 deletions(-) create mode 100644 autoware_utils_geometry/CMakeLists.txt create mode 100644 autoware_utils_geometry/README.md rename {autoware_utils/include/autoware_utils => autoware_utils_geometry/include/autoware_utils_geometry}/geometry/alt_geometry.hpp (95%) rename {autoware_utils/include/autoware_utils => autoware_utils_geometry/include/autoware_utils_geometry}/geometry/boost_geometry.hpp (94%) rename {autoware_utils/include/autoware_utils => autoware_utils_geometry/include/autoware_utils_geometry}/geometry/boost_polygon_utils.hpp (88%) rename {autoware_utils/include/autoware_utils => autoware_utils_geometry/include/autoware_utils_geometry}/geometry/ear_clipping.hpp (94%) rename {autoware_utils/include/autoware_utils => autoware_utils_geometry/include/autoware_utils_geometry}/geometry/geometry.hpp (97%) rename {autoware_utils/include/autoware_utils => autoware_utils_geometry/include/autoware_utils_geometry}/geometry/gjk_2d.hpp (79%) rename {autoware_utils/include/autoware_utils => autoware_utils_geometry/include/autoware_utils_geometry}/geometry/pose_deviation.hpp (87%) rename {autoware_utils/include/autoware_utils => autoware_utils_geometry/include/autoware_utils_geometry}/geometry/random_concave_polygon.hpp (86%) rename {autoware_utils/include/autoware_utils => autoware_utils_geometry/include/autoware_utils_geometry}/geometry/random_convex_polygon.hpp (78%) rename {autoware_utils/include/autoware_utils => autoware_utils_geometry/include/autoware_utils_geometry}/geometry/sat_2d.hpp (80%) rename autoware_utils/include/autoware_utils/ros/msg_covariance.hpp => autoware_utils_geometry/include/autoware_utils_geometry/msg/covariance.hpp (93%) rename autoware_utils/include/autoware_utils/ros/msg_operation.hpp => autoware_utils_geometry/include/autoware_utils_geometry/msg/operation.hpp (85%) create mode 100644 autoware_utils_geometry/package.xml rename {autoware_utils => autoware_utils_geometry}/src/geometry/alt_geometry.cpp (99%) rename {autoware_utils => autoware_utils_geometry}/src/geometry/boost_polygon_utils.cpp (98%) rename {autoware_utils => autoware_utils_geometry}/src/geometry/ear_clipping.cpp (99%) rename {autoware_utils => autoware_utils_geometry}/src/geometry/geometry.cpp (99%) rename {autoware_utils => autoware_utils_geometry}/src/geometry/gjk_2d.cpp (97%) rename {autoware_utils => autoware_utils_geometry}/src/geometry/pose_deviation.cpp (93%) rename {autoware_utils => autoware_utils_geometry}/src/geometry/random_concave_polygon.cpp (98%) rename {autoware_utils => autoware_utils_geometry}/src/geometry/random_convex_polygon.cpp (97%) rename {autoware_utils => autoware_utils_geometry}/src/geometry/sat_2d.cpp (98%) rename autoware_utils/src/ros/msg_operation.cpp => autoware_utils_geometry/src/msg/operation.cpp (90%) create mode 100644 autoware_utils_geometry/test/cases/msg/operation.cpp create mode 100644 autoware_utils_geometry/test/main.cpp diff --git a/autoware_utils/README.md b/autoware_utils/README.md index ded235e..d098b7b 100644 --- a/autoware_utils/README.md +++ b/autoware_utils/README.md @@ -6,105 +6,8 @@ The **autoware_utils** library is a comprehensive toolkit designed to facilitate ### Design -#### Geometry Module - -The geometry module provides classes and functions for handling 2D and 3D points, vectors, polygons, and performing geometric operations: - -- **`boost_geometry.hpp`**: Integrates Boost.Geometry for advanced geometric computations, defining point, segment, box, linestring, ring, and polygon types. -- **`alt_geometry.hpp`**: Implements alternative geometric types and operations for 2D vectors and polygons, including vector arithmetic, polygon creation, and various geometric predicates. -- **`ear_clipping.hpp`**: Provides algorithms for triangulating polygons using the ear clipping method. -- **`gjk_2d.hpp`**: Implements the GJK algorithm for fast intersection detection between convex polygons. -- **`sat_2d.hpp`**: Implements the SAT (Separating Axis Theorem) algorithm for detecting intersections between convex polygons. -- **`random_concave_polygon.hpp` and `random_convex_polygon.hpp`**: Generate random concave and convex polygons for testing purposes. -- **`pose_deviation.hpp`**: Calculates deviations between poses in terms of lateral, longitudinal, and yaw angles. -- **`boost_polygon_utils.hpp`**: Utility functions for manipulating polygons, including: - - Checking if a polygon is clockwise. - - Rotating polygons around the origin. - - Converting poses and shapes to polygons. - - Expanding polygons by an offset. -- **`geometry.hpp`**: Comprehensive geometric operations, including: - - Distance calculations between points and segments. - - Curvature computation. - - Pose transformations and interpolations. - - Intersection checks for convex polygons using GJK. - - Conversion between different coordinate systems. - #### ROS Module The ROS module provides utilities for working with ROS messages and nodes: -- **`msg_covariance.hpp`**: Indices for accessing covariance matrices in ROS messages. -- **`msg_operation.hpp`**: Overloaded operators for quaternion messages. - **`self_pose_listener.hpp`**: Listens to the self-pose of the vehicle. - -## Usage - -### Including Headers - -To use the Autoware Utils library in your project, include the necessary headers at the top of your source files: - -```cpp -#include "autoware_utils/geometry/boost_geometry.hpp" -#include "autoware_utils/math/accumulator.hpp" -#include "autoware_utils/ros/debug_publisher.hpp" -``` - -or you can include `autoware_utils/autoware_utils.hpp` for all features: - -```cpp -#include "autoware_utils/autoware_utils.hpp" -``` - -### Example Code Snippets - -#### Using Vector2d from alt_geometry.hpp - -```cpp -#include "autoware_utils/geometry/alt_geometry.hpp" - -using namespace autoware_utils::alt; - -int main() { - Vector2d vec1(3.0, 4.0); - Vector2d vec2(1.0, 2.0); - - // Compute the dot product - double dot_product = vec1.dot(vec2); - - // Compute the norm - double norm = vec1.norm(); - - return 0; -} -``` - -### Detailed Usage Examples - -#### Manipulating Polygons with boost_polygon_utils.hpp - -```cpp -#include "autoware_utils/geometry/boost_polygon_utils.hpp" -#include "autoware_utils/geometry/boost_geometry.hpp" -#include - -int main(int argc, char * argv[]) { - rclcpp::init(argc, argv); - auto node = rclcpp::Node::make_shared("polygon_node"); - - // Create a polygon - autoware_utils::Polygon2d polygon; - // Assume polygon is populated with points - - // Rotate the polygon by 90 degrees - autoware_utils::Polygon2d rotated_polygon = autoware_utils::rotate_polygon(polygon, M_PI / 2); - - // Expand the polygon by an offset - autoware_utils::Polygon2d expanded_polygon = autoware_utils::expand_polygon(polygon, 1.0); - - // Check if the polygon is clockwise - bool is_clockwise = autoware_utils::is_clockwise(polygon); - - rclcpp::shutdown(); - return 0; -} -``` diff --git a/autoware_utils_geometry/CMakeLists.txt b/autoware_utils_geometry/CMakeLists.txt new file mode 100644 index 0000000..866c964 --- /dev/null +++ b/autoware_utils_geometry/CMakeLists.txt @@ -0,0 +1,25 @@ +cmake_minimum_required(VERSION 3.14) +project(autoware_utils_geometry) + +find_package(autoware_cmake REQUIRED) +autoware_package() + +ament_auto_add_library(${PROJECT_NAME} SHARED + "src/geometry/alt_geometry.cpp" + "src/geometry/boost_polygon_utils.cpp" + "src/geometry/ear_clipping.cpp" + "src/geometry/geometry.cpp" + "src/geometry/gjk_2d.cpp" + "src/geometry/pose_deviation.cpp" + "src/geometry/random_concave_polygon.cpp" + "src/geometry/random_convex_polygon.cpp" + "src/geometry/sat_2d.cpp" + "src/msg/operation.cpp" +) + +if(BUILD_TESTING) + file(GLOB_RECURSE test_files test/*.cpp) + ament_auto_add_gtest(test_${PROJECT_NAME} ${test_files}) +endif() + +ament_auto_package() diff --git a/autoware_utils_geometry/README.md b/autoware_utils_geometry/README.md new file mode 100644 index 0000000..4bc8254 --- /dev/null +++ b/autoware_utils_geometry/README.md @@ -0,0 +1,87 @@ +# autoware_utils_geometry + +## Overview + +The **autoware_utils** library is a comprehensive toolkit designed to facilitate the development of autonomous driving applications. +This package provides essential utilities for geometry. +It is extensively used in the Autoware project to handle common tasks such as geometric calculations and message conversions. + +## Design + +The message modules. + +- **`covariance.hpp`**: Indices for accessing covariance matrices in ROS messages. +- **`operation.hpp`**: Overloaded operators for quaternion messages. + +The geometry module provides classes and functions for handling 2D and 3D points, vectors, polygons, and performing geometric operations: + +- **`boost_geometry.hpp`**: Integrates Boost.Geometry for advanced geometric computations, defining point, segment, box, linestring, ring, and polygon types. +- **`alt_geometry.hpp`**: Implements alternative geometric types and operations for 2D vectors and polygons, including vector arithmetic, polygon creation, and various geometric predicates. +- **`ear_clipping.hpp`**: Provides algorithms for triangulating polygons using the ear clipping method. +- **`gjk_2d.hpp`**: Implements the GJK algorithm for fast intersection detection between convex polygons. +- **`sat_2d.hpp`**: Implements the SAT (Separating Axis Theorem) algorithm for detecting intersections between convex polygons. +- **`random_concave_polygon.hpp` and `random_convex_polygon.hpp`**: Generate random concave and convex polygons for testing purposes. +- **`pose_deviation.hpp`**: Calculates deviations between poses in terms of lateral, longitudinal, and yaw angles. +- **`boost_polygon_utils.hpp`**: Utility functions for manipulating polygons, including: +- Checking if a polygon is clockwise. +- Rotating polygons around the origin. +- Converting poses and shapes to polygons. +- Expanding polygons by an offset. +- **`geometry.hpp`**: Comprehensive geometric operations, including: +- Distance calculations between points and segments. +- Curvature computation. +- Pose transformations and interpolations. +- Intersection checks for convex polygons using GJK. +- Conversion between different coordinate systems. + +## Example Code Snippets + +### Using Vector2d from alt_geometry.hpp + +```cpp +#include "autoware_utils/geometry/alt_geometry.hpp" + +using namespace autoware_utils::alt; + +int main() { + Vector2d vec1(3.0, 4.0); + Vector2d vec2(1.0, 2.0); + + // Compute the dot product + double dot_product = vec1.dot(vec2); + + // Compute the norm + double norm = vec1.norm(); + + return 0; +} +``` + +### Manipulating Polygons with boost_polygon_utils.hpp + +```cpp +#include "autoware_utils/geometry/boost_polygon_utils.hpp" +#include "autoware_utils/geometry/boost_geometry.hpp" +#include + +int main(int argc, char * argv[]) { + rclcpp::init(argc, argv); + auto node = rclcpp::Node::make_shared("polygon_node"); + + // Create a polygon + autoware_utils::Polygon2d polygon; + // Assume polygon is populated with points + + // Rotate the polygon by 90 degrees + autoware_utils::Polygon2d rotated_polygon = autoware_utils::rotate_polygon(polygon, M_PI / 2); + + // Expand the polygon by an offset + autoware_utils::Polygon2d expanded_polygon = autoware_utils::expand_polygon(polygon, 1.0); + + // Check if the polygon is clockwise + bool is_clockwise = autoware_utils::is_clockwise(polygon); + + rclcpp::shutdown(); + return 0; +} +``` diff --git a/autoware_utils/include/autoware_utils/geometry/alt_geometry.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/alt_geometry.hpp similarity index 95% rename from autoware_utils/include/autoware_utils/geometry/alt_geometry.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/geometry/alt_geometry.hpp index 6879818..d64d69f 100644 --- a/autoware_utils/include/autoware_utils/geometry/alt_geometry.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/alt_geometry.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS__GEOMETRY__ALT_GEOMETRY_HPP_ -#define AUTOWARE_UTILS__GEOMETRY__ALT_GEOMETRY_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY__ALT_GEOMETRY_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__GEOMETRY__ALT_GEOMETRY_HPP_ -#include "autoware_utils/geometry/boost_geometry.hpp" +#include "autoware_utils_geometry/geometry/boost_geometry.hpp" #include #include @@ -197,4 +197,4 @@ bool within( const alt::ConvexPolygon2d & poly_contained, const alt::ConvexPolygon2d & poly_containing); } // namespace autoware_utils -#endif // AUTOWARE_UTILS__GEOMETRY__ALT_GEOMETRY_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__ALT_GEOMETRY_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/boost_geometry.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_geometry.hpp similarity index 94% rename from autoware_utils/include/autoware_utils/geometry/boost_geometry.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_geometry.hpp index 3742eb8..b3eadd9 100644 --- a/autoware_utils/include/autoware_utils/geometry/boost_geometry.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_geometry.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_ -#define AUTOWARE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY__BOOST_GEOMETRY_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__GEOMETRY__BOOST_GEOMETRY_HPP_ #include #include @@ -101,4 +101,4 @@ BOOST_GEOMETRY_REGISTER_POINT_3D( // NOLINT autoware_utils::Point3d, double, cs::cartesian, x(), y(), z()) // NOLINT BOOST_GEOMETRY_REGISTER_RING(autoware_utils::LinearRing2d) // NOLINT -#endif // AUTOWARE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__BOOST_GEOMETRY_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/boost_polygon_utils.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_polygon_utils.hpp similarity index 88% rename from autoware_utils/include/autoware_utils/geometry/boost_polygon_utils.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_polygon_utils.hpp index 51c32a3..cb9ce03 100644 --- a/autoware_utils/include/autoware_utils/geometry/boost_polygon_utils.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_polygon_utils.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS__GEOMETRY__BOOST_POLYGON_UTILS_HPP_ -#define AUTOWARE_UTILS__GEOMETRY__BOOST_POLYGON_UTILS_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY__BOOST_POLYGON_UTILS_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__GEOMETRY__BOOST_POLYGON_UTILS_HPP_ -#include "autoware_utils/geometry/boost_geometry.hpp" +#include "autoware_utils_geometry/geometry/boost_geometry.hpp" #include #include @@ -49,4 +49,4 @@ double get_area(const autoware_perception_msgs::msg::Shape & shape); Polygon2d expand_polygon(const Polygon2d & input_polygon, const double offset); } // namespace autoware_utils -#endif // AUTOWARE_UTILS__GEOMETRY__BOOST_POLYGON_UTILS_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__BOOST_POLYGON_UTILS_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/ear_clipping.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/ear_clipping.hpp similarity index 94% rename from autoware_utils/include/autoware_utils/geometry/ear_clipping.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/geometry/ear_clipping.hpp index f351321..3de4b9f 100644 --- a/autoware_utils/include/autoware_utils/geometry/ear_clipping.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/ear_clipping.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS__GEOMETRY__EAR_CLIPPING_HPP_ -#define AUTOWARE_UTILS__GEOMETRY__EAR_CLIPPING_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY__EAR_CLIPPING_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__GEOMETRY__EAR_CLIPPING_HPP_ -#include "autoware_utils/geometry/alt_geometry.hpp" +#include "autoware_utils_geometry/geometry/alt_geometry.hpp" #include #include @@ -103,4 +103,4 @@ std::vector triangulate(const alt::Polygon2d & polygon); std::vector triangulate(const Polygon2d & polygon); } // namespace autoware_utils -#endif // AUTOWARE_UTILS__GEOMETRY__EAR_CLIPPING_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__EAR_CLIPPING_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/geometry.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/geometry.hpp similarity index 97% rename from autoware_utils/include/autoware_utils/geometry/geometry.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/geometry/geometry.hpp index 56cc14f..714602e 100644 --- a/autoware_utils/include/autoware_utils/geometry/geometry.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/geometry.hpp @@ -12,13 +12,13 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS__GEOMETRY__GEOMETRY_HPP_ -#define AUTOWARE_UTILS__GEOMETRY__GEOMETRY_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY__GEOMETRY_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__GEOMETRY__GEOMETRY_HPP_ -#include "autoware_utils/geometry/boost_geometry.hpp" -#include "autoware_utils/math/constants.hpp" -#include "autoware_utils/math/normalization.hpp" -#include "autoware_utils/ros/msg_covariance.hpp" +#include "autoware_utils_geometry/geometry/boost_geometry.hpp" +#include "autoware_utils_geometry/msg/covariance.hpp" +#include "autoware_utils_math/constants.hpp" +#include "autoware_utils_math/normalization.hpp" #include #include @@ -98,6 +98,11 @@ inline void doTransform( namespace autoware_utils { + +// TODO(Takagi, Isamu): Move to each function. +using autoware_utils_math::normalize_radian; +using autoware_utils_math::pi; + template geometry_msgs::msg::Point get_point(const T & p) { @@ -590,4 +595,4 @@ bool intersects_convex(const Polygon2d & convex_polygon1, const Polygon2d & conv } // namespace autoware_utils -#endif // AUTOWARE_UTILS__GEOMETRY__GEOMETRY_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__GEOMETRY_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/gjk_2d.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/gjk_2d.hpp similarity index 79% rename from autoware_utils/include/autoware_utils/geometry/gjk_2d.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/geometry/gjk_2d.hpp index 40e2557..3439c06 100644 --- a/autoware_utils/include/autoware_utils/geometry/gjk_2d.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/gjk_2d.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS__GEOMETRY__GJK_2D_HPP_ -#define AUTOWARE_UTILS__GEOMETRY__GJK_2D_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY__GJK_2D_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__GEOMETRY__GJK_2D_HPP_ -#include "autoware_utils/geometry/boost_geometry.hpp" +#include "autoware_utils_geometry/geometry/boost_geometry.hpp" namespace autoware_utils::gjk { @@ -26,4 +26,4 @@ namespace autoware_utils::gjk bool intersects(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2); } // namespace autoware_utils::gjk -#endif // AUTOWARE_UTILS__GEOMETRY__GJK_2D_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__GJK_2D_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/pose_deviation.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/pose_deviation.hpp similarity index 87% rename from autoware_utils/include/autoware_utils/geometry/pose_deviation.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/geometry/pose_deviation.hpp index c7d7e67..0df6359 100644 --- a/autoware_utils/include/autoware_utils/geometry/pose_deviation.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/pose_deviation.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS__GEOMETRY__POSE_DEVIATION_HPP_ -#define AUTOWARE_UTILS__GEOMETRY__POSE_DEVIATION_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY__POSE_DEVIATION_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__GEOMETRY__POSE_DEVIATION_HPP_ #include #include @@ -41,4 +41,4 @@ PoseDeviation calc_pose_deviation( } // namespace autoware_utils -#endif // AUTOWARE_UTILS__GEOMETRY__POSE_DEVIATION_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__POSE_DEVIATION_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/random_concave_polygon.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_concave_polygon.hpp similarity index 86% rename from autoware_utils/include/autoware_utils/geometry/random_concave_polygon.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_concave_polygon.hpp index 300fa11..c29ea6f 100644 --- a/autoware_utils/include/autoware_utils/geometry/random_concave_polygon.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_concave_polygon.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS__GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ -#define AUTOWARE_UTILS__GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ -#include +#include #include #include @@ -44,4 +44,4 @@ bool test_intersection( } // namespace autoware_utils -#endif // AUTOWARE_UTILS__GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/random_convex_polygon.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_convex_polygon.hpp similarity index 78% rename from autoware_utils/include/autoware_utils/geometry/random_convex_polygon.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_convex_polygon.hpp index f7fbf86..aa756c9 100644 --- a/autoware_utils/include/autoware_utils/geometry/random_convex_polygon.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_convex_polygon.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS__GEOMETRY__RANDOM_CONVEX_POLYGON_HPP_ -#define AUTOWARE_UTILS__GEOMETRY__RANDOM_CONVEX_POLYGON_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY__RANDOM_CONVEX_POLYGON_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__GEOMETRY__RANDOM_CONVEX_POLYGON_HPP_ -#include +#include namespace autoware_utils { @@ -26,4 +26,4 @@ namespace autoware_utils Polygon2d random_convex_polygon(const size_t vertices, const double max); } // namespace autoware_utils -#endif // AUTOWARE_UTILS__GEOMETRY__RANDOM_CONVEX_POLYGON_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__RANDOM_CONVEX_POLYGON_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/sat_2d.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/sat_2d.hpp similarity index 80% rename from autoware_utils/include/autoware_utils/geometry/sat_2d.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/geometry/sat_2d.hpp index 48eef84..aa735ab 100644 --- a/autoware_utils/include/autoware_utils/geometry/sat_2d.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/sat_2d.hpp @@ -12,10 +12,10 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS__GEOMETRY__SAT_2D_HPP_ -#define AUTOWARE_UTILS__GEOMETRY__SAT_2D_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY__SAT_2D_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__GEOMETRY__SAT_2D_HPP_ -#include "autoware_utils/geometry/boost_geometry.hpp" +#include "autoware_utils_geometry/geometry/boost_geometry.hpp" namespace autoware_utils::sat { @@ -27,4 +27,4 @@ bool intersects(const Polygon2d & convex_polygon1, const Polygon2d & convex_poly } // namespace autoware_utils::sat -#endif // AUTOWARE_UTILS__GEOMETRY__SAT_2D_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__SAT_2D_HPP_ diff --git a/autoware_utils/include/autoware_utils/ros/msg_covariance.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/msg/covariance.hpp similarity index 93% rename from autoware_utils/include/autoware_utils/ros/msg_covariance.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/msg/covariance.hpp index e566860..3d6bc34 100644 --- a/autoware_utils/include/autoware_utils/ros/msg_covariance.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/msg/covariance.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS__ROS__MSG_COVARIANCE_HPP_ -#define AUTOWARE_UTILS__ROS__MSG_COVARIANCE_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__MSG__COVARIANCE_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__MSG__COVARIANCE_HPP_ namespace autoware_utils { @@ -117,4 +117,4 @@ enum XYZ_UPPER_COV_IDX { } // namespace xyz_upper_covariance_index } // namespace autoware_utils -#endif // AUTOWARE_UTILS__ROS__MSG_COVARIANCE_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__MSG__COVARIANCE_HPP_ diff --git a/autoware_utils/include/autoware_utils/ros/msg_operation.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/msg/operation.hpp similarity index 85% rename from autoware_utils/include/autoware_utils/ros/msg_operation.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/msg/operation.hpp index 132414b..6bfd9e7 100644 --- a/autoware_utils/include/autoware_utils/ros/msg_operation.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/msg/operation.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS__ROS__MSG_OPERATION_HPP_ -#define AUTOWARE_UTILS__ROS__MSG_OPERATION_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__MSG__OPERATION_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__MSG__OPERATION_HPP_ #include "geometry_msgs/msg/quaternion.hpp" @@ -28,4 +28,4 @@ Quaternion operator-(Quaternion a, Quaternion b) noexcept; } // namespace msg } // namespace geometry_msgs -#endif // AUTOWARE_UTILS__ROS__MSG_OPERATION_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__MSG__OPERATION_HPP_ diff --git a/autoware_utils_geometry/package.xml b/autoware_utils_geometry/package.xml new file mode 100644 index 0000000..d6b2276 --- /dev/null +++ b/autoware_utils_geometry/package.xml @@ -0,0 +1,29 @@ + + + + autoware_utils_geometry + 1.1.0 + The autoware_utils_geometry package + Jian Kang + Ryohsuke Mitsudome + Esteve Fernandez + Yutaka Kondo + Takagi, Isamu + Apache License 2.0 + + ament_cmake_auto + autoware_cmake + + autoware_internal_planning_msgs + autoware_utils_math + tf2 + tf2_eigen + tf2_geometry_msgs + + ament_lint_auto + autoware_lint_common + + + ament_cmake + + diff --git a/autoware_utils/src/geometry/alt_geometry.cpp b/autoware_utils_geometry/src/geometry/alt_geometry.cpp similarity index 99% rename from autoware_utils/src/geometry/alt_geometry.cpp rename to autoware_utils_geometry/src/geometry/alt_geometry.cpp index 7c5738e..0dad4e4 100644 --- a/autoware_utils/src/geometry/alt_geometry.cpp +++ b/autoware_utils_geometry/src/geometry/alt_geometry.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_utils/geometry/alt_geometry.hpp" +#include "autoware_utils_geometry/geometry/alt_geometry.hpp" #include #include diff --git a/autoware_utils/src/geometry/boost_polygon_utils.cpp b/autoware_utils_geometry/src/geometry/boost_polygon_utils.cpp similarity index 98% rename from autoware_utils/src/geometry/boost_polygon_utils.cpp rename to autoware_utils_geometry/src/geometry/boost_polygon_utils.cpp index 4e4bbcc..8db07c5 100644 --- a/autoware_utils/src/geometry/boost_polygon_utils.cpp +++ b/autoware_utils_geometry/src/geometry/boost_polygon_utils.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_utils/geometry/boost_polygon_utils.hpp" +#include "autoware_utils_geometry/geometry/boost_polygon_utils.hpp" -#include "autoware_utils/geometry/geometry.hpp" +#include "autoware_utils_geometry/geometry/geometry.hpp" #include diff --git a/autoware_utils/src/geometry/ear_clipping.cpp b/autoware_utils_geometry/src/geometry/ear_clipping.cpp similarity index 99% rename from autoware_utils/src/geometry/ear_clipping.cpp rename to autoware_utils_geometry/src/geometry/ear_clipping.cpp index 8bf8e32..e89895b 100644 --- a/autoware_utils/src/geometry/ear_clipping.cpp +++ b/autoware_utils_geometry/src/geometry/ear_clipping.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_utils/geometry/ear_clipping.hpp" +#include "autoware_utils_geometry/geometry/ear_clipping.hpp" #include #include diff --git a/autoware_utils/src/geometry/geometry.cpp b/autoware_utils_geometry/src/geometry/geometry.cpp similarity index 99% rename from autoware_utils/src/geometry/geometry.cpp rename to autoware_utils_geometry/src/geometry/geometry.cpp index ed9866d..7aed66d 100644 --- a/autoware_utils/src/geometry/geometry.cpp +++ b/autoware_utils_geometry/src/geometry/geometry.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_utils/geometry/geometry.hpp" +#include "autoware_utils_geometry/geometry/geometry.hpp" -#include "autoware_utils/geometry/gjk_2d.hpp" +#include "autoware_utils_geometry/geometry/gjk_2d.hpp" #include diff --git a/autoware_utils/src/geometry/gjk_2d.cpp b/autoware_utils_geometry/src/geometry/gjk_2d.cpp similarity index 97% rename from autoware_utils/src/geometry/gjk_2d.cpp rename to autoware_utils_geometry/src/geometry/gjk_2d.cpp index ca9ec6e..9b1f029 100644 --- a/autoware_utils/src/geometry/gjk_2d.cpp +++ b/autoware_utils_geometry/src/geometry/gjk_2d.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_utils/geometry/gjk_2d.hpp" +#include "autoware_utils_geometry/geometry/gjk_2d.hpp" -#include "autoware_utils/geometry/boost_geometry.hpp" +#include "autoware_utils_geometry/geometry/boost_geometry.hpp" #include diff --git a/autoware_utils/src/geometry/pose_deviation.cpp b/autoware_utils_geometry/src/geometry/pose_deviation.cpp similarity index 93% rename from autoware_utils/src/geometry/pose_deviation.cpp rename to autoware_utils_geometry/src/geometry/pose_deviation.cpp index 0563d23..3197e17 100644 --- a/autoware_utils/src/geometry/pose_deviation.cpp +++ b/autoware_utils_geometry/src/geometry/pose_deviation.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_utils/geometry/pose_deviation.hpp" +#include "autoware_utils_geometry/geometry/pose_deviation.hpp" -#include "autoware_utils/math/normalization.hpp" +#include "autoware_utils_math/normalization.hpp" #include @@ -68,7 +68,7 @@ double calc_yaw_deviation( { const auto base_yaw = tf2::getYaw(base_pose.orientation); const auto target_yaw = tf2::getYaw(target_pose.orientation); - return normalize_radian(target_yaw - base_yaw); + return autoware_utils_math::normalize_radian(target_yaw - base_yaw); } PoseDeviation calc_pose_deviation( diff --git a/autoware_utils/src/geometry/random_concave_polygon.cpp b/autoware_utils_geometry/src/geometry/random_concave_polygon.cpp similarity index 98% rename from autoware_utils/src/geometry/random_concave_polygon.cpp rename to autoware_utils_geometry/src/geometry/random_concave_polygon.cpp index b40e421..6b151a5 100644 --- a/autoware_utils/src/geometry/random_concave_polygon.cpp +++ b/autoware_utils_geometry/src/geometry/random_concave_polygon.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_utils/geometry/random_concave_polygon.hpp" +#include "autoware_utils_geometry/geometry/random_concave_polygon.hpp" -#include "autoware_utils/geometry/boost_geometry.hpp" +#include "autoware_utils_geometry/geometry/boost_geometry.hpp" #include #include diff --git a/autoware_utils/src/geometry/random_convex_polygon.cpp b/autoware_utils_geometry/src/geometry/random_convex_polygon.cpp similarity index 97% rename from autoware_utils/src/geometry/random_convex_polygon.cpp rename to autoware_utils_geometry/src/geometry/random_convex_polygon.cpp index 13e3f0a..9dd2a78 100644 --- a/autoware_utils/src/geometry/random_convex_polygon.cpp +++ b/autoware_utils_geometry/src/geometry/random_convex_polygon.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_utils/geometry/random_convex_polygon.hpp" +#include "autoware_utils_geometry/geometry/random_convex_polygon.hpp" #include diff --git a/autoware_utils/src/geometry/sat_2d.cpp b/autoware_utils_geometry/src/geometry/sat_2d.cpp similarity index 98% rename from autoware_utils/src/geometry/sat_2d.cpp rename to autoware_utils_geometry/src/geometry/sat_2d.cpp index 4628966..f78a464 100644 --- a/autoware_utils/src/geometry/sat_2d.cpp +++ b/autoware_utils_geometry/src/geometry/sat_2d.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_utils/geometry/sat_2d.hpp" +#include "autoware_utils_geometry/geometry/sat_2d.hpp" #include diff --git a/autoware_utils/src/ros/msg_operation.cpp b/autoware_utils_geometry/src/msg/operation.cpp similarity index 90% rename from autoware_utils/src/ros/msg_operation.cpp rename to autoware_utils_geometry/src/msg/operation.cpp index 73aa6bf..2ee0002 100644 --- a/autoware_utils/src/ros/msg_operation.cpp +++ b/autoware_utils_geometry/src/msg/operation.cpp @@ -12,15 +12,11 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_utils/ros/msg_operation.hpp" +#include "autoware_utils_geometry/msg/operation.hpp" -#include - -#ifdef ROS_DISTRO_GALACTIC -#include -#else #include -#endif + +#include // NOTE: Do not use autoware_utils namespace namespace geometry_msgs diff --git a/autoware_utils_geometry/test/cases/msg/operation.cpp b/autoware_utils_geometry/test/cases/msg/operation.cpp new file mode 100644 index 0000000..5b3ff07 --- /dev/null +++ b/autoware_utils_geometry/test/cases/msg/operation.cpp @@ -0,0 +1,17 @@ +// Copyright 2025 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_utils_geometry/msg/operation.hpp" + +#include diff --git a/autoware_utils_geometry/test/main.cpp b/autoware_utils_geometry/test/main.cpp new file mode 100644 index 0000000..7c283b2 --- /dev/null +++ b/autoware_utils_geometry/test/main.cpp @@ -0,0 +1,21 @@ +// Copyright 2025 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include + +int main(int argc, char ** argv) +{ + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); +} From d28ac4cde98a81479217864db20e8fa4063c6fe5 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" Date: Fri, 7 Mar 2025 21:47:14 +0900 Subject: [PATCH 2/6] compatibility header Signed-off-by: Takagi, Isamu --- .../autoware_utils/geometry/alt_geometry.hpp | 27 +++++++++++++++++++ .../geometry/boost_geometry.hpp | 27 +++++++++++++++++++ .../geometry/boost_polygon_utils.hpp | 27 +++++++++++++++++++ .../autoware_utils/geometry/ear_clipping.hpp | 27 +++++++++++++++++++ .../autoware_utils/geometry/geometry.hpp | 27 +++++++++++++++++++ .../autoware_utils/geometry/gjk_2d.hpp | 27 +++++++++++++++++++ .../geometry/pose_deviation.hpp | 27 +++++++++++++++++++ .../geometry/random_concave_polygon.hpp | 27 +++++++++++++++++++ .../geometry/random_convex_polygon.hpp | 27 +++++++++++++++++++ .../autoware_utils/geometry/sat_2d.hpp | 27 +++++++++++++++++++ .../autoware_utils/ros/msg_covariance.hpp | 27 +++++++++++++++++++ .../autoware_utils/ros/msg_operation.hpp | 27 +++++++++++++++++++ autoware_utils/package.xml | 1 + 13 files changed, 325 insertions(+) create mode 100644 autoware_utils/include/autoware_utils/geometry/alt_geometry.hpp create mode 100644 autoware_utils/include/autoware_utils/geometry/boost_geometry.hpp create mode 100644 autoware_utils/include/autoware_utils/geometry/boost_polygon_utils.hpp create mode 100644 autoware_utils/include/autoware_utils/geometry/ear_clipping.hpp create mode 100644 autoware_utils/include/autoware_utils/geometry/geometry.hpp create mode 100644 autoware_utils/include/autoware_utils/geometry/gjk_2d.hpp create mode 100644 autoware_utils/include/autoware_utils/geometry/pose_deviation.hpp create mode 100644 autoware_utils/include/autoware_utils/geometry/random_concave_polygon.hpp create mode 100644 autoware_utils/include/autoware_utils/geometry/random_convex_polygon.hpp create mode 100644 autoware_utils/include/autoware_utils/geometry/sat_2d.hpp create mode 100644 autoware_utils/include/autoware_utils/ros/msg_covariance.hpp create mode 100644 autoware_utils/include/autoware_utils/ros/msg_operation.hpp diff --git a/autoware_utils/include/autoware_utils/geometry/alt_geometry.hpp b/autoware_utils/include/autoware_utils/geometry/alt_geometry.hpp new file mode 100644 index 0000000..fdd8deb --- /dev/null +++ b/autoware_utils/include/autoware_utils/geometry/alt_geometry.hpp @@ -0,0 +1,27 @@ +// Copyright 2025 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__GEOMETRY__ALT_GEOMETRY_HPP_ +#define AUTOWARE_UTILS__GEOMETRY__ALT_GEOMETRY_HPP_ + +// NOLINTBEGIN(build/namespaces, whitespace/line_length) +// clang-format off + +#include +namespace autoware_utils { using namespace autoware_utils_geometry; } + +// clang-format on +// NOLINTEND + +#endif // AUTOWARE_UTILS__GEOMETRY__ALT_GEOMETRY_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/boost_geometry.hpp b/autoware_utils/include/autoware_utils/geometry/boost_geometry.hpp new file mode 100644 index 0000000..33a7110 --- /dev/null +++ b/autoware_utils/include/autoware_utils/geometry/boost_geometry.hpp @@ -0,0 +1,27 @@ +// Copyright 2025 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_ +#define AUTOWARE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_ + +// NOLINTBEGIN(build/namespaces, whitespace/line_length) +// clang-format off + +#include +namespace autoware_utils { using namespace autoware_utils_geometry; } + +// clang-format on +// NOLINTEND + +#endif // AUTOWARE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/boost_polygon_utils.hpp b/autoware_utils/include/autoware_utils/geometry/boost_polygon_utils.hpp new file mode 100644 index 0000000..2bca3dd --- /dev/null +++ b/autoware_utils/include/autoware_utils/geometry/boost_polygon_utils.hpp @@ -0,0 +1,27 @@ +// Copyright 2025 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__GEOMETRY__BOOST_POLYGON_UTILS_HPP_ +#define AUTOWARE_UTILS__GEOMETRY__BOOST_POLYGON_UTILS_HPP_ + +// NOLINTBEGIN(build/namespaces, whitespace/line_length) +// clang-format off + +#include +namespace autoware_utils { using namespace autoware_utils_geometry; } + +// clang-format on +// NOLINTEND + +#endif // AUTOWARE_UTILS__GEOMETRY__BOOST_POLYGON_UTILS_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/ear_clipping.hpp b/autoware_utils/include/autoware_utils/geometry/ear_clipping.hpp new file mode 100644 index 0000000..1b301ce --- /dev/null +++ b/autoware_utils/include/autoware_utils/geometry/ear_clipping.hpp @@ -0,0 +1,27 @@ +// Copyright 2025 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__GEOMETRY__EAR_CLIPPING_HPP_ +#define AUTOWARE_UTILS__GEOMETRY__EAR_CLIPPING_HPP_ + +// NOLINTBEGIN(build/namespaces, whitespace/line_length) +// clang-format off + +#include +namespace autoware_utils { using namespace autoware_utils_geometry; } + +// clang-format on +// NOLINTEND + +#endif // AUTOWARE_UTILS__GEOMETRY__EAR_CLIPPING_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/geometry.hpp b/autoware_utils/include/autoware_utils/geometry/geometry.hpp new file mode 100644 index 0000000..b24dd20 --- /dev/null +++ b/autoware_utils/include/autoware_utils/geometry/geometry.hpp @@ -0,0 +1,27 @@ +// Copyright 2025 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__GEOMETRY__GEOMETRY_HPP_ +#define AUTOWARE_UTILS__GEOMETRY__GEOMETRY_HPP_ + +// NOLINTBEGIN(build/namespaces, whitespace/line_length) +// clang-format off + +#include +namespace autoware_utils { using namespace autoware_utils_geometry; } + +// clang-format on +// NOLINTEND + +#endif // AUTOWARE_UTILS__GEOMETRY__GEOMETRY_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/gjk_2d.hpp b/autoware_utils/include/autoware_utils/geometry/gjk_2d.hpp new file mode 100644 index 0000000..24920a5 --- /dev/null +++ b/autoware_utils/include/autoware_utils/geometry/gjk_2d.hpp @@ -0,0 +1,27 @@ +// Copyright 2025 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__GEOMETRY__GJK_2D_HPP_ +#define AUTOWARE_UTILS__GEOMETRY__GJK_2D_HPP_ + +// NOLINTBEGIN(build/namespaces, whitespace/line_length) +// clang-format off + +#include +namespace autoware_utils { using namespace autoware_utils_geometry; } + +// clang-format on +// NOLINTEND + +#endif // AUTOWARE_UTILS__GEOMETRY__GJK_2D_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/pose_deviation.hpp b/autoware_utils/include/autoware_utils/geometry/pose_deviation.hpp new file mode 100644 index 0000000..7e833c6 --- /dev/null +++ b/autoware_utils/include/autoware_utils/geometry/pose_deviation.hpp @@ -0,0 +1,27 @@ +// Copyright 2025 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__GEOMETRY__POSE_DEVIATION_HPP_ +#define AUTOWARE_UTILS__GEOMETRY__POSE_DEVIATION_HPP_ + +// NOLINTBEGIN(build/namespaces, whitespace/line_length) +// clang-format off + +#include +namespace autoware_utils { using namespace autoware_utils_geometry; } + +// clang-format on +// NOLINTEND + +#endif // AUTOWARE_UTILS__GEOMETRY__POSE_DEVIATION_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/random_concave_polygon.hpp b/autoware_utils/include/autoware_utils/geometry/random_concave_polygon.hpp new file mode 100644 index 0000000..6bee72a --- /dev/null +++ b/autoware_utils/include/autoware_utils/geometry/random_concave_polygon.hpp @@ -0,0 +1,27 @@ +// Copyright 2025 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ +#define AUTOWARE_UTILS__GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ + +// NOLINTBEGIN(build/namespaces, whitespace/line_length) +// clang-format off + +#include +namespace autoware_utils { using namespace autoware_utils_geometry; } + +// clang-format on +// NOLINTEND + +#endif // AUTOWARE_UTILS__GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/random_convex_polygon.hpp b/autoware_utils/include/autoware_utils/geometry/random_convex_polygon.hpp new file mode 100644 index 0000000..b621dd0 --- /dev/null +++ b/autoware_utils/include/autoware_utils/geometry/random_convex_polygon.hpp @@ -0,0 +1,27 @@ +// Copyright 2025 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__GEOMETRY__RANDOM_CONVEX_POLYGON_HPP_ +#define AUTOWARE_UTILS__GEOMETRY__RANDOM_CONVEX_POLYGON_HPP_ + +// NOLINTBEGIN(build/namespaces, whitespace/line_length) +// clang-format off + +#include +namespace autoware_utils { using namespace autoware_utils_geometry; } + +// clang-format on +// NOLINTEND + +#endif // AUTOWARE_UTILS__GEOMETRY__RANDOM_CONVEX_POLYGON_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/sat_2d.hpp b/autoware_utils/include/autoware_utils/geometry/sat_2d.hpp new file mode 100644 index 0000000..f5fd8e4 --- /dev/null +++ b/autoware_utils/include/autoware_utils/geometry/sat_2d.hpp @@ -0,0 +1,27 @@ +// Copyright 2025 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__GEOMETRY__SAT_2D_HPP_ +#define AUTOWARE_UTILS__GEOMETRY__SAT_2D_HPP_ + +// NOLINTBEGIN(build/namespaces, whitespace/line_length) +// clang-format off + +#include +namespace autoware_utils { using namespace autoware_utils_geometry; } + +// clang-format on +// NOLINTEND + +#endif // AUTOWARE_UTILS__GEOMETRY__SAT_2D_HPP_ diff --git a/autoware_utils/include/autoware_utils/ros/msg_covariance.hpp b/autoware_utils/include/autoware_utils/ros/msg_covariance.hpp new file mode 100644 index 0000000..5b069ae --- /dev/null +++ b/autoware_utils/include/autoware_utils/ros/msg_covariance.hpp @@ -0,0 +1,27 @@ +// Copyright 2025 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__ROS__MSG_COVARIANCE_HPP_ +#define AUTOWARE_UTILS__ROS__MSG_COVARIANCE_HPP_ + +// NOLINTBEGIN(build/namespaces, whitespace/line_length) +// clang-format off + +#include +namespace autoware_utils { using namespace autoware_utils_geometry; } + +// clang-format on +// NOLINTEND + +#endif // AUTOWARE_UTILS__ROS__MSG_COVARIANCE_HPP_ diff --git a/autoware_utils/include/autoware_utils/ros/msg_operation.hpp b/autoware_utils/include/autoware_utils/ros/msg_operation.hpp new file mode 100644 index 0000000..0adf0f7 --- /dev/null +++ b/autoware_utils/include/autoware_utils/ros/msg_operation.hpp @@ -0,0 +1,27 @@ +// Copyright 2025 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__ROS__MSG_OPERATION_HPP_ +#define AUTOWARE_UTILS__ROS__MSG_OPERATION_HPP_ + +// NOLINTBEGIN(build/namespaces, whitespace/line_length) +// clang-format off + +#include +namespace autoware_utils { using namespace autoware_utils_geometry; } + +// clang-format on +// NOLINTEND + +#endif // AUTOWARE_UTILS__ROS__MSG_OPERATION_HPP_ diff --git a/autoware_utils/package.xml b/autoware_utils/package.xml index 3e633d4..c179121 100644 --- a/autoware_utils/package.xml +++ b/autoware_utils/package.xml @@ -21,6 +21,7 @@ autoware_planning_msgs autoware_utils_debug autoware_utils_diagnostics + autoware_utils_geometry autoware_utils_logging autoware_utils_math autoware_utils_pcl From e0054df35438cf455d042382e681699ad2c38ef4 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" Date: Fri, 7 Mar 2025 22:00:20 +0900 Subject: [PATCH 3/6] rename namespace Signed-off-by: Takagi, Isamu --- autoware_utils_geometry/README.md | 2 +- .../include/autoware_utils_geometry/geometry/alt_geometry.hpp | 4 ++-- .../autoware_utils_geometry/geometry/boost_geometry.hpp | 4 ++-- .../autoware_utils_geometry/geometry/boost_polygon_utils.hpp | 4 ++-- .../include/autoware_utils_geometry/geometry/ear_clipping.hpp | 4 ++-- .../include/autoware_utils_geometry/geometry/geometry.hpp | 4 ++-- .../include/autoware_utils_geometry/geometry/gjk_2d.hpp | 4 ++-- .../autoware_utils_geometry/geometry/pose_deviation.hpp | 4 ++-- .../geometry/random_concave_polygon.hpp | 4 ++-- .../geometry/random_convex_polygon.hpp | 4 ++-- .../include/autoware_utils_geometry/geometry/sat_2d.hpp | 4 ++-- .../include/autoware_utils_geometry/msg/covariance.hpp | 4 ++-- autoware_utils_geometry/package.xml | 1 + autoware_utils_geometry/src/geometry/alt_geometry.cpp | 4 ++-- autoware_utils_geometry/src/geometry/boost_polygon_utils.cpp | 4 ++-- autoware_utils_geometry/src/geometry/ear_clipping.cpp | 4 ++-- autoware_utils_geometry/src/geometry/geometry.cpp | 4 ++-- autoware_utils_geometry/src/geometry/gjk_2d.cpp | 4 ++-- autoware_utils_geometry/src/geometry/pose_deviation.cpp | 4 ++-- .../src/geometry/random_concave_polygon.cpp | 4 ++-- .../src/geometry/random_convex_polygon.cpp | 4 ++-- autoware_utils_geometry/src/geometry/sat_2d.cpp | 4 ++-- 22 files changed, 42 insertions(+), 41 deletions(-) diff --git a/autoware_utils_geometry/README.md b/autoware_utils_geometry/README.md index 4bc8254..a409c27 100644 --- a/autoware_utils_geometry/README.md +++ b/autoware_utils_geometry/README.md @@ -41,7 +41,7 @@ The geometry module provides classes and functions for handling 2D and 3D points ```cpp #include "autoware_utils/geometry/alt_geometry.hpp" -using namespace autoware_utils::alt; +using namespace autoware_utils_geometry::alt; int main() { Vector2d vec1(3.0, 4.0); diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/alt_geometry.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/alt_geometry.hpp index d64d69f..28af483 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/alt_geometry.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/alt_geometry.hpp @@ -22,7 +22,7 @@ #include #include -namespace autoware_utils +namespace autoware_utils_geometry { // Alternatives for Boost.Geometry ---------------------------------------------------------------- // TODO(mitukou1109): remove namespace @@ -195,6 +195,6 @@ bool within(const alt::Point2d & point, const alt::ConvexPolygon2d & poly); bool within( const alt::ConvexPolygon2d & poly_contained, const alt::ConvexPolygon2d & poly_containing); -} // namespace autoware_utils +} // namespace autoware_utils_geometry #endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__ALT_GEOMETRY_HPP_ diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_geometry.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_geometry.hpp index b3eadd9..1440a79 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_geometry.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_geometry.hpp @@ -25,7 +25,7 @@ #include -namespace autoware_utils +namespace autoware_utils_geometry { // 2D struct Point2d; @@ -93,7 +93,7 @@ inline Point3d from_msg(const geometry_msgs::msg::Point & msg) point.z() = msg.z; return point; } -} // namespace autoware_utils +} // namespace autoware_utils_geometry BOOST_GEOMETRY_REGISTER_POINT_2D( // NOLINT autoware_utils::Point2d, double, cs::cartesian, x(), y()) // NOLINT diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_polygon_utils.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_polygon_utils.hpp index cb9ce03..0d0bba3 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_polygon_utils.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_polygon_utils.hpp @@ -24,7 +24,7 @@ #include -namespace autoware_utils +namespace autoware_utils_geometry { bool is_clockwise(const Polygon2d & polygon); Polygon2d inverse_clockwise(const Polygon2d & polygon); @@ -47,6 +47,6 @@ Polygon2d to_footprint( const double base_to_rear, const double width); double get_area(const autoware_perception_msgs::msg::Shape & shape); Polygon2d expand_polygon(const Polygon2d & input_polygon, const double offset); -} // namespace autoware_utils +} // namespace autoware_utils_geometry #endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__BOOST_POLYGON_UTILS_HPP_ diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/ear_clipping.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/ear_clipping.hpp index 3de4b9f..c2e7c0d 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/ear_clipping.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/ear_clipping.hpp @@ -20,7 +20,7 @@ #include #include -namespace autoware_utils +namespace autoware_utils_geometry { struct LinkedPoint { @@ -101,6 +101,6 @@ std::vector triangulate(const alt::Polygon2d & polygon); * @return A vector of convex triangles representing the triangulated polygon. */ std::vector triangulate(const Polygon2d & polygon); -} // namespace autoware_utils +} // namespace autoware_utils_geometry #endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__EAR_CLIPPING_HPP_ diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/geometry.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/geometry.hpp index 714602e..aa540ad 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/geometry.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/geometry.hpp @@ -96,7 +96,7 @@ inline void doTransform( #endif } // namespace tf2 -namespace autoware_utils +namespace autoware_utils_geometry { // TODO(Takagi, Isamu): Move to each function. @@ -593,6 +593,6 @@ std::optional intersect( */ bool intersects_convex(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2); -} // namespace autoware_utils +} // namespace autoware_utils_geometry #endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__GEOMETRY_HPP_ diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/gjk_2d.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/gjk_2d.hpp index 3439c06..7a0453f 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/gjk_2d.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/gjk_2d.hpp @@ -17,13 +17,13 @@ #include "autoware_utils_geometry/geometry/boost_geometry.hpp" -namespace autoware_utils::gjk +namespace autoware_utils_geometry::gjk { /** * @brief Check if 2 convex polygons intersect using the GJK algorithm * @details much faster than boost::geometry::overlaps() but limited to convex polygons */ bool intersects(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2); -} // namespace autoware_utils::gjk +} // namespace autoware_utils_geometry::gjk #endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__GJK_2D_HPP_ diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/pose_deviation.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/pose_deviation.hpp index 0df6359..b9de7a8 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/pose_deviation.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/pose_deviation.hpp @@ -18,7 +18,7 @@ #include #include -namespace autoware_utils +namespace autoware_utils_geometry { struct PoseDeviation { @@ -39,6 +39,6 @@ double calc_yaw_deviation( PoseDeviation calc_pose_deviation( const geometry_msgs::msg::Pose & base_pose, const geometry_msgs::msg::Pose & target_pose); -} // namespace autoware_utils +} // namespace autoware_utils_geometry #endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__POSE_DEVIATION_HPP_ diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_concave_polygon.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_concave_polygon.hpp index c29ea6f..8a88381 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_concave_polygon.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_concave_polygon.hpp @@ -20,7 +20,7 @@ #include #include -namespace autoware_utils +namespace autoware_utils_geometry { /// @brief generate a random non-convex polygon /// @param vertices number of vertices for the desired polygon @@ -42,6 +42,6 @@ bool test_intersection( const std::function< bool(const autoware_utils::Polygon2d &, const autoware_utils::Polygon2d &)> &); -} // namespace autoware_utils +} // namespace autoware_utils_geometry #endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_convex_polygon.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_convex_polygon.hpp index aa756c9..f76f307 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_convex_polygon.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_convex_polygon.hpp @@ -17,13 +17,13 @@ #include -namespace autoware_utils +namespace autoware_utils_geometry { /// @brief generate a random convex polygon /// @param vertices number of vertices for the desired polygon /// @param max points will be generated in the range [-max,max] /// @details algorithm from https://cglab.ca/~sander/misc/ConvexGeneration/convex.html Polygon2d random_convex_polygon(const size_t vertices, const double max); -} // namespace autoware_utils +} // namespace autoware_utils_geometry #endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__RANDOM_CONVEX_POLYGON_HPP_ diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/sat_2d.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/sat_2d.hpp index aa735ab..1abfb24 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/sat_2d.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/sat_2d.hpp @@ -17,7 +17,7 @@ #include "autoware_utils_geometry/geometry/boost_geometry.hpp" -namespace autoware_utils::sat +namespace autoware_utils_geometry::sat { /** * @brief Check if 2 convex polygons intersect using the SAT algorithm @@ -25,6 +25,6 @@ namespace autoware_utils::sat */ bool intersects(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2); -} // namespace autoware_utils::sat +} // namespace autoware_utils_geometry::sat #endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__SAT_2D_HPP_ diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/msg/covariance.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/msg/covariance.hpp index 3d6bc34..7fee287 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/msg/covariance.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/msg/covariance.hpp @@ -15,7 +15,7 @@ #ifndef AUTOWARE_UTILS_GEOMETRY__MSG__COVARIANCE_HPP_ #define AUTOWARE_UTILS_GEOMETRY__MSG__COVARIANCE_HPP_ -namespace autoware_utils +namespace autoware_utils_geometry { namespace xyz_covariance_index { @@ -115,6 +115,6 @@ enum XYZ_UPPER_COV_IDX { Z_Z = 5, }; } // namespace xyz_upper_covariance_index -} // namespace autoware_utils +} // namespace autoware_utils_geometry #endif // AUTOWARE_UTILS_GEOMETRY__MSG__COVARIANCE_HPP_ diff --git a/autoware_utils_geometry/package.xml b/autoware_utils_geometry/package.xml index d6b2276..066a121 100644 --- a/autoware_utils_geometry/package.xml +++ b/autoware_utils_geometry/package.xml @@ -16,6 +16,7 @@ autoware_internal_planning_msgs autoware_utils_math + libboost-system-dev tf2 tf2_eigen tf2_geometry_msgs diff --git a/autoware_utils_geometry/src/geometry/alt_geometry.cpp b/autoware_utils_geometry/src/geometry/alt_geometry.cpp index 0dad4e4..7233aa7 100644 --- a/autoware_utils_geometry/src/geometry/alt_geometry.cpp +++ b/autoware_utils_geometry/src/geometry/alt_geometry.cpp @@ -19,7 +19,7 @@ #include #include -namespace autoware_utils +namespace autoware_utils_geometry { // Alternatives for Boost.Geometry ---------------------------------------------------------------- namespace alt @@ -644,4 +644,4 @@ bool within( return true; } -} // namespace autoware_utils +} // namespace autoware_utils_geometry diff --git a/autoware_utils_geometry/src/geometry/boost_polygon_utils.cpp b/autoware_utils_geometry/src/geometry/boost_polygon_utils.cpp index 8db07c5..b1e1351 100644 --- a/autoware_utils_geometry/src/geometry/boost_polygon_utils.cpp +++ b/autoware_utils_geometry/src/geometry/boost_polygon_utils.cpp @@ -68,7 +68,7 @@ double get_circle_area(const geometry_msgs::msg::Vector3 & dimensions) } } // namespace -namespace autoware_utils +namespace autoware_utils_geometry { bool is_clockwise(const Polygon2d & polygon) { @@ -264,4 +264,4 @@ Polygon2d expand_polygon(const Polygon2d & input_polygon, const double offset) boost::geometry::correct(expanded_polygon); return expanded_polygon; } -} // namespace autoware_utils +} // namespace autoware_utils_geometry diff --git a/autoware_utils_geometry/src/geometry/ear_clipping.cpp b/autoware_utils_geometry/src/geometry/ear_clipping.cpp index e89895b..b7e5022 100644 --- a/autoware_utils_geometry/src/geometry/ear_clipping.cpp +++ b/autoware_utils_geometry/src/geometry/ear_clipping.cpp @@ -18,7 +18,7 @@ #include #include -namespace autoware_utils +namespace autoware_utils_geometry { void remove_point(const std::size_t p_index, std::vector & points) @@ -631,4 +631,4 @@ std::vector triangulate(const Polygon2d & poly) } return triangles; } -} // namespace autoware_utils +} // namespace autoware_utils_geometry diff --git a/autoware_utils_geometry/src/geometry/geometry.cpp b/autoware_utils_geometry/src/geometry/geometry.cpp index 7aed66d..2b6dc1f 100644 --- a/autoware_utils_geometry/src/geometry/geometry.cpp +++ b/autoware_utils_geometry/src/geometry/geometry.cpp @@ -36,7 +36,7 @@ void fromMsg(const geometry_msgs::msg::PoseStamped & msg, tf2::Stamped -namespace autoware_utils::gjk +namespace autoware_utils_geometry::gjk { namespace @@ -147,4 +147,4 @@ bool intersects(const Polygon2d & convex_polygon1, const Polygon2d & convex_poly } return true; } -} // namespace autoware_utils::gjk +} // namespace autoware_utils_geometry::gjk diff --git a/autoware_utils_geometry/src/geometry/pose_deviation.cpp b/autoware_utils_geometry/src/geometry/pose_deviation.cpp index 3197e17..fa542c3 100644 --- a/autoware_utils_geometry/src/geometry/pose_deviation.cpp +++ b/autoware_utils_geometry/src/geometry/pose_deviation.cpp @@ -28,7 +28,7 @@ #include #endif -namespace autoware_utils +namespace autoware_utils_geometry { double calc_lateral_deviation( @@ -82,4 +82,4 @@ PoseDeviation calc_pose_deviation( return deviation; } -} // namespace autoware_utils +} // namespace autoware_utils_geometry diff --git a/autoware_utils_geometry/src/geometry/random_concave_polygon.cpp b/autoware_utils_geometry/src/geometry/random_concave_polygon.cpp index 6b151a5..d5f1aba 100644 --- a/autoware_utils_geometry/src/geometry/random_concave_polygon.cpp +++ b/autoware_utils_geometry/src/geometry/random_concave_polygon.cpp @@ -29,7 +29,7 @@ #include #include -namespace autoware_utils +namespace autoware_utils_geometry { namespace { @@ -404,4 +404,4 @@ std::optional random_concave_polygon(const size_t vertices, const dou } return poly; } -} // namespace autoware_utils +} // namespace autoware_utils_geometry diff --git a/autoware_utils_geometry/src/geometry/random_convex_polygon.cpp b/autoware_utils_geometry/src/geometry/random_convex_polygon.cpp index 9dd2a78..ea9e79b 100644 --- a/autoware_utils_geometry/src/geometry/random_convex_polygon.cpp +++ b/autoware_utils_geometry/src/geometry/random_convex_polygon.cpp @@ -20,7 +20,7 @@ #include #include -namespace autoware_utils +namespace autoware_utils_geometry { namespace { @@ -110,4 +110,4 @@ Polygon2d random_convex_polygon(const size_t vertices, const double max) boost::geometry::correct(poly); return poly; } -} // namespace autoware_utils +} // namespace autoware_utils_geometry diff --git a/autoware_utils_geometry/src/geometry/sat_2d.cpp b/autoware_utils_geometry/src/geometry/sat_2d.cpp index f78a464..682fed7 100644 --- a/autoware_utils_geometry/src/geometry/sat_2d.cpp +++ b/autoware_utils_geometry/src/geometry/sat_2d.cpp @@ -16,7 +16,7 @@ #include -namespace autoware_utils::sat +namespace autoware_utils_geometry::sat { namespace @@ -79,4 +79,4 @@ bool intersects(const Polygon2d & convex_polygon1, const Polygon2d & convex_poly has_no_separating_axis(convex_polygon2, convex_polygon1); } -} // namespace autoware_utils::sat +} // namespace autoware_utils_geometry::sat From 7162fa281170ba04a18ff62813fc2a75a4e886f6 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" Date: Tue, 11 Mar 2025 13:21:29 +0900 Subject: [PATCH 4/6] fix namespace Signed-off-by: Takagi, Isamu --- autoware_utils_geometry/README.md | 8 ++-- .../geometry/alt_geometry.hpp | 12 ++++-- .../geometry/boost_geometry.hpp | 10 ++--- .../geometry/random_concave_polygon.hpp | 8 ++-- .../src/geometry/alt_geometry.cpp | 11 ++--- .../src/geometry/boost_polygon_utils.cpp | 41 ++++++++++--------- .../src/geometry/geometry.cpp | 2 +- .../src/geometry/random_concave_polygon.cpp | 9 ++-- 8 files changed, 54 insertions(+), 47 deletions(-) diff --git a/autoware_utils_geometry/README.md b/autoware_utils_geometry/README.md index a409c27..f3c5475 100644 --- a/autoware_utils_geometry/README.md +++ b/autoware_utils_geometry/README.md @@ -69,17 +69,17 @@ int main(int argc, char * argv[]) { auto node = rclcpp::Node::make_shared("polygon_node"); // Create a polygon - autoware_utils::Polygon2d polygon; + autoware_utils_geometry::Polygon2d polygon; // Assume polygon is populated with points // Rotate the polygon by 90 degrees - autoware_utils::Polygon2d rotated_polygon = autoware_utils::rotate_polygon(polygon, M_PI / 2); + autoware_utils_geometry::Polygon2d rotated_polygon = autoware_utils_geometry::rotate_polygon(polygon, M_PI / 2); // Expand the polygon by an offset - autoware_utils::Polygon2d expanded_polygon = autoware_utils::expand_polygon(polygon, 1.0); + autoware_utils_geometry::Polygon2d expanded_polygon = autoware_utils_geometry::expand_polygon(polygon, 1.0); // Check if the polygon is clockwise - bool is_clockwise = autoware_utils::is_clockwise(polygon); + bool is_clockwise = autoware_utils_geometry::is_clockwise(polygon); rclcpp::shutdown(); return 0; diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/alt_geometry.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/alt_geometry.hpp index 28af483..1d7e271 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/alt_geometry.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/alt_geometry.hpp @@ -35,7 +35,9 @@ class Vector2d Vector2d(const double x, const double y) : x_(x), y_(y) {} - explicit Vector2d(const autoware_utils::Point2d & point) : x_(point.x()), y_(point.y()) {} + explicit Vector2d(const autoware_utils_geometry::Point2d & point) : x_(point.x()), y_(point.y()) + { + } double cross(const Vector2d & other) const { return x_ * other.y() - y_ * other.x(); } @@ -99,7 +101,8 @@ class Polygon2d static std::optional create( PointList2d && outer, std::vector && inners) noexcept; - static std::optional create(const autoware_utils::Polygon2d & polygon) noexcept; + static std::optional create( + const autoware_utils_geometry::Polygon2d & polygon) noexcept; const PointList2d & outer() const noexcept { return outer_; } @@ -109,7 +112,7 @@ class Polygon2d std::vector & inners() noexcept { return inners_; } - autoware_utils::Polygon2d to_boost() const; + autoware_utils_geometry::Polygon2d to_boost() const; protected: Polygon2d(const PointList2d & outer, const std::vector & inners) @@ -134,7 +137,8 @@ class ConvexPolygon2d : public Polygon2d static std::optional create(PointList2d && vertices) noexcept; - static std::optional create(const autoware_utils::Polygon2d & polygon) noexcept; + static std::optional create( + const autoware_utils_geometry::Polygon2d & polygon) noexcept; const PointList2d & vertices() const noexcept { return outer(); } diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_geometry.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_geometry.hpp index 1440a79..f892189 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_geometry.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_geometry.hpp @@ -95,10 +95,10 @@ inline Point3d from_msg(const geometry_msgs::msg::Point & msg) } } // namespace autoware_utils_geometry -BOOST_GEOMETRY_REGISTER_POINT_2D( // NOLINT - autoware_utils::Point2d, double, cs::cartesian, x(), y()) // NOLINT -BOOST_GEOMETRY_REGISTER_POINT_3D( // NOLINT - autoware_utils::Point3d, double, cs::cartesian, x(), y(), z()) // NOLINT -BOOST_GEOMETRY_REGISTER_RING(autoware_utils::LinearRing2d) // NOLINT +BOOST_GEOMETRY_REGISTER_POINT_2D( // NOLINT + autoware_utils_geometry::Point2d, double, cs::cartesian, x(), y()) // NOLINT +BOOST_GEOMETRY_REGISTER_POINT_3D( // NOLINT + autoware_utils_geometry::Point3d, double, cs::cartesian, x(), y(), z()) // NOLINT +BOOST_GEOMETRY_REGISTER_RING(autoware_utils_geometry::LinearRing2d) // NOLINT #endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__BOOST_GEOMETRY_HPP_ diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_concave_polygon.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_concave_polygon.hpp index 8a88381..b5d05ea 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_concave_polygon.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_concave_polygon.hpp @@ -37,10 +37,10 @@ std::optional random_concave_polygon(const size_t vertices, const dou /// otherwise false. /// @return True if at least one pair of polygons intersects, otherwise false. bool test_intersection( - const std::vector & polygons1, - const std::vector & polygons2, - const std::function< - bool(const autoware_utils::Polygon2d &, const autoware_utils::Polygon2d &)> &); + const std::vector & polygons1, + const std::vector & polygons2, + const std::function &); } // namespace autoware_utils_geometry diff --git a/autoware_utils_geometry/src/geometry/alt_geometry.cpp b/autoware_utils_geometry/src/geometry/alt_geometry.cpp index 7233aa7..831711a 100644 --- a/autoware_utils_geometry/src/geometry/alt_geometry.cpp +++ b/autoware_utils_geometry/src/geometry/alt_geometry.cpp @@ -62,7 +62,8 @@ std::optional Polygon2d::create( return poly; } -std::optional Polygon2d::create(const autoware_utils::Polygon2d & polygon) noexcept +std::optional Polygon2d::create( + const autoware_utils_geometry::Polygon2d & polygon) noexcept { PointList2d outer; for (const auto & point : polygon.outer()) { @@ -84,16 +85,16 @@ std::optional Polygon2d::create(const autoware_utils::Polygon2d & pol return Polygon2d::create(outer, inners); } -autoware_utils::Polygon2d Polygon2d::to_boost() const +autoware_utils_geometry::Polygon2d Polygon2d::to_boost() const { - autoware_utils::Polygon2d polygon; + autoware_utils_geometry::Polygon2d polygon; for (const auto & point : outer_) { polygon.outer().emplace_back(point.x(), point.y()); } for (const auto & inner : inners_) { - autoware_utils::LinearRing2d _inner; + autoware_utils_geometry::LinearRing2d _inner; for (const auto & point : inner) { _inner.emplace_back(point.x(), point.y()); } @@ -136,7 +137,7 @@ std::optional ConvexPolygon2d::create(PointList2d && vertices) } std::optional ConvexPolygon2d::create( - const autoware_utils::Polygon2d & polygon) noexcept + const autoware_utils_geometry::Polygon2d & polygon) noexcept { PointList2d vertices; for (const auto & point : polygon.outer()) { diff --git a/autoware_utils_geometry/src/geometry/boost_polygon_utils.cpp b/autoware_utils_geometry/src/geometry/boost_polygon_utils.cpp index b1e1351..cae8525 100644 --- a/autoware_utils_geometry/src/geometry/boost_polygon_utils.cpp +++ b/autoware_utils_geometry/src/geometry/boost_polygon_utils.cpp @@ -23,8 +23,8 @@ namespace { namespace bg = boost::geometry; -using autoware_utils::Point2d; -using autoware_utils::Polygon2d; +using autoware_utils_geometry::Point2d; +using autoware_utils_geometry::Polygon2d; void append_point_to_polygon(Polygon2d & polygon, const geometry_msgs::msg::Point & geom_point) { @@ -123,16 +123,16 @@ Polygon2d to_polygon2d( Polygon2d polygon; if (shape.type == autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { - const auto point0 = autoware_utils::calc_offset_pose( + const auto point0 = autoware_utils_geometry::calc_offset_pose( pose, shape.dimensions.x / 2.0, shape.dimensions.y / 2.0, 0.0) .position; - const auto point1 = autoware_utils::calc_offset_pose( + const auto point1 = autoware_utils_geometry::calc_offset_pose( pose, -shape.dimensions.x / 2.0, shape.dimensions.y / 2.0, 0.0) .position; - const auto point2 = autoware_utils::calc_offset_pose( + const auto point2 = autoware_utils_geometry::calc_offset_pose( pose, -shape.dimensions.x / 2.0, -shape.dimensions.y / 2.0, 0.0) .position; - const auto point3 = autoware_utils::calc_offset_pose( + const auto point3 = autoware_utils_geometry::calc_offset_pose( pose, shape.dimensions.x / 2.0, -shape.dimensions.y / 2.0, 0.0) .position; @@ -179,20 +179,24 @@ Polygon2d to_polygon2d( return is_clockwise(polygon) ? polygon : inverse_clockwise(polygon); } -autoware_utils::Polygon2d to_polygon2d(const autoware_perception_msgs::msg::DetectedObject & object) +autoware_utils_geometry::Polygon2d to_polygon2d( + const autoware_perception_msgs::msg::DetectedObject & object) { - return autoware_utils::to_polygon2d(object.kinematics.pose_with_covariance.pose, object.shape); + return autoware_utils_geometry::to_polygon2d( + object.kinematics.pose_with_covariance.pose, object.shape); } -autoware_utils::Polygon2d to_polygon2d(const autoware_perception_msgs::msg::TrackedObject & object) +autoware_utils_geometry::Polygon2d to_polygon2d( + const autoware_perception_msgs::msg::TrackedObject & object) { - return autoware_utils::to_polygon2d(object.kinematics.pose_with_covariance.pose, object.shape); + return autoware_utils_geometry::to_polygon2d( + object.kinematics.pose_with_covariance.pose, object.shape); } -autoware_utils::Polygon2d to_polygon2d( +autoware_utils_geometry::Polygon2d to_polygon2d( const autoware_perception_msgs::msg::PredictedObject & object) { - return autoware_utils::to_polygon2d( + return autoware_utils_geometry::to_polygon2d( object.kinematics.initial_pose_with_covariance.pose, object.shape); } @@ -200,15 +204,12 @@ Polygon2d to_footprint( const geometry_msgs::msg::Pose & base_link_pose, const double base_to_front, const double base_to_rear, const double width) { + using autoware_utils_geometry::calc_offset_pose; Polygon2d polygon; - const auto point0 = - autoware_utils::calc_offset_pose(base_link_pose, base_to_front, width / 2.0, 0.0).position; - const auto point1 = - autoware_utils::calc_offset_pose(base_link_pose, base_to_front, -width / 2.0, 0.0).position; - const auto point2 = - autoware_utils::calc_offset_pose(base_link_pose, -base_to_rear, -width / 2.0, 0.0).position; - const auto point3 = - autoware_utils::calc_offset_pose(base_link_pose, -base_to_rear, width / 2.0, 0.0).position; + const auto point0 = calc_offset_pose(base_link_pose, base_to_front, width / 2.0, 0.0).position; + const auto point1 = calc_offset_pose(base_link_pose, base_to_front, -width / 2.0, 0.0).position; + const auto point2 = calc_offset_pose(base_link_pose, -base_to_rear, -width / 2.0, 0.0).position; + const auto point3 = calc_offset_pose(base_link_pose, -base_to_rear, width / 2.0, 0.0).position; append_point_to_polygon(polygon, point0); append_point_to_polygon(polygon, point1); diff --git a/autoware_utils_geometry/src/geometry/geometry.cpp b/autoware_utils_geometry/src/geometry/geometry.cpp index 2b6dc1f..fb3c153 100644 --- a/autoware_utils_geometry/src/geometry/geometry.cpp +++ b/autoware_utils_geometry/src/geometry/geometry.cpp @@ -213,7 +213,7 @@ geometry_msgs::msg::Point32 transform_point( { const auto point = geometry_msgs::build().x(point32.x).y(point32.y).z(point32.z); - const auto transformed_point = autoware_utils::transform_point(point, pose); + const auto transformed_point = autoware_utils_geometry::transform_point(point, pose); return geometry_msgs::build() .x(transformed_point.x) .y(transformed_point.y) diff --git a/autoware_utils_geometry/src/geometry/random_concave_polygon.cpp b/autoware_utils_geometry/src/geometry/random_concave_polygon.cpp index d5f1aba..2851fca 100644 --- a/autoware_utils_geometry/src/geometry/random_concave_polygon.cpp +++ b/autoware_utils_geometry/src/geometry/random_concave_polygon.cpp @@ -287,7 +287,7 @@ Polygon2d inward_denting(LinearRing2d & ring) } // namespace /// @brief checks if a polygon is convex -bool is_convex(const autoware_utils::Polygon2d & polygon) +bool is_convex(const autoware_utils_geometry::Polygon2d & polygon) { const auto & outer_ring = polygon.outer(); size_t num_points = outer_ring.size(); @@ -324,9 +324,10 @@ bool is_convex(const autoware_utils::Polygon2d & polygon) /// @brief checks for collisions between two vectors of convex polygons using a specified collision /// detection algorithm bool test_intersection( - const std::vector & polygons1, - const std::vector & polygons2, - const std::function & + const std::vector & polygons1, + const std::vector & polygons2, + const std::function< + bool(const autoware_utils_geometry::Polygon2d &, const autoware_utils_geometry::Polygon2d &)> & intersection_func) { for (const auto & poly1 : polygons1) { From f0924124dab7b945951e2b1fdf0a6bf14558ff79 Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" Date: Thu, 13 Mar 2025 19:39:32 +0900 Subject: [PATCH 5/6] fix path Signed-off-by: Takagi, Isamu --- .../include/autoware_utils/geometry/alt_geometry.hpp | 2 +- .../include/autoware_utils/geometry/boost_geometry.hpp | 2 +- .../include/autoware_utils/geometry/boost_polygon_utils.hpp | 2 +- .../include/autoware_utils/geometry/ear_clipping.hpp | 2 +- autoware_utils/include/autoware_utils/geometry/geometry.hpp | 2 +- autoware_utils/include/autoware_utils/geometry/gjk_2d.hpp | 2 +- .../include/autoware_utils/geometry/pose_deviation.hpp | 2 +- .../autoware_utils/geometry/random_concave_polygon.hpp | 2 +- .../autoware_utils/geometry/random_convex_polygon.hpp | 2 +- autoware_utils/include/autoware_utils/geometry/sat_2d.hpp | 2 +- .../autoware_utils_geometry/{geometry => }/alt_geometry.hpp | 6 +++--- .../{geometry => }/boost_geometry.hpp | 6 +++--- .../{geometry => }/boost_polygon_utils.hpp | 6 +++--- .../autoware_utils_geometry/{geometry => }/ear_clipping.hpp | 6 +++--- .../autoware_utils_geometry/{geometry => }/geometry.hpp | 6 +++--- .../autoware_utils_geometry/{geometry => }/gjk_2d.hpp | 6 +++--- .../{geometry => }/pose_deviation.hpp | 6 +++--- .../{geometry => }/random_concave_polygon.hpp | 6 +++--- .../{geometry => }/random_convex_polygon.hpp | 6 +++--- .../autoware_utils_geometry/{geometry => }/sat_2d.hpp | 6 +++--- 20 files changed, 40 insertions(+), 40 deletions(-) rename autoware_utils_geometry/include/autoware_utils_geometry/{geometry => }/alt_geometry.hpp (96%) rename autoware_utils_geometry/include/autoware_utils_geometry/{geometry => }/boost_geometry.hpp (94%) rename autoware_utils_geometry/include/autoware_utils_geometry/{geometry => }/boost_polygon_utils.hpp (91%) rename autoware_utils_geometry/include/autoware_utils_geometry/{geometry => }/ear_clipping.hpp (95%) rename autoware_utils_geometry/include/autoware_utils_geometry/{geometry => }/geometry.hpp (99%) rename autoware_utils_geometry/include/autoware_utils_geometry/{geometry => }/gjk_2d.hpp (85%) rename autoware_utils_geometry/include/autoware_utils_geometry/{geometry => }/pose_deviation.hpp (87%) rename autoware_utils_geometry/include/autoware_utils_geometry/{geometry => }/random_concave_polygon.hpp (89%) rename autoware_utils_geometry/include/autoware_utils_geometry/{geometry => }/random_convex_polygon.hpp (83%) rename autoware_utils_geometry/include/autoware_utils_geometry/{geometry => }/sat_2d.hpp (85%) diff --git a/autoware_utils/include/autoware_utils/geometry/alt_geometry.hpp b/autoware_utils/include/autoware_utils/geometry/alt_geometry.hpp index fdd8deb..ac1ea55 100644 --- a/autoware_utils/include/autoware_utils/geometry/alt_geometry.hpp +++ b/autoware_utils/include/autoware_utils/geometry/alt_geometry.hpp @@ -18,7 +18,7 @@ // NOLINTBEGIN(build/namespaces, whitespace/line_length) // clang-format off -#include +#include namespace autoware_utils { using namespace autoware_utils_geometry; } // clang-format on diff --git a/autoware_utils/include/autoware_utils/geometry/boost_geometry.hpp b/autoware_utils/include/autoware_utils/geometry/boost_geometry.hpp index 33a7110..f150736 100644 --- a/autoware_utils/include/autoware_utils/geometry/boost_geometry.hpp +++ b/autoware_utils/include/autoware_utils/geometry/boost_geometry.hpp @@ -18,7 +18,7 @@ // NOLINTBEGIN(build/namespaces, whitespace/line_length) // clang-format off -#include +#include namespace autoware_utils { using namespace autoware_utils_geometry; } // clang-format on diff --git a/autoware_utils/include/autoware_utils/geometry/boost_polygon_utils.hpp b/autoware_utils/include/autoware_utils/geometry/boost_polygon_utils.hpp index 2bca3dd..dc17824 100644 --- a/autoware_utils/include/autoware_utils/geometry/boost_polygon_utils.hpp +++ b/autoware_utils/include/autoware_utils/geometry/boost_polygon_utils.hpp @@ -18,7 +18,7 @@ // NOLINTBEGIN(build/namespaces, whitespace/line_length) // clang-format off -#include +#include namespace autoware_utils { using namespace autoware_utils_geometry; } // clang-format on diff --git a/autoware_utils/include/autoware_utils/geometry/ear_clipping.hpp b/autoware_utils/include/autoware_utils/geometry/ear_clipping.hpp index 1b301ce..d9b734d 100644 --- a/autoware_utils/include/autoware_utils/geometry/ear_clipping.hpp +++ b/autoware_utils/include/autoware_utils/geometry/ear_clipping.hpp @@ -18,7 +18,7 @@ // NOLINTBEGIN(build/namespaces, whitespace/line_length) // clang-format off -#include +#include namespace autoware_utils { using namespace autoware_utils_geometry; } // clang-format on diff --git a/autoware_utils/include/autoware_utils/geometry/geometry.hpp b/autoware_utils/include/autoware_utils/geometry/geometry.hpp index b24dd20..36748fe 100644 --- a/autoware_utils/include/autoware_utils/geometry/geometry.hpp +++ b/autoware_utils/include/autoware_utils/geometry/geometry.hpp @@ -18,7 +18,7 @@ // NOLINTBEGIN(build/namespaces, whitespace/line_length) // clang-format off -#include +#include namespace autoware_utils { using namespace autoware_utils_geometry; } // clang-format on diff --git a/autoware_utils/include/autoware_utils/geometry/gjk_2d.hpp b/autoware_utils/include/autoware_utils/geometry/gjk_2d.hpp index 24920a5..6347ced 100644 --- a/autoware_utils/include/autoware_utils/geometry/gjk_2d.hpp +++ b/autoware_utils/include/autoware_utils/geometry/gjk_2d.hpp @@ -18,7 +18,7 @@ // NOLINTBEGIN(build/namespaces, whitespace/line_length) // clang-format off -#include +#include namespace autoware_utils { using namespace autoware_utils_geometry; } // clang-format on diff --git a/autoware_utils/include/autoware_utils/geometry/pose_deviation.hpp b/autoware_utils/include/autoware_utils/geometry/pose_deviation.hpp index 7e833c6..7cfb1df 100644 --- a/autoware_utils/include/autoware_utils/geometry/pose_deviation.hpp +++ b/autoware_utils/include/autoware_utils/geometry/pose_deviation.hpp @@ -18,7 +18,7 @@ // NOLINTBEGIN(build/namespaces, whitespace/line_length) // clang-format off -#include +#include namespace autoware_utils { using namespace autoware_utils_geometry; } // clang-format on diff --git a/autoware_utils/include/autoware_utils/geometry/random_concave_polygon.hpp b/autoware_utils/include/autoware_utils/geometry/random_concave_polygon.hpp index 6bee72a..b039627 100644 --- a/autoware_utils/include/autoware_utils/geometry/random_concave_polygon.hpp +++ b/autoware_utils/include/autoware_utils/geometry/random_concave_polygon.hpp @@ -18,7 +18,7 @@ // NOLINTBEGIN(build/namespaces, whitespace/line_length) // clang-format off -#include +#include namespace autoware_utils { using namespace autoware_utils_geometry; } // clang-format on diff --git a/autoware_utils/include/autoware_utils/geometry/random_convex_polygon.hpp b/autoware_utils/include/autoware_utils/geometry/random_convex_polygon.hpp index b621dd0..33cd0c1 100644 --- a/autoware_utils/include/autoware_utils/geometry/random_convex_polygon.hpp +++ b/autoware_utils/include/autoware_utils/geometry/random_convex_polygon.hpp @@ -18,7 +18,7 @@ // NOLINTBEGIN(build/namespaces, whitespace/line_length) // clang-format off -#include +#include namespace autoware_utils { using namespace autoware_utils_geometry; } // clang-format on diff --git a/autoware_utils/include/autoware_utils/geometry/sat_2d.hpp b/autoware_utils/include/autoware_utils/geometry/sat_2d.hpp index f5fd8e4..ef4f150 100644 --- a/autoware_utils/include/autoware_utils/geometry/sat_2d.hpp +++ b/autoware_utils/include/autoware_utils/geometry/sat_2d.hpp @@ -18,7 +18,7 @@ // NOLINTBEGIN(build/namespaces, whitespace/line_length) // clang-format off -#include +#include namespace autoware_utils { using namespace autoware_utils_geometry; } // clang-format on diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/alt_geometry.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/alt_geometry.hpp similarity index 96% rename from autoware_utils_geometry/include/autoware_utils_geometry/geometry/alt_geometry.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/alt_geometry.hpp index 1d7e271..50c727a 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/alt_geometry.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/alt_geometry.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY__ALT_GEOMETRY_HPP_ -#define AUTOWARE_UTILS_GEOMETRY__GEOMETRY__ALT_GEOMETRY_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__ALT_GEOMETRY_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__ALT_GEOMETRY_HPP_ #include "autoware_utils_geometry/geometry/boost_geometry.hpp" @@ -201,4 +201,4 @@ bool within( const alt::ConvexPolygon2d & poly_contained, const alt::ConvexPolygon2d & poly_containing); } // namespace autoware_utils_geometry -#endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__ALT_GEOMETRY_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__ALT_GEOMETRY_HPP_ diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_geometry.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/boost_geometry.hpp similarity index 94% rename from autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_geometry.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/boost_geometry.hpp index f892189..3823b2f 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_geometry.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/boost_geometry.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY__BOOST_GEOMETRY_HPP_ -#define AUTOWARE_UTILS_GEOMETRY__GEOMETRY__BOOST_GEOMETRY_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__BOOST_GEOMETRY_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__BOOST_GEOMETRY_HPP_ #include #include @@ -101,4 +101,4 @@ BOOST_GEOMETRY_REGISTER_POINT_3D( // NO autoware_utils_geometry::Point3d, double, cs::cartesian, x(), y(), z()) // NOLINT BOOST_GEOMETRY_REGISTER_RING(autoware_utils_geometry::LinearRing2d) // NOLINT -#endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__BOOST_GEOMETRY_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__BOOST_GEOMETRY_HPP_ diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_polygon_utils.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/boost_polygon_utils.hpp similarity index 91% rename from autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_polygon_utils.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/boost_polygon_utils.hpp index 0d0bba3..e6eec13 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/boost_polygon_utils.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/boost_polygon_utils.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY__BOOST_POLYGON_UTILS_HPP_ -#define AUTOWARE_UTILS_GEOMETRY__GEOMETRY__BOOST_POLYGON_UTILS_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__BOOST_POLYGON_UTILS_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__BOOST_POLYGON_UTILS_HPP_ #include "autoware_utils_geometry/geometry/boost_geometry.hpp" @@ -49,4 +49,4 @@ double get_area(const autoware_perception_msgs::msg::Shape & shape); Polygon2d expand_polygon(const Polygon2d & input_polygon, const double offset); } // namespace autoware_utils_geometry -#endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__BOOST_POLYGON_UTILS_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__BOOST_POLYGON_UTILS_HPP_ diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/ear_clipping.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/ear_clipping.hpp similarity index 95% rename from autoware_utils_geometry/include/autoware_utils_geometry/geometry/ear_clipping.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/ear_clipping.hpp index c2e7c0d..e65eb95 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/ear_clipping.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/ear_clipping.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY__EAR_CLIPPING_HPP_ -#define AUTOWARE_UTILS_GEOMETRY__GEOMETRY__EAR_CLIPPING_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__EAR_CLIPPING_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__EAR_CLIPPING_HPP_ #include "autoware_utils_geometry/geometry/alt_geometry.hpp" @@ -103,4 +103,4 @@ std::vector triangulate(const alt::Polygon2d & polygon); std::vector triangulate(const Polygon2d & polygon); } // namespace autoware_utils_geometry -#endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__EAR_CLIPPING_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__EAR_CLIPPING_HPP_ diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/geometry.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry.hpp similarity index 99% rename from autoware_utils_geometry/include/autoware_utils_geometry/geometry/geometry.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/geometry.hpp index aa540ad..171aa52 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/geometry.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY__GEOMETRY_HPP_ -#define AUTOWARE_UTILS_GEOMETRY__GEOMETRY__GEOMETRY_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__GEOMETRY_HPP_ #include "autoware_utils_geometry/geometry/boost_geometry.hpp" #include "autoware_utils_geometry/msg/covariance.hpp" @@ -595,4 +595,4 @@ bool intersects_convex(const Polygon2d & convex_polygon1, const Polygon2d & conv } // namespace autoware_utils_geometry -#endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__GEOMETRY_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY_HPP_ diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/gjk_2d.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/gjk_2d.hpp similarity index 85% rename from autoware_utils_geometry/include/autoware_utils_geometry/geometry/gjk_2d.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/gjk_2d.hpp index 7a0453f..2276adf 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/gjk_2d.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/gjk_2d.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY__GJK_2D_HPP_ -#define AUTOWARE_UTILS_GEOMETRY__GEOMETRY__GJK_2D_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__GJK_2D_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__GJK_2D_HPP_ #include "autoware_utils_geometry/geometry/boost_geometry.hpp" @@ -26,4 +26,4 @@ namespace autoware_utils_geometry::gjk bool intersects(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2); } // namespace autoware_utils_geometry::gjk -#endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__GJK_2D_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__GJK_2D_HPP_ diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/pose_deviation.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/pose_deviation.hpp similarity index 87% rename from autoware_utils_geometry/include/autoware_utils_geometry/geometry/pose_deviation.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/pose_deviation.hpp index b9de7a8..0cee98d 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/pose_deviation.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/pose_deviation.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY__POSE_DEVIATION_HPP_ -#define AUTOWARE_UTILS_GEOMETRY__GEOMETRY__POSE_DEVIATION_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__POSE_DEVIATION_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__POSE_DEVIATION_HPP_ #include #include @@ -41,4 +41,4 @@ PoseDeviation calc_pose_deviation( } // namespace autoware_utils_geometry -#endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__POSE_DEVIATION_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__POSE_DEVIATION_HPP_ diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_concave_polygon.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/random_concave_polygon.hpp similarity index 89% rename from autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_concave_polygon.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/random_concave_polygon.hpp index b5d05ea..636caac 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_concave_polygon.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/random_concave_polygon.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ -#define AUTOWARE_UTILS_GEOMETRY__GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ #include @@ -44,4 +44,4 @@ bool test_intersection( } // namespace autoware_utils_geometry -#endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_convex_polygon.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/random_convex_polygon.hpp similarity index 83% rename from autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_convex_polygon.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/random_convex_polygon.hpp index f76f307..a9581c1 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/random_convex_polygon.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/random_convex_polygon.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY__RANDOM_CONVEX_POLYGON_HPP_ -#define AUTOWARE_UTILS_GEOMETRY__GEOMETRY__RANDOM_CONVEX_POLYGON_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__RANDOM_CONVEX_POLYGON_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__RANDOM_CONVEX_POLYGON_HPP_ #include @@ -26,4 +26,4 @@ namespace autoware_utils_geometry Polygon2d random_convex_polygon(const size_t vertices, const double max); } // namespace autoware_utils_geometry -#endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__RANDOM_CONVEX_POLYGON_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__RANDOM_CONVEX_POLYGON_HPP_ diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/sat_2d.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/sat_2d.hpp similarity index 85% rename from autoware_utils_geometry/include/autoware_utils_geometry/geometry/sat_2d.hpp rename to autoware_utils_geometry/include/autoware_utils_geometry/sat_2d.hpp index 1abfb24..c614789 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry/sat_2d.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/sat_2d.hpp @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY__SAT_2D_HPP_ -#define AUTOWARE_UTILS_GEOMETRY__GEOMETRY__SAT_2D_HPP_ +#ifndef AUTOWARE_UTILS_GEOMETRY__SAT_2D_HPP_ +#define AUTOWARE_UTILS_GEOMETRY__SAT_2D_HPP_ #include "autoware_utils_geometry/geometry/boost_geometry.hpp" @@ -27,4 +27,4 @@ bool intersects(const Polygon2d & convex_polygon1, const Polygon2d & convex_poly } // namespace autoware_utils_geometry::sat -#endif // AUTOWARE_UTILS_GEOMETRY__GEOMETRY__SAT_2D_HPP_ +#endif // AUTOWARE_UTILS_GEOMETRY__SAT_2D_HPP_ From 15eb6ef2625a326a46de75ec6e970ce34f2617ad Mon Sep 17 00:00:00 2001 From: "Takagi, Isamu" Date: Thu, 13 Mar 2025 19:45:14 +0900 Subject: [PATCH 6/6] fix include path Signed-off-by: Takagi, Isamu --- .../include/autoware_utils_geometry/alt_geometry.hpp | 2 +- .../include/autoware_utils_geometry/boost_polygon_utils.hpp | 2 +- .../include/autoware_utils_geometry/ear_clipping.hpp | 2 +- .../include/autoware_utils_geometry/geometry.hpp | 2 +- .../include/autoware_utils_geometry/gjk_2d.hpp | 2 +- .../autoware_utils_geometry/random_concave_polygon.hpp | 2 +- .../autoware_utils_geometry/random_convex_polygon.hpp | 2 +- .../include/autoware_utils_geometry/sat_2d.hpp | 2 +- autoware_utils_geometry/src/geometry/alt_geometry.cpp | 2 +- autoware_utils_geometry/src/geometry/boost_polygon_utils.cpp | 4 ++-- autoware_utils_geometry/src/geometry/ear_clipping.cpp | 2 +- autoware_utils_geometry/src/geometry/geometry.cpp | 4 ++-- autoware_utils_geometry/src/geometry/gjk_2d.cpp | 5 ++--- autoware_utils_geometry/src/geometry/pose_deviation.cpp | 2 +- .../src/geometry/random_concave_polygon.cpp | 4 ++-- .../src/geometry/random_convex_polygon.cpp | 2 +- autoware_utils_geometry/src/geometry/sat_2d.cpp | 2 +- 17 files changed, 21 insertions(+), 22 deletions(-) diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/alt_geometry.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/alt_geometry.hpp index 50c727a..0e63b72 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/alt_geometry.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/alt_geometry.hpp @@ -15,7 +15,7 @@ #ifndef AUTOWARE_UTILS_GEOMETRY__ALT_GEOMETRY_HPP_ #define AUTOWARE_UTILS_GEOMETRY__ALT_GEOMETRY_HPP_ -#include "autoware_utils_geometry/geometry/boost_geometry.hpp" +#include "autoware_utils_geometry/boost_geometry.hpp" #include #include diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/boost_polygon_utils.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/boost_polygon_utils.hpp index e6eec13..d459dea 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/boost_polygon_utils.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/boost_polygon_utils.hpp @@ -15,7 +15,7 @@ #ifndef AUTOWARE_UTILS_GEOMETRY__BOOST_POLYGON_UTILS_HPP_ #define AUTOWARE_UTILS_GEOMETRY__BOOST_POLYGON_UTILS_HPP_ -#include "autoware_utils_geometry/geometry/boost_geometry.hpp" +#include #include #include diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/ear_clipping.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/ear_clipping.hpp index e65eb95..ac50cd2 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/ear_clipping.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/ear_clipping.hpp @@ -15,7 +15,7 @@ #ifndef AUTOWARE_UTILS_GEOMETRY__EAR_CLIPPING_HPP_ #define AUTOWARE_UTILS_GEOMETRY__EAR_CLIPPING_HPP_ -#include "autoware_utils_geometry/geometry/alt_geometry.hpp" +#include "autoware_utils_geometry/alt_geometry.hpp" #include #include diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/geometry.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/geometry.hpp index 171aa52..d3b38a5 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/geometry.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/geometry.hpp @@ -15,7 +15,7 @@ #ifndef AUTOWARE_UTILS_GEOMETRY__GEOMETRY_HPP_ #define AUTOWARE_UTILS_GEOMETRY__GEOMETRY_HPP_ -#include "autoware_utils_geometry/geometry/boost_geometry.hpp" +#include "autoware_utils_geometry/boost_geometry.hpp" #include "autoware_utils_geometry/msg/covariance.hpp" #include "autoware_utils_math/constants.hpp" #include "autoware_utils_math/normalization.hpp" diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/gjk_2d.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/gjk_2d.hpp index 2276adf..b63e851 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/gjk_2d.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/gjk_2d.hpp @@ -15,7 +15,7 @@ #ifndef AUTOWARE_UTILS_GEOMETRY__GJK_2D_HPP_ #define AUTOWARE_UTILS_GEOMETRY__GJK_2D_HPP_ -#include "autoware_utils_geometry/geometry/boost_geometry.hpp" +#include namespace autoware_utils_geometry::gjk { diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/random_concave_polygon.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/random_concave_polygon.hpp index 636caac..1bea3f4 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/random_concave_polygon.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/random_concave_polygon.hpp @@ -15,7 +15,7 @@ #ifndef AUTOWARE_UTILS_GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ #define AUTOWARE_UTILS_GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ -#include +#include #include #include diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/random_convex_polygon.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/random_convex_polygon.hpp index a9581c1..db4cc21 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/random_convex_polygon.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/random_convex_polygon.hpp @@ -15,7 +15,7 @@ #ifndef AUTOWARE_UTILS_GEOMETRY__RANDOM_CONVEX_POLYGON_HPP_ #define AUTOWARE_UTILS_GEOMETRY__RANDOM_CONVEX_POLYGON_HPP_ -#include +#include namespace autoware_utils_geometry { diff --git a/autoware_utils_geometry/include/autoware_utils_geometry/sat_2d.hpp b/autoware_utils_geometry/include/autoware_utils_geometry/sat_2d.hpp index c614789..b5626f9 100644 --- a/autoware_utils_geometry/include/autoware_utils_geometry/sat_2d.hpp +++ b/autoware_utils_geometry/include/autoware_utils_geometry/sat_2d.hpp @@ -15,7 +15,7 @@ #ifndef AUTOWARE_UTILS_GEOMETRY__SAT_2D_HPP_ #define AUTOWARE_UTILS_GEOMETRY__SAT_2D_HPP_ -#include "autoware_utils_geometry/geometry/boost_geometry.hpp" +#include namespace autoware_utils_geometry::sat { diff --git a/autoware_utils_geometry/src/geometry/alt_geometry.cpp b/autoware_utils_geometry/src/geometry/alt_geometry.cpp index 831711a..a03a0a3 100644 --- a/autoware_utils_geometry/src/geometry/alt_geometry.cpp +++ b/autoware_utils_geometry/src/geometry/alt_geometry.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_utils_geometry/geometry/alt_geometry.hpp" +#include "autoware_utils_geometry/alt_geometry.hpp" #include #include diff --git a/autoware_utils_geometry/src/geometry/boost_polygon_utils.cpp b/autoware_utils_geometry/src/geometry/boost_polygon_utils.cpp index cae8525..261d3d6 100644 --- a/autoware_utils_geometry/src/geometry/boost_polygon_utils.cpp +++ b/autoware_utils_geometry/src/geometry/boost_polygon_utils.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_utils_geometry/geometry/boost_polygon_utils.hpp" +#include "autoware_utils_geometry/boost_polygon_utils.hpp" -#include "autoware_utils_geometry/geometry/geometry.hpp" +#include "autoware_utils_geometry/geometry.hpp" #include diff --git a/autoware_utils_geometry/src/geometry/ear_clipping.cpp b/autoware_utils_geometry/src/geometry/ear_clipping.cpp index b7e5022..73d8bde 100644 --- a/autoware_utils_geometry/src/geometry/ear_clipping.cpp +++ b/autoware_utils_geometry/src/geometry/ear_clipping.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_utils_geometry/geometry/ear_clipping.hpp" +#include "autoware_utils_geometry/ear_clipping.hpp" #include #include diff --git a/autoware_utils_geometry/src/geometry/geometry.cpp b/autoware_utils_geometry/src/geometry/geometry.cpp index fb3c153..d76d956 100644 --- a/autoware_utils_geometry/src/geometry/geometry.cpp +++ b/autoware_utils_geometry/src/geometry/geometry.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_utils_geometry/geometry/geometry.hpp" +#include "autoware_utils_geometry/geometry.hpp" -#include "autoware_utils_geometry/geometry/gjk_2d.hpp" +#include "autoware_utils_geometry/gjk_2d.hpp" #include diff --git a/autoware_utils_geometry/src/geometry/gjk_2d.cpp b/autoware_utils_geometry/src/geometry/gjk_2d.cpp index 17ee7bc..8a122dc 100644 --- a/autoware_utils_geometry/src/geometry/gjk_2d.cpp +++ b/autoware_utils_geometry/src/geometry/gjk_2d.cpp @@ -12,9 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_utils_geometry/geometry/gjk_2d.hpp" - -#include "autoware_utils_geometry/geometry/boost_geometry.hpp" +#include +#include #include diff --git a/autoware_utils_geometry/src/geometry/pose_deviation.cpp b/autoware_utils_geometry/src/geometry/pose_deviation.cpp index fa542c3..a75aa28 100644 --- a/autoware_utils_geometry/src/geometry/pose_deviation.cpp +++ b/autoware_utils_geometry/src/geometry/pose_deviation.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_utils_geometry/geometry/pose_deviation.hpp" +#include "autoware_utils_geometry/pose_deviation.hpp" #include "autoware_utils_math/normalization.hpp" diff --git a/autoware_utils_geometry/src/geometry/random_concave_polygon.cpp b/autoware_utils_geometry/src/geometry/random_concave_polygon.cpp index 2851fca..5702447 100644 --- a/autoware_utils_geometry/src/geometry/random_concave_polygon.cpp +++ b/autoware_utils_geometry/src/geometry/random_concave_polygon.cpp @@ -12,9 +12,9 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_utils_geometry/geometry/random_concave_polygon.hpp" +#include "autoware_utils_geometry/random_concave_polygon.hpp" -#include "autoware_utils_geometry/geometry/boost_geometry.hpp" +#include "autoware_utils_geometry/boost_geometry.hpp" #include #include diff --git a/autoware_utils_geometry/src/geometry/random_convex_polygon.cpp b/autoware_utils_geometry/src/geometry/random_convex_polygon.cpp index ea9e79b..eeb291f 100644 --- a/autoware_utils_geometry/src/geometry/random_convex_polygon.cpp +++ b/autoware_utils_geometry/src/geometry/random_convex_polygon.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_utils_geometry/geometry/random_convex_polygon.hpp" +#include "autoware_utils_geometry/random_convex_polygon.hpp" #include diff --git a/autoware_utils_geometry/src/geometry/sat_2d.cpp b/autoware_utils_geometry/src/geometry/sat_2d.cpp index 682fed7..71557d7 100644 --- a/autoware_utils_geometry/src/geometry/sat_2d.cpp +++ b/autoware_utils_geometry/src/geometry/sat_2d.cpp @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "autoware_utils_geometry/geometry/sat_2d.hpp" +#include #include