50 template <
typename PrimitiveT>
75 template <
typename PrimitiveT>
79 template <
typename PrimitiveT>
83 template <
typename PrimitiveT>
87 template <
typename PrimitiveT>
91 template <
typename PrimitiveT>
95 template <
typename PrimitiveT>
101 template <
typename PrimitiveT>
107 template <
typename PrimitiveT>
112 template <
typename PrimitiveT>
114 return std::is_same<PrimitiveT, ConstPrimitiveType<PrimitiveT>>::value;
118 template <
typename PrimitiveT>
124 template <
typename PrimitiveT>
132 template <
typename Po
intT>
137 static constexpr
bool IsPrimitive =
true;
142 template <
typename LineStringT>
149 template <
typename PolygonT>
155 template <
typename Po
intT>
158 template <
typename Po
intT>
161 template <
typename Po
intT>
164 template <
typename Po
intT>
166 return point.basicPoint();
168 template <
typename Po
intT>
170 -> std::enable_if_t<!PointTraits<PointT>::IsPrimitive && std::is_same<PointT, BasicPointT<PointT>>::value, PointT> {
173 template <
typename Po
intT>
175 -> std::enable_if_t<!PointTraits<PointT>::IsPrimitive && !std::is_same<PointT, BasicPointT<PointT>>::value,
180 template <
typename PrimT,
typename TagT>
182 return std::is_same<typename PrimitiveTraits<std::decay_t<PrimT>>::Category, TagT>::value;
185 template <
typename T>
187 return !traits::isCategory<T, traits::RegulatoryElementTag>();
190 template <
typename LineStringT>
193 template <
typename PrimT>
typename LineStringT ::DataType DataType
typename PolygonT::PointType PointType
typename Owned< PrimitiveT >::Type OwnedT
std::shared_ptr< RegulatoryElement > RegulatoryElementPtr
Specialization of traits for polygons.
constexpr bool isCategory()
typename PointTraits< PointT >::BasicPoint BasicPointT
ConstPrimitiveType< PrimitiveT > toConst(const PrimitiveT &primitive)
Converts a primitive to its matching const type.
Specialization of traits for linestrings.
typename LineStringTraits< LineStringT >::PointType PointType
typename PointTraits< PointT >::ConstPoint ConstPointT
The famous (mutable) lanelet class.
Identifies LaneletPrimitives.
typename LineStringT ::MutableType MutableType
typename PrimitiveTraits< PrimitiveT >::ThreeDType ThreeD
f Utility for determinig the matching three dimensional type for a primitive
Identifies PolygonPrimitives.
Identifies bounding boxes.
RegulatoryElementConstPtr ConstType
typename PrimitiveTraits< PointT >::ConstType ConstPoint
Identifies RegulatoryElementPrimitives.
Identifies LineStringPrimitives.
A normal 3d linestring with mutable data.
RegulatoryElementPtr ThreeDType
typename PolygonT::HybridType HybridType
typename LineStringT::PointType PointType
Identifies PointPrimitives.
Data container for all RegulatoryElement types.
typename PrimitiveTraits< PrimitiveT >::ConstType ConstPrimitiveType
Utility for determinig the matching const type for a primitive.
std::shared_ptr< const RegulatoryElement > RegulatoryElementConstPtr
typename PointT::BasicPoint BasicPoint
RegulatoryElementPtr TwoDType
typename PrimitiveTraits< PrimitiveT >::TwoDType TwoD
Utility for determinig the matching two dimensional type for a primitive.
A mutable clockwise oriented, open (ie start point != end point) polygon in 3d.
typename LineStringT ::TwoDType TwoDType
Famous Area class that represents a basic area as element of the map.
Can be used to determine which primitive type is managed by a primitive.
constexpr bool noRegelem()
RegulatoryElementPtr MutableType
auto toBasicPoint(const PointT &point) -> std::enable_if_t< PointTraits< PointT >::IsPrimitive, BasicPointT< PointT >>
constexpr bool is3D()
Checks (at compile time) whether a primitive is three dimensional.
RegulatoryElementPtr ThreeDType
typename LineStringT ::ThreeDType ThreeDType
BoundingBox2d to2D(const BoundingBox3d &primitive)
typename LineStringT ::Category Category
constexpr bool is2D()
Checks (at compile time) whether a primitive is two dimensional.
Id getId(const PrimT &prim)
typename PointTraits< PointT >::MutablePoint MutablePointT
BoundingBox3d to3D(const BoundingBox2d &primitive)
Identifies AreaPrimitives.
Specialization of traits for points.
RegulatoryElementPtr TwoDType
typename LineStringT::HybridType HybridType
typename PrimitiveTraits< PointT >::MutableType MutablePoint
typename PrimitiveTraits< PrimitiveT >::MutableType MutablePrimitiveType
Utility for determinig the matching mutable type for a primitive.
RegulatoryElementConstPtr ConstType
typename LineStringT ::ConstType ConstType
RegulatoryElementPtr MutableType