ad_map_access
Public Member Functions | Static Public Member Functions | List of all members
ad::map::opendrive::AdMapFactory Class Reference

Creates an AdMap from an OpenDRIVE map file. More...

#include <ad/map/opendrive/AdMapFactory.hpp>

Inheritance diagram for ad::map::opendrive::AdMapFactory:
Inheritance graph
[legend]
Collaboration diagram for ad::map::opendrive::AdMapFactory:
Collaboration graph
[legend]

Public Member Functions

 AdMapFactory (access::Store &store)
 
 AdMapFactory (AdMapFactory const &)=delete
 
 AdMapFactory (AdMapFactory const &&)=delete
 
AdMapFactoryoperator= (AdMapFactory &&)=delete
 
AdMapFactoryoperator= (AdMapFactory const &)=delete
 
bool createAdMap (std::string const &mapFilePath, double const overlapMargin, intersection::IntersectionType const defaultIntersectionType, landmark::TrafficLightType const defaultTrafficLightType=landmark::TrafficLightType::SOLID_RED_YELLOW_GREEN)
 Reads the OpenDRIVE map xml, generates a lane map and populates the AdMap store with it via admap Factory. More...
 
bool createAdMapFromString (std::string const &mapContent, double const overlapMargin, intersection::IntersectionType const defaultIntersectionType, landmark::TrafficLightType const defaultTrafficLightType=landmark::TrafficLightType::SOLID_RED_YELLOW_GREEN)
 Parses OpenDRIVE map content string, generates a lane map and populates the AdMap store with it via admap Factory. More...
 
- Public Member Functions inherited from ad::map::access::Factory
 Factory (Store &store)
 Constructor. More...
 
virtual ~Factory ()=default
 Destructor. Releases all resources.
 
bool add (PartitionId part_id, const lane::LaneId &id, lane::LaneType type, lane::LaneDirection direction)
 Adds or modifies new Lane in the Store. More...
 
lane::LaneId add (PartitionId part_id, const point::GeoEdge &left_geo, const point::GeoEdge &right_geo)
 Add new lane to the store. More...
 
lane::LaneId add (PartitionId part_id, const point::ECEFEdge &left_ecef, const point::ECEFEdge &right_ecef, const lane::LaneId &lane_id_0, const lane::LaneId &lane_id_1)
 Add new intersection lane to the store. More...
 
bool addLandmark (PartitionId part_id, const landmark::LandmarkId &id, const landmark::LandmarkType type, const point::ECEFPoint &position, const point::ECEFPoint &orientation, const point::Geometry &bounding_box)
 Adds or modifies new landmark in the Store. More...
 
bool addTrafficLight (PartitionId part_id, const landmark::LandmarkId &id, const landmark::TrafficLightType type, const point::ECEFPoint &position, const point::ECEFPoint &orientation, const point::Geometry &bounding_box)
 Adds or modifies new traffic light landmark in the Store. More...
 
bool addTrafficSign (PartitionId part_id, const landmark::LandmarkId &id, const landmark::TrafficSignType type, const point::ECEFPoint &position, const point::ECEFPoint &orientation, const point::Geometry &bounding_box, const std::string &text)
 Adds or modifies new traffic sign landmark in the Store. More...
 
bool add (const lane::LaneId &id, const lane::ContactLane &contact_lane)
 Adds Contact to Lane to the Lane object. More...
 
bool add (const lane::LaneId &id, const lane::ContactLaneList &contact_lanes)
 Adds Contacts to Lane to the Lane object. More...
 
bool add (const lane::LaneId &id, const restriction::SpeedLimit &para_speed)
 Add parametic speed limit to the Lane object. More...
 
bool add (const lane::LaneId &id, const landmark::LandmarkId &landmark)
 Add visible landmark to the Lane object. More...
 
bool add (const lane::LaneId &id, const restriction::Restriction &restriction, bool andx)
 Add Restriction to the Lane object. More...
 
bool add (const lane::LaneId &id_from, const lane::LaneId &id_to, const lane::ContactLocation location, const lane::ContactTypeList &types, const restriction::Restrictions &restrs)
 Add Contact to Lane to the Lane object. More...
 
bool add (const lane::LaneId &id_from, const lane::LaneId &id_to, const lane::ContactLocation location, const lane::ContactTypeList &types, const restriction::Restrictions &restrs, const landmark::LandmarkId &traffic_light)
 Add Contact to Lane to the Lane object. More...
 
bool set (const lane::LaneId &id, lane::LaneDirection direction)
 Sets the lane attribute. More...
 
bool set (const lane::LaneId &id, lane::LaneType type)
 Sets the lane attribute. More...
 
bool set (const lane::LaneId &id, lane::ComplianceVersion compliance_ver)
 Sets the lane attribute. More...
 
bool set (const lane::LaneId &id, const point::Geometry &edge_left, const point::Geometry &edge_right)
 Sets the Lane Edges. More...
 
bool set (const lane::LaneId &id, const physics::Speed &speed_limit)
 Sets speed limit for the COMPLETE lane. More...
 
bool set (const lane::LaneId &id, const restriction::Restrictions &restrictions)
 Set Restrictions to the Lane object. More...
 
bool set (const lane::LaneId &id, const landmark::LandmarkIdList &landmarks)
 Set visible landmarks to the Lane object. More...
 
bool set (const TrafficType &traffic_type)
 Set traffic type of the map. More...
 
bool deleteLane (lane::LaneId id)
 Method to be called to delete Lane from the Store. More...
 
bool deleteContacts (lane::LaneId from_id, lane::LaneId to_id)
 Delete all contacts from one lane to another. More...
 
bool deleteLandmark (landmark::LandmarkId id)
 Method to be called to delete landmark from the Store. More...
 
bool autoConnect (lane::LaneId from_lane_id, lane::LaneId to_lane_id)
 Creates missing topological contacts from one lane to another. More...
 

Static Public Member Functions

static bool isOpenDriveMap (std::string const &mapName)
 Returns true if the given file matches an OpenDRIVE map file. More...
 

Additional Inherited Members

- Protected Attributes inherited from ad::map::access::Factory
StoremStore
 Store on which this Factory operates.
 

Detailed Description

Creates an AdMap from an OpenDRIVE map file.

Calls the OpenDRIVE map parser and the geometry generator. Once these operations are done, converts the resulting map into AdMap The AdMap is generated in the store via factory calls.

Member Function Documentation

◆ createAdMap()

bool ad::map::opendrive::AdMapFactory::createAdMap ( std::string const &  mapFilePath,
double const  overlapMargin,
intersection::IntersectionType const  defaultIntersectionType,
landmark::TrafficLightType const  defaultTrafficLightType = landmark::TrafficLightType::SOLID_RED_YELLOW_GREEN 
)

Reads the OpenDRIVE map xml, generates a lane map and populates the AdMap store with it via admap Factory.

Parameters
[in]overlapMarginmargin the lanes are narrowed when calculating overlaps.
[in]defaultIntersectionTypedefault type of intersections to be used
[in]defaultTrafficLightTypedefault type of traffic light to be used in case of traffic light intersection
Returns
true if a map was generated, false otherwise.

◆ createAdMapFromString()

bool ad::map::opendrive::AdMapFactory::createAdMapFromString ( std::string const &  mapContent,
double const  overlapMargin,
intersection::IntersectionType const  defaultIntersectionType,
landmark::TrafficLightType const  defaultTrafficLightType = landmark::TrafficLightType::SOLID_RED_YELLOW_GREEN 
)

Parses OpenDRIVE map content string, generates a lane map and populates the AdMap store with it via admap Factory.

Parameters
[in]overlapMarginmargin the lanes are narrowed when calculating overlaps.
[in]defaultIntersectionTypedefault type of intersections to be used
[in]defaultTrafficLightTypedefault type of traffic light to be used in case of traffic light intersection
Returns
true if a map was generated, false otherwise.

◆ isOpenDriveMap()

static bool ad::map::opendrive::AdMapFactory::isOpenDriveMap ( std::string const &  mapName)
static

Returns true if the given file matches an OpenDRIVE map file.

Parameters
[in]mapNameThe path to the file.
Returns
true if the map is generated without any fatal error

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