maliput_malidrive
RoadGeometry Class Referencefinal

Detailed Description

Maliput implementation of the malidrive backend.

#include <src/maliput_malidrive/base/road_geometry.h>

Inheritance diagram for RoadGeometry:
[legend]

Public Member Functions

 MALIDRIVE_NO_COPY_NO_MOVE_NO_ASSIGN (RoadGeometry)
 
 RoadGeometry (const maliput::api::RoadGeometryId &id, std::unique_ptr< xodr::DBManager > manager, double linear_tolerance, double angular_tolerance, double scale_length, const maliput::math::Vector3 &inertial_to_backend_frame_translation)
 Constructs a RoadGeometry. More...
 
xodr::DBManagerget_manager () const
 Returns a xodr::DBManager. More...
 
void AddRoadCharacteristics (const xodr::RoadHeader::Id &road_id, std::unique_ptr< road_curve::RoadCurve > road_curve, std::unique_ptr< road_curve::Function > reference_line_offset)
 Adds the description of a Road. More...
 
const road_curve::RoadCurveGetRoadCurve (const xodr::RoadHeader::Id &road_id) const
 Gets the RoadCurve of road_id. More...
 
const road_curve::FunctionGetReferenceLineOffset (const xodr::RoadHeader::Id &road_id) const
 Gets the reference line offset function of road_id. More...
 
- Public Member Functions inherited from RoadGeometry
 MALIPUT_NO_COPY_NO_MOVE_NO_ASSIGN (RoadGeometry)
 
 RoadGeometry (const api::RoadGeometryId &id, double linear_tolerance, double angular_tolerance, double scale_length, const math::Vector3 &inertial_to_backend_frame_translation)
 
T * AddJunction (std::unique_ptr< T > junction)
 
T * AddBranchPoint (std::unique_ptr< T > branch_point)
 
void InitializeStrategy (Args &&... args)
 
 ~RoadGeometry () override=default
 
- Public Member Functions inherited from RoadGeometry
RoadGeometryId id () const
 
int num_junctions () const
 
const Junctionjunction (int index) const
 
int num_branch_points () const
 
const BranchPointbranch_point (int index) const
 
const IdIndex & ById () const
 
RoadPositionResult ToRoadPosition (const InertialPosition &inertial_position, const std::optional< RoadPosition > &hint=std::nullopt) const
 
std::vector< RoadPositionResultFindRoadPositions (const InertialPosition &inertial_position, double radius) const
 
double linear_tolerance () const
 
double angular_tolerance () const
 
double scale_length () const
 
std::vector< std::string > CheckInvariants () const
 
std::vector< InertialPositionSampleAheadWaypoints (const LaneSRoute &lane_s_route, double path_length_sampling_rate) const
 
math::Vector3 inertial_to_backend_frame_translation () const
 

Additional Inherited Members

- Protected Member Functions inherited from RoadGeometry
 RoadGeometry ()=default
 

Constructor & Destructor Documentation

◆ RoadGeometry()

RoadGeometry ( const maliput::api::RoadGeometryId id,
std::unique_ptr< xodr::DBManager manager,
double  linear_tolerance,
double  angular_tolerance,
double  scale_length,
const maliput::math::Vector3 inertial_to_backend_frame_translation 
)

Constructs a RoadGeometry.

Parameters
idsee maliput::api::RoadGeometry::id() for reference.
managerAn xodr::DBManager that contains a parsed XODR description. It must not be nullptr.
linear_tolerancesee maliput::api::RoadGeometry::linear_tolerance() for reference.
angular_tolerancesee maliput::api::RoadGeometry::angular_tolerance() for reference.
scale_lengthsee maliput::api::RoadGeometry::scale_length() for reference.
inertial_to_backend_frame_translationmaliput's Inertial Frame to Backend Frame translation vector.
Exceptions
maliput::common::assertion_errorWhen manager_ is nullptr.

Member Function Documentation

◆ AddRoadCharacteristics()

void AddRoadCharacteristics ( const xodr::RoadHeader::Id road_id,
std::unique_ptr< road_curve::RoadCurve road_curve,
std::unique_ptr< road_curve::Function reference_line_offset 
)

Adds the description of a Road.

Parameters
road_idIs the xodr id of the road that road_curve belongs to.
road_curveIs the RoadCurve to be added.
reference_line_offsetIs a Function that describes the lateral shift of the road reference line.
Exceptions
maliput::common::assertion_errorWhen road_curve is nullptr.
maliput::common::assertion_errorWhen reference_line_offset is nullptr.
maliput::common::assertion_errorWhen road_id is duplicated.

◆ get_manager()

xodr::DBManager* get_manager ( ) const

Returns a xodr::DBManager.

◆ GetReferenceLineOffset()

const road_curve::Function * GetReferenceLineOffset ( const xodr::RoadHeader::Id road_id) const

Gets the reference line offset function of road_id.

Parameters
road_idIs the xodr id of the road that road_curve belongs to.
Returns
A Function pointer to the road reference line offset function.
Exceptions
maliput::common::assertion_errorWhen there is no a function described for road_id.

◆ GetRoadCurve()

const road_curve::RoadCurve * GetRoadCurve ( const xodr::RoadHeader::Id road_id) const

Gets the RoadCurve of road_id.

Parameters
road_idIs the xodr id of the road that road_curve belongs to.
Returns
A RoadCurve pointer.
Exceptions
maliput::common::assertion_errorWhen there is no RoadCurve for road_id.

◆ MALIDRIVE_NO_COPY_NO_MOVE_NO_ASSIGN()

MALIDRIVE_NO_COPY_NO_MOVE_NO_ASSIGN ( RoadGeometry  )

The documentation for this class was generated from the following files: