15
15
#ifndef AUTOWARE__UNIVERSE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_
16
16
#define AUTOWARE__UNIVERSE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_
17
17
18
+ #include < autoware_utils/geometry/boost_geometry.hpp>
19
+
18
20
#include < boost/geometry/core/cs.hpp>
19
21
#include < boost/geometry/geometries/geometries.hpp>
20
22
#include < boost/geometry/geometries/register/point.hpp>
28
30
namespace autoware ::universe_utils
29
31
{
30
32
// 2D
31
- struct Point2d ;
33
+ using Point2d = autoware_utils:: Point2d;
32
34
using Segment2d = boost::geometry::model::segment<Point2d>;
33
35
using Box2d = boost::geometry::model::box<Point2d>;
34
36
using LineString2d = boost::geometry::model::linestring<Point2d>;
@@ -40,7 +42,7 @@ using MultiLineString2d = boost::geometry::model::multi_linestring<LineString2d>
40
42
using MultiPolygon2d = boost::geometry::model::multi_polygon<Polygon2d>;
41
43
42
44
// 3D
43
- struct Point3d ;
45
+ using Point3d = autoware_utils:: Point3d;
44
46
using Segment3d = boost::geometry::model::segment<Point3d>;
45
47
using Box3d = boost::geometry::model::box<Point3d>;
46
48
using LineString3d = boost::geometry::model::linestring<Point3d>;
@@ -50,32 +52,6 @@ using MultiPoint3d = boost::geometry::model::multi_point<Point3d>;
50
52
using MultiLineString3d = boost::geometry::model::multi_linestring<LineString3d>;
51
53
using MultiPolygon3d = boost::geometry::model::multi_polygon<Polygon3d>;
52
54
53
- struct Point2d : public Eigen ::Vector2d
54
- {
55
- Point2d () = default ;
56
- Point2d (const double x, const double y) : Eigen::Vector2d(x, y) {}
57
-
58
- [[nodiscard]] Point3d to_3d (const double z = 0.0 ) const ;
59
- };
60
-
61
- struct Point3d : public Eigen ::Vector3d
62
- {
63
- Point3d () = default ;
64
- Point3d (const double x, const double y, const double z) : Eigen::Vector3d(x, y, z) {}
65
-
66
- [[nodiscard]] Point2d to_2d () const ;
67
- };
68
-
69
- inline Point3d Point2d::to_3d (const double z) const
70
- {
71
- return Point3d{x (), y (), z};
72
- }
73
-
74
- inline Point2d Point3d::to_2d () const
75
- {
76
- return Point2d{x (), y ()};
77
- }
78
-
79
55
inline geometry_msgs::msg::Point toMsg (const Point3d & point)
80
56
{
81
57
geometry_msgs::msg::Point msg;
@@ -95,10 +71,4 @@ inline Point3d fromMsg(const geometry_msgs::msg::Point & msg)
95
71
}
96
72
} // namespace autoware::universe_utils
97
73
98
- BOOST_GEOMETRY_REGISTER_POINT_2D ( // NOLINT
99
- autoware::universe_utils::Point2d, double , cs::cartesian, x(), y()) // NOLINT
100
- BOOST_GEOMETRY_REGISTER_POINT_3D( // NOLINT
101
- autoware::universe_utils::Point3d, double , cs::cartesian, x(), y(), z()) // NOLINT
102
- BOOST_GEOMETRY_REGISTER_RING(autoware::universe_utils::LinearRing2d) // NOLINT
103
-
104
74
#endif // AUTOWARE__UNIVERSE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_
0 commit comments