maliput_malidrive
|
Interface of a helper class to build road curve related objects by MalidriveRoadGeometryBuilder.
This class is provided as an interface to facilitate testing of MalidriveRoadGeometry via dependency injection.
#include <src/maliput_malidrive/builder/road_curve_factory.h>
Public Member Functions | |
RoadCurveFactoryBase ()=delete | |
RoadCurveFactoryBase (double linear_tolerance, double scale_length, double angular_tolerance) | |
Constructs RoadCurveFactoryBase. More... | |
virtual | ~RoadCurveFactoryBase ()=default |
virtual std::unique_ptr< road_curve::Function > | MakeCubicPolynomial (double a, double b, double c, double d, double p0, double p1) const =0 |
virtual std::unique_ptr< road_curve::Function > | MakeCubicPolynomial (double p0, double p1, double y, double dy) const =0 |
Creates a cubic polynomial: More... | |
virtual std::unique_ptr< road_curve::GroundCurve > | MakeArcGroundCurve (const xodr::Geometry &arc_geometry) const =0 |
Makes a road_curve::ArcGroundCurve. More... | |
virtual std::unique_ptr< road_curve::GroundCurve > | MakeLineGroundCurve (const xodr::Geometry &line_geometry) const =0 |
Makes a road_curve::LineGroundCurve. More... | |
virtual std::unique_ptr< road_curve::GroundCurve > | MakeSpiralGroundCurve (const xodr::Geometry &spiral_geometry) const =0 |
Makes a road_curve::SpiralGroundCurve. More... | |
virtual std::unique_ptr< road_curve::GroundCurve > | MakePiecewiseGroundCurve (const std::vector< xodr::Geometry > &geometries) const =0 |
Makes a road_curve::PiecewiseGroundCurve. More... | |
virtual std::unique_ptr< malidrive::road_curve::Function > | MakeElevation (const xodr::ElevationProfile &elevation_profile, double p0, double p1, bool assert_continuity) const =0 |
Makes a cubic polynomial that describes the elevation of a Road. More... | |
virtual std::unique_ptr< malidrive::road_curve::Function > | MakeSuperelevation (const xodr::LateralProfile &lateral_profile, double p0, double p1, bool assert_continuity) const =0 |
Makes a cubic polynomial that describes the superelevation of a Road. More... | |
virtual std::unique_ptr< malidrive::road_curve::Function > | MakeLaneWidth (const std::vector< xodr::LaneWidth > &lane_widths, double p0, double p1, bool assert_continuity) const =0 |
Makes a cubic polynomial that describes the width of a Lane. More... | |
virtual std::unique_ptr< malidrive::road_curve::Function > | MakeReferenceLineOffset (const std::vector< xodr::LaneOffset > &reference_offsets, double p0, double p1) const =0 |
Makes a cubic polynomial that describes the lateral shift of the road reference line. More... | |
virtual std::unique_ptr< road_curve::RoadCurve > | MakeMalidriveRoadCurve (std::unique_ptr< road_curve::GroundCurve > ground_curve, std::unique_ptr< road_curve::Function > elevation, std::unique_ptr< road_curve::Function > superelevation, bool assert_contiguity) const =0 |
Makes a road_curve::MalidriveGroundCurve. More... | |
virtual double | linear_tolerance () const |
Tolerance accessors. More... | |
virtual double | scale_length () const |
virtual double | angular_tolerance () const |
|
delete |
RoadCurveFactoryBase | ( | double | linear_tolerance, |
double | scale_length, | ||
double | angular_tolerance | ||
) |
Constructs RoadCurveFactoryBase.
linear_tolerance | RoadGeometry's linear tolerance. It will be used to build geometry objects. It must be non negative. |
scale_length | RoadGeometry's scale length. It will be used to build geometry objects. It must be positive. |
angular_tolerance | RoadGeometry's angular tolerance. It will be used to build geometry objects. It must be positive. |
maliput::common::assertion_error | When linear_tolerance is not positive. |
maliput::common::assertion_error | When scale_length is not positive. |
maliput::common::assertion_error | When angular_tolerance is not positive. |
|
virtualdefault |
|
virtual |
|
virtual |
Tolerance accessors.
|
pure virtual |
Makes a road_curve::ArcGroundCurve.
Its linear tolerance will be the constructor argument.
arc_geometry | xodr::Geometry definition to construct a road_curve::ArcGroundCurve. Its type must be xodr::Geometry::Type::kArc. |
maliput::common::assertion_error | When arc_geometry.type is not xodr::Geometry::Type::kArc. |
Implemented in RoadCurveFactory.
|
pure virtual |
Implemented in RoadCurveFactory.
|
pure virtual |
Creates a cubic polynomial:
\( f(p) = a p^3 + b p^2 + c p + d / p ∈ [`p0`; `p1`] \).
Meeting the following considerations: f(p0
) = 0 f'(p0
) = 0 f(p1
) = y
f'(p1
) = dy
p0 | Lower bound extreme of the parameter range. It must not be negative and must be less than p1 . |
p1 | Upper bound extreme of the parameter range. It must be greater than p0 . |
y | Polynomial evaluated at \( p = `p1` \). |
dy | Derived polynomial evaluated at \( p = `p1` \). |
maliput::common::assertion_error | When p0 is negative. |
maliput::common::assertion_error | When p1 is not greater than p0 . |
Implemented in RoadCurveFactory.
|
pure virtual |
Makes a cubic polynomial that describes the elevation of a Road.
Constructs a road::curve::Function out of elevation_profile
. There could be two scenarios that depends on elevation_profile
:
p0
, p1
]p0
, p1
]p0
and the S0 value of the first elevation then a cubic polynomial is created to fullfill that gap. elevation_profile | Contains the elevation described in the XODR for the Road. |
p0 | Lower bound extreme of the parameter range. It must not be negative and must be less than p1 . |
p1 | Upper bound extreme of the parameter range. It must be greater than p0 . |
assert_continuity | If true, C1 continuity is assert when function describing the elevation is built. Otherwise only warning messages are printed. |
maliput::common::assertion_error | When p0 is negative. |
maliput::common::assertion_error | When p1 is not greater enough than p0 . |
Implemented in RoadCurveFactory.
|
pure virtual |
Makes a cubic polynomial that describes the width of a Lane.
Constructs a road::curve::Function out of lane_widths
.
lane_widths | Contains the width described in the XODR for the Lane. |
p0 | Lower bound extreme of the parameter range. It must not be negative and must be less than p1 . |
p1 | Upper bound extreme of the parameter range. It must be greater than p0 . |
assert_continuity | If true, C1 continuity is assert when function describing the lane width is built. Otherwise only warning messages are printed. |
maliput::common::assertion_error | When p0 is negative. |
maliput::common::assertion_error | When p1 is not greater enough than p0 . |
maliput::common::assertion_error | When lane_widths 's size is zero. |
maliput::common::assertion_error | When the first offset value of lane_widths is different than zero. |
maliput::common::assertion_error | When lane_widths 's start points are distanced less than linear tolerance. |
maliput::common::assertion_error | When lane_widths 's functions aren't at least as long as road::curve::GroundCurve::kEpsilon. |
Implemented in RoadCurveFactory.
|
pure virtual |
Makes a road_curve::LineGroundCurve.
Its linear tolerance will be the constructor argument.
line_geometry | xodr::Geometry definition to construct a road_curve::LineGroundCurve. Its type must be xodr::Geometry::Type::kLine. |
maliput::common::assertion_error | When line_geometry.type is not xodr::Geometry::Type::kLine. |
Implemented in RoadCurveFactory.
|
pure virtual |
Makes a road_curve::MalidriveGroundCurve.
Its linear tolerance and scale length will be the constructor arguments.
Implemented in RoadCurveFactory.
|
pure virtual |
Makes a road_curve::PiecewiseGroundCurve.
Its linear tolerance will be the constructor argument.
geometries | A vector of xodr::Geometry definitions to construct a road_curve::PiecewiseGroundCurve. Item's type must be one of {xodr::Geometry::Type::kArc, xodr::Geometry::Type::kLine, xodr::Geometry::Type::kSpiral}. It must not be empty. Geometries whose length is less than GroundCurve::kEpsilon are discarded. |
maliput::common::assertion_error | When any item of geometries has other type than {xodr::Geometry::Type::kArc, xodr::Geometry::Type::kLine, xodr::Geometry::Type::kSpiral}. |
maliput::common::assertion_error | When geometries is empty. |
Implemented in RoadCurveFactory.
|
pure virtual |
Makes a cubic polynomial that describes the lateral shift of the road reference line.
When reference_offsets
is empty, a zero cubic polynomial is created in the range [p0
, p1
]. Otherwise, a PiecewiseFunction is created in the range [p0
, p1
].
p0
and the S0 value of the first offset function then a zero cubic polynomial is created to fullfill that gap.reference_offsets | Contains the offset described in the XODR's laneOffset record for the road reference line. |
p0 | Lower bound extreme of the parameter range. It must not be negative and must be less than p1 . |
p1 | Upper bound extreme of the parameter range. It must be greater than p0 . |
maliput::common::assertion_error | When p0 is negative. |
maliput::common::assertion_error | When p1 is not greater enough than p0 . |
Implemented in RoadCurveFactory.
|
pure virtual |
Makes a road_curve::SpiralGroundCurve.
Its linear tolerance will be the constructor argument.
spiral_geometry | xodr::Geometry definition to construct a road_curve::SpiralGroundCurve. Its type must be xodr::Geometry::Type::kSpiral. |
maliput::common::assertion_error | When spiral_geometry.type is not xodr::Geometry::Type::kSpiral. |
Implemented in RoadCurveFactory.
|
pure virtual |
Makes a cubic polynomial that describes the superelevation of a Road.
Constructs a road::curve::Function out of lateral_profile
. There could be two scenarios that depends on lateral_profile
:
p0
, p1
]p0
, p1
]p0
and the S0 value of the first superelevation then a cubic polynomial is created to fullfill that gap. lateral_profile | Contains the superelevation described in the XODR for the Road. |
p0 | Lower bound extreme of the parameter range. It must not be negative and must be less than p1 . |
p1 | Upper bound extreme of the parameter range. It must be greater than p0 . |
assert_continuity | If true, C1 continuity is assert when function describing the superelevation is built. Otherwise only warning messages are printed. |
maliput::common::assertion_error | When p0 is negative. |
maliput::common::assertion_error | When p1 is not greater enough than p0 . |
Implemented in RoadCurveFactory.
|
virtual |