Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
lanelet Namespace Reference

Namespaces

 ConstLineStringImpl
 
 detail
 
 geometry
 
 helper
 
 impl
 
 internal
 
 io
 
 io_handlers
 
 osm
 
 projection
 
 test_cases
 
 test_setup
 
 traits
 
 units
 
 utils
 

Classes

class  AllWayStop
 
struct  ArcCoordinates
 
class  Area
 
class  AreaData
 
class  AreaLayer
 
class  Attribute
 
struct  AttributeNamesString
 
struct  AttributeValueString
 
class  BasicPolygon2d
 
class  BasicPolygon3d
 
class  BasicPolygonWithHoles2d
 
class  BasicPolygonWithHoles3d
 
class  BoundingBox2d
 
class  CompoundHybridLineString2d
 
class  CompoundHybridLineString3d
 
class  CompoundHybridPolygon2d
 
class  CompoundHybridPolygon3d
 
class  CompoundLineString2d
 
class  CompoundLineString3d
 
class  CompoundLineStringData
 
class  CompoundLineStringImpl
 
class  CompoundPolygon2d
 
class  CompoundPolygon3d
 
class  ConstArea
 
class  ConstHybridLineString2d
 
class  ConstHybridLineString3d
 
class  ConstHybridPolygon2d
 
class  ConstHybridPolygon3d
 
class  ConstLanelet
 
class  ConstLaneletOrArea
 
struct  ConstLaneletWithStopLine
 
class  ConstLineString2d
 
class  ConstLineString3d
 
class  ConstLineStringImpl
 
class  ConstLineStringOrPolygon3d
 
class  ConstPoint2d
 
class  ConstPoint3d
 
class  ConstPolygon2d
 
class  ConstPolygon3d
 
class  ConstPrimitive
 
class  ConstWeakArea
 
class  ConstWeakLanelet
 
class  DefaultProjectionNotAllowedError
 Thrown when a user attempts to load a map with georeferenced data without providing an origin. More...
 
class  FileNotFoundError
 Error for not existent filepaths. More...
 
class  ForwardProjectionError
 Thrown by the projector classes if projection from lat/lon to x/y fails. More...
 
class  GenericRegulatoryElement
 
class  GeometryError
 
class  GPSPoint
 
struct  HashBase
 
class  HybridMap
 
class  InvalidInputError
 
class  InvalidObjectStateError
 
class  IOError
 Generic error for all errors in this module. More...
 
class  Lanelet
 
class  LaneletData
 
class  LaneletError
 
class  LaneletLayer
 
class  LaneletMap
 
class  LaneletMapLayers
 
class  LaneletMultiError
 
class  LaneletSequence
 
class  LaneletSequenceData
 
class  LaneletSubmap
 
struct  LaneletWithStopLine
 
class  LineString2d
 
class  LineString3d
 
class  LineStringData
 
class  LineStringImpl
 
class  LineStringOrPolygon3d
 
class  LineStringOrPolygonBase
 
class  NoSuchAttributeError
 
class  NoSuchPrimitiveError
 
class  NullptrError
 
struct  Origin
 
class  ParseError
 Error thrown if some error occured during the parsing of the file. More...
 
struct  Participants
 
class  Point2d
 
class  Point3d
 
class  PointData
 
class  Polygon2d
 
class  Polygon3d
 
class  Primitive
 
class  PrimitiveData
 
class  PrimitiveLayer
 
class  Projector
 
class  RegisterRegulatoryElement
 
class  RegulatoryElement
 
class  RegulatoryElementData
 
class  RegulatoryElementFactory
 
class  ReverseProjectionError
 Thrown by the projector classes if projection from x/y to lat/lon fails. More...
 
class  RightOfWay
 
struct  RoleNameString
 
class  RuleParameterVisitor
 
class  SpeedLimit
 
class  TrafficLight
 
class  TrafficSign
 
struct  TrafficSignsWithType
 
class  UnsupportedExtensionError
 Error for an unsupported extension. More...
 
class  UnsupportedIOHandlerError
 Error thrown if an unsupported handler (parser/writer) has been specified. More...
 
struct  UsageLookup
 
struct  UsageLookup< Area >
 
struct  UsageLookup< Lanelet >
 
struct  UsageLookup< Point3d >
 
struct  UsageLookup< RegulatoryElementPtr >
 
class  WeakArea
 
class  WeakLanelet
 
class  WriteError
 Error thown if some error occurd during writing of a map. More...
 

Typedefs

typedef units::MPS2Quantity Acceleration
 
typedef std::shared_ptr< const AreaDataAreaDataConstPtr
 
typedef std::vector< AreaDataConstPtrAreaDataConstPtrs
 
typedef std::shared_ptr< AreaDataAreaDataPtr
 
typedef std::weak_ptr< AreaDataAreaDataptr
 
typedef std::vector< AreaDataPtrAreaDataPtrs
 
typedef std::vector< AreaAreas
 
typedef HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::MapAttributeMap
 
typedef std::pair< const char *, const AttributeNameAttributeNamesItem
 
typedef BasicPoints2d BasicLineString2d
 
typedef BasicPoints3d BasicLineString3d
 
typedef Eigen::Matrix< double, 2, 1, Eigen::DontAlign > BasicPoint2d
 
typedef Eigen::Vector3d BasicPoint3d
 
typedef std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > BasicPoints2d
 
typedef std::vector< BasicPoint3dBasicPoints3d
 
typedef std::vector< BasicPolygon2dBasicPolygons2d
 
typedef std::vector< BasicPolygon3dBasicPolygons3d
 
typedef std::vector< BasicPolygonWithHoles2dBasicPolygonsWithHoles2d
 
typedef std::vector< BasicPolygonWithHoles3dBasicPolygonsWithHoles3d
 
typedef Segment< BasicPoint2dBasicSegment2d
 
typedef Segment< BasicPoint3dBasicSegment3d
 
typedef Eigen::AlignedBox3d BoundingBox3d
 
typedef std::vector< CompoundHybridLineString2dCompoundHybridLineStrings2d
 
typedef std::vector< CompoundHybridLineString3dCompoundHybridLineStrings3d
 
typedef std::vector< CompoundHybridPolygon2dCompoundHybridPolygons2d
 
typedef std::vector< CompoundHybridPolygon3dCompoundHybridPolygons3d
 
typedef std::shared_ptr< const CompoundLineStringDataCompoundLineStringDataConstPtr
 
typedef std::vector< CompoundLineStringDataConstPtrCompoundLineStringDataConstPtrs
 
typedef std::shared_ptr< CompoundLineStringDataCompoundLineStringDataPtr
 
typedef std::vector< CompoundLineStringDataPtrCompoundLineStringDataPtrs
 
typedef std::vector< CompoundLineString2dCompoundLineStrings2d
 
typedef std::vector< CompoundLineString3dCompoundLineStrings3d
 
typedef std::vector< CompoundPolygon2dCompoundPolygons2d
 
typedef std::vector< CompoundPolygon3dCompoundPolygons3d
 
typedef std::vector< ConstAreaConstAreas
 
typedef std::vector< ConstHybridLineString2dConstHybridLineStrings2d
 
typedef std::vector< ConstHybridLineString3dConstHybridLineStrings3d
 
typedef std::vector< ConstHybridPolygon2dConstHybridPolygons2d
 
typedef std::vector< ConstHybridPolygon3dConstHybridPolygons3d
 
typedef std::vector< ConstLineStrings3dConstInnerBounds
 
typedef std::vector< ConstLaneletOrAreaConstLaneletOrAreas
 
typedef std::vector< ConstLaneletConstLanelets
 
typedef std::vector< ConstLineString2dConstLineStrings2d
 
typedef std::vector< ConstLineString3dConstLineStrings3d
 
typedef std::vector< ConstLineStringOrPolygon3dConstLineStringsOrPolygons3d
 
typedef std::vector< ConstPoint2dConstPoints2d
 
typedef std::vector< ConstPoint3dConstPoints3d
 
typedef std::vector< ConstPolygon2dConstPolygons2d
 
typedef std::vector< ConstPolygon3dConstPolygons3d
 
typedef boost::variant< ConstPoint3d, ConstLineString3d, ConstPolygon3d, ConstWeakLanelet, ConstWeakAreaConstRuleParameter
 
typedef HybridMap< ConstRuleParameters, decltype(RoleNameString::Map)&, RoleNameString::MapConstRuleParameterMap
 
typedef std::vector< ConstRuleParameterConstRuleParameters
 
typedef Segment< ConstPoint2dConstSegment2d
 
typedef Segment< ConstPoint3dConstSegment3d
 
using DefaultProjector = projection::SphericalMercatorProjector
 
using ErrorMessages = std::vector< std::string >
 
typedef std::vector< GPSPointGPSPoints
 
typedef int64_t Id
 
typedef std::vector< IdIds
 
typedef std::enable_if_t< traits::isAreaT< T >(), RetT > IfAr
 
typedef std::enable_if_t< traits::isLaneletT< T >(), RetT > IfLL
 
typedef std::enable_if_t< traits::isLinestringT< T >(), RetT > IfLS
 
typedef std::enable_if_t< traits::isLinestringT< T1 >() &&traits::isLinestringT< T2 >(), RetT > IfLS2
 
typedef std::enable_if_t< traits::isPolygonT< T >(), RetT > IfPoly
 
typedef std::enable_if_t< traits::isPointT< T >(), RetT > IfPT
 
typedef std::enable_if_t< traits::isRegulatoryElementT< T >(), RetT > IfRE
 
typedef std::vector< LineStrings3dInnerBounds
 
typedef std::shared_ptr< const LaneletDataLaneletDataConstPtr
 
typedef std::vector< LaneletDataConstPtrLaneletDataConstPtrs
 
typedef std::weak_ptr< const LaneletDataLaneletDataConstWptr
 
typedef std::vector< LaneletDataConstWptrLaneletDataConstWptrs
 
typedef std::shared_ptr< LaneletDataLaneletDataPtr
 
typedef std::weak_ptr< LaneletDataLaneletDataptr
 
typedef std::vector< LaneletDataPtrLaneletDataPtrs
 
typedef std::shared_ptr< const LaneletMapLaneletMapConstPtr
 
typedef std::vector< LaneletMapConstPtrLaneletMapConstPtrs
 
typedef std::unique_ptr< const LaneletMapLaneletMapConstUPtr
 
typedef std::shared_ptr< LaneletMapLaneletMapPtr
 
typedef std::vector< LaneletMapPtrLaneletMapPtrs
 
typedef std::unique_ptr< LaneletMapLaneletMapUPtr
 
typedef std::vector< LaneletLanelets
 
typedef std::shared_ptr< const LaneletSequenceDataLaneletSequenceDataConstPtr
 
typedef std::vector< LaneletSequenceDataConstPtrLaneletSequenceDataConstPtrs
 
typedef std::shared_ptr< LaneletSequenceDataLaneletSequenceDataPtr
 
typedef std::vector< LaneletSequenceDataPtrLaneletSequenceDataPtrs
 
typedef std::vector< LaneletSequenceLaneletSequences
 
typedef std::shared_ptr< const LaneletSubmapLaneletSubmapConstPtr
 
typedef std::vector< LaneletSubmapConstPtrLaneletSubmapConstPtrs
 
typedef std::unique_ptr< const LaneletSubmapLaneletSubmapConstUPtr
 
typedef std::shared_ptr< LaneletSubmapLaneletSubmapPtr
 
typedef std::vector< LaneletSubmapPtrLaneletSubmapPtrs
 
typedef std::unique_ptr< LaneletSubmapLaneletSubmapUPtr
 
typedef std::vector< LaneletWithStopLineLaneletsWithStopLines
 
typedef std::shared_ptr< const LineStringDataLineStringDataConstPtr
 
typedef std::vector< LineStringDataConstPtrLineStringDataConstPtrs
 
typedef std::shared_ptr< LineStringDataLineStringDataPtr
 
typedef std::vector< LineStringDataPtrLineStringDataPtrs
 
typedef PrimitiveLayer< LineString3dLineStringLayer
 
typedef std::vector< LineString2dLineStrings2d
 
typedef std::vector< LineString3dLineStrings3d
 
typedef std::vector< LineStringOrPolygon3dLineStringsOrPolygons3d
 
typedef boost::optional< double > OptDistance
 
typedef boost::optional< T > Optional
 
typedef std::shared_ptr< const PointDataPointDataConstPtr
 
typedef std::vector< PointDataConstPtrPointDataConstPtrs
 
typedef std::shared_ptr< PointDataPointDataPtr
 
typedef std::vector< PointDataPtrPointDataPtrs
 
typedef PrimitiveLayer< Point3dPointLayer
 
typedef std::vector< Point2dPoints2d
 
typedef std::vector< Point3dPoints3d
 
typedef PrimitiveLayer< Polygon3dPolygonLayer
 
typedef std::vector< Polygon2dPolygons2d
 
typedef std::vector< Polygon3dPolygons3d
 
typedef std::shared_ptr< const PrimitiveDataPrimitiveDataConstPtr
 
typedef std::vector< PrimitiveDataConstPtrPrimitiveDataConstPtrs
 
typedef std::shared_ptr< PrimitiveDataPrimitiveDataPtr
 
typedef std::vector< PrimitiveDataPtrPrimitiveDataPtrs
 
typedef std::shared_ptr< const RegulatoryElementRegulatoryElementConstPtr
 
typedef std::vector< RegulatoryElementConstPtrRegulatoryElementConstPtrs
 
typedef std::shared_ptr< const RegulatoryElementDataRegulatoryElementDataConstPtr
 
typedef std::vector< RegulatoryElementDataConstPtrRegulatoryElementDataConstPtrs
 
typedef std::shared_ptr< RegulatoryElementDataRegulatoryElementDataPtr
 
typedef std::vector< RegulatoryElementDataPtrRegulatoryElementDataPtrs
 
typedef PrimitiveLayer< RegulatoryElementPtrRegulatoryElementLayer
 
typedef std::shared_ptr< RegulatoryElementRegulatoryElementPtr
 
typedef std::vector< RegulatoryElementPtrRegulatoryElementPtrs
 
typedef boost::variant< Point3d, LineString3d, Polygon3d, WeakLanelet, WeakAreaRuleParameter
 
typedef HybridMap< RuleParameters, decltype(RoleNameString::Map)&, RoleNameString::MapRuleParameterMap
 
typedef std::vector< RuleParameterRuleParameters
 
typedef std::pair< PointT, PointT > Segment
 
typedef Segment< Point2dSegment2d
 
typedef Segment< Point3dSegment3d
 
typedef units::MPSQuantity Velocity
 

Enumerations

enum  AttributeName {
  AttributeName::Type, AttributeName::Subtype, AttributeName::OneWay, AttributeName::ParticipantVehicle,
  AttributeName::ParticipantPedestrian, AttributeName::SpeedLimit, AttributeName::Location, AttributeName::Dynamic
}
 
enum  LaneletType { LaneletType::OneWay, LaneletType::Bidirectional }
 
enum  ManeuverType { ManeuverType::Yield, ManeuverType::RightOfWay, ManeuverType::Unknown }
 
enum  RoleName {
  RoleName::Refers, RoleName::RefLine, RoleName::RightOfWay, RoleName::Yield,
  RoleName::Cancels, RoleName::CancelLine
}
 

Functions

Optional< std::string > Attribute::as< Optional< std::string > > () const
 
Optional< std::string > Attribute::as< std::string > () const
 
DefaultProjector defaultProjection (Origin origin=Origin::defaultOrigin())
 
std::unique_ptr< LaneletMapload (const std::string &filename, const Origin &origin=Origin::defaultOrigin(), ErrorMessages *errors=nullptr, const io::Configuration &params=io::Configuration())
 Loads a lanelet map from a file. More...
 
std::unique_ptr< LaneletMapload (const std::string &filename, const Projector &projector, ErrorMessages *errors=nullptr, const io::Configuration &params=io::Configuration())
 Loads a lanelet map from a file. More...
 
std::unique_ptr< LaneletMapload (const std::string &filename, const std::string &parserName, const Origin &origin=Origin::defaultOrigin(), ErrorMessages *errors=nullptr, const io::Configuration &params=io::Configuration())
 Loads a lanelet map from a file. More...
 
std::unique_ptr< LaneletMapload (const std::string &filename, const std::string &parserName, const Projector &projector, ErrorMessages *errors=nullptr, const io::Configuration &params=io::Configuration())
 Loads a lanelet map from file. More...
 
bool operator!= (const Attribute &lhs, const Attribute &rhs)
 
bool operator!= (const CompoundLineStringImpl< Point1T > &lhs, const CompoundLineStringImpl< Point2T > &rhs)
 
bool operator!= (const CompoundLineStringImpl< Point1T > &lhs, const std::vector< Point2T > &rhs)
 
bool operator!= (const ConstArea &lhs, const ConstArea &rhs)
 
bool operator!= (const ConstLanelet &lhs, const ConstLanelet &rhs)
 
bool operator!= (const ConstLaneletOrArea &lhs, const ConstLaneletOrArea &rhs)
 
bool operator!= (const ConstLineStringImpl< LhsPointT > &lhs, const ConstLineStringImpl< RhsPointT > &rhs)
 
bool operator!= (const ConstLineStringImpl< PointT > &lhs, const std::vector< PointT > &rhs)
 
bool operator!= (const ConstLineStringOrPolygon3d &lhs, const ConstLineStringOrPolygon3d &rhs)
 
bool operator!= (const ConstWeakArea &lhs, const ConstWeakArea &rhs)
 
bool operator!= (const ConstWeakLanelet &lhs, const ConstWeakLanelet &rhs)
 
bool operator!= (const LaneletSequence &lhs, const LaneletSequence &rhs)
 
bool operator!= (const LineStringOrPolygon3d &lhs, const LineStringOrPolygon3d &rhs)
 
bool operator!= (const std::vector< Point1T > &lhs, const CompoundLineStringImpl< Point2T > &rhs)
 
bool operator!= (const std::vector< PointT > &lhs, const ConstLineStringImpl< PointT > &rhs)
 
std::ostream & operator<< (std::ostream &stream, const Attribute &obj)
 
std::ostream & operator<< (std::ostream &stream, const AttributeMap &obj)
 
std::ostream & operator<< (std::ostream &stream, const CompoundLineStringImpl< PointT > &obj)
 
std::ostream & operator<< (std::ostream &stream, const ConstArea &obj)
 
std::ostream & operator<< (std::ostream &stream, const ConstLanelet &obj)
 
std::ostream & operator<< (std::ostream &stream, const ConstLaneletOrArea &obj)
 
std::ostream & operator<< (std::ostream &stream, const ConstLineString2d &obj)
 
std::ostream & operator<< (std::ostream &stream, const ConstLineString3d &obj)
 
std::ostream & operator<< (std::ostream &stream, const ConstLineStringOrPolygon3d &obj)
 
std::ostream & operator<< (std::ostream &stream, const ConstPoint2d &obj)
 
std::ostream & operator<< (std::ostream &stream, const ConstPoint3d &obj)
 
std::ostream & operator<< (std::ostream &stream, const ConstPolygon2d &obj)
 
std::ostream & operator<< (std::ostream &stream, const ConstPolygon3d &obj)
 
std::ostream & operator<< (std::ostream &stream, const LaneletSequence &obj)
 
std::ostream & operator<< (std::ostream &stream, const LineStringOrPolygon3d &obj)
 
std::ostream & operator<< (std::ostream &stream, const Point2d &obj)
 
std::ostream & operator<< (std::ostream &stream, const Point3d &obj)
 
std::ostream & operator<< (std::ostream &stream, const RegulatoryElement &obj)
 
std::ostream & operator<< (std::ostream &stream, HybridMap< Value, Enum, Lookup > map)
 
bool operator== (const AreaData &lhs, const AreaData &rhs)
 
bool operator== (const Attribute &lhs, const Attribute &rhs)
 
bool operator== (const CompoundLineStringImpl< Point1T > &lhs, const CompoundLineStringImpl< Point2T > &rhs)
 
bool operator== (const CompoundLineStringImpl< Point1T > &lhs, const std::vector< Point2T > &rhs)
 
bool operator== (const ConstArea &lhs, const ConstArea &rhs)
 
bool operator== (const ConstLanelet &lhs, const ConstLanelet &rhs)
 
bool operator== (const ConstLaneletOrArea &lhs, const ConstLaneletOrArea &rhs)
 
bool operator== (const ConstLineStringImpl< LhsPointT > &lhs, const ConstLineStringImpl< RhsPointT > &rhs)
 
bool operator== (const ConstLineStringImpl< PointT > &lhs, const std::vector< PointT > &rhs)
 
bool operator== (const ConstLineStringOrPolygon3d &lhs, const ConstLineStringOrPolygon3d &rhs)
 
bool operator== (const ConstWeakArea &lhs, const ConstWeakArea &rhs)
 
bool operator== (const ConstWeakLanelet &lhs, const ConstWeakLanelet &rhs)
 
bool operator== (const LaneletData &lhs, const LaneletData &rhs)
 
bool operator== (const LaneletMap &rhs, const LaneletMap &lhs)
 
bool operator== (const LaneletSequence &lhs, const LaneletSequence &rhs)
 
bool operator== (const LineStringData &lhs, const LineStringData &rhs)
 
bool operator== (const LineStringOrPolygon3d &lhs, const LineStringOrPolygon3d &rhs)
 
bool operator== (const PointData &lhs, const PointData &rhs)
 
template<typename T >
bool operator== (const PrimitiveLayer< T > &rhs, const PrimitiveLayer< T > &lhs)
 
bool operator== (const RegulatoryElementData &rhs, const RegulatoryElementData &lhs)
 
bool operator== (const std::vector< Point1T > &lhs, const CompoundLineStringImpl< Point2T > &rhs)
 
bool operator== (const std::vector< PointT > &lhs, const ConstLineStringImpl< PointT > &rhs)
 
template<>
bool operator==<RegulatoryElementPtr > (const PrimitiveLayer< RegulatoryElementPtr > &rhs, const PrimitiveLayer< RegulatoryElementPtr > &lhs)
 
std::vector< std::string > supportedParserExtensions ()
 
std::vector< std::string > supportedParsers ()
 returns the names of the currently registered parsers (parsers from plugins included) More...
 
std::vector< std::string > supportedWriterExtensions ()
 returns the names of the currently supported extensions for writing (including the dot) More...
 
std::vector< std::string > supportedWriters ()
 returns the names of the currently registered writing (writers from plugins included) More...
 
void write (const std::string &filename, const lanelet::LaneletMap &map, const Origin &origin=Origin::defaultOrigin(), ErrorMessages *errors=nullptr, const io::Configuration &params=io::Configuration())
 writes a map to a file More...
 
void write (const std::string &filename, const lanelet::LaneletMap &map, const std::string &writerName, const Origin &origin=Origin::defaultOrigin(), ErrorMessages *errors=nullptr, const io::Configuration &params=io::Configuration())
 writes a map to a file More...
 
void write (const std::string &filename, const LaneletMap &map, const Projector &projector, ErrorMessages *errors=nullptr, const io::Configuration &params=io::Configuration())
 writes a map to a file More...
 
void write (const std::string &filename, const LaneletMap &map, const std::string &writerName, const Projector &projector, ErrorMessages *errors=nullptr, const io::Configuration &params=io::Configuration())
 writes a map to a file More...
 

Variables

static RegisterRegulatoryElement< GenericRegulatoryElementgenRegelem
 
constexpr Id InvalId
 
static RegisterRegulatoryElement< AllWayStopregAllWayStop
 
static RegisterRegulatoryElement< RightOfWayregRightOfWay
 
static RegisterRegulatoryElement< SpeedLimitregSpeedLimit
 
static RegisterRegulatoryElement< TrafficLightregTraffic
 
static RegisterRegulatoryElement< TrafficSignregTrafficSign
 

Typedef Documentation

◆ DefaultProjector

Definition at line 76 of file Projection.h.

◆ ErrorMessages

typedef std::vector< std::string > lanelet::ErrorMessages

Definition at line 11 of file Io.h.

Function Documentation

◆ defaultProjection()

DefaultProjector lanelet::defaultProjection ( Origin  origin = Origin::defaultOrigin())
inline

Definition at line 78 of file Projection.h.

◆ load() [1/4]

std::unique_ptr< LaneletMap > lanelet::load ( const std::string &  filename,
const Origin origin = Origin::defaultOrigin(),
ErrorMessages errors = nullptr,
const io::Configuration params = io::Configuration() 
)

Loads a lanelet map from a file.

Parameters
filenamename to load from. The extension decides how the file will be parsed.
originorigin for the lat/lon -> x/y conversion. This must not be the default origin if the specified format requires an origin (e.g. you must always provide an origin if you load .osm data).
errorsif this points to a valid object, errors occured during parsing the map will be passed via this parameter. If this is nullptr, an exception will be thrown if errors have occurred.
paramsoptional params for loading. It depends on the parser that is used which parameters are required. If no params are passed, default values will be used
Returns
Loaded map. Pointer is aways valid. Otherwise, an exception will be thrown
Exceptions
lanelet2::IOErrorif the file did not exist, could not be parsed or extension is not supported. If errors is not null, the loader will instead try to recover and only throw on unrecoverable errors (ie if the map did not exist). However, the loaded map will be incomplete if errors occurred. The loader will also throw if you did not provide a valid origin for a map that requires an origin for projections.

It can not be stressed enough that it is important to provide a valid origin to write/load maps with georeferenced (lat/lon) data. If no origin is specified, the loaded map will most likely be not correctly located and deformed.

Definition at line 24 of file Io.cpp.

◆ load() [2/4]

std::unique_ptr< LaneletMap > lanelet::load ( const std::string &  filename,
const Projector projector,
ErrorMessages errors = nullptr,
const io::Configuration params = io::Configuration() 
)

Loads a lanelet map from a file.

Parameters
filenamename to load from. The extension decides how the file will be parsed.
projectorprojection object for the transformations used
errorsif not null, errors will be reported here instead of throwing
paramsoptional params for loading. It depends on the parser that is used which parameters are required. If no params are passed, default values will be used
Returns
Loaded map. Pointer is aways valid. Otherwise, an exception will be thrown
Exceptions
lanelet2::IOErrorif the file did not exist, could not be parsed or extension is not supported. If errors is not null, the loader will instead try to recover and only throw on unrecoverable errors (ie if the map did not exist). However, the loaded map will be incomplete if errors occurred.

Definition at line 29 of file Io.cpp.

◆ load() [3/4]

std::unique_ptr< LaneletMap > lanelet::load ( const std::string &  filename,
const std::string &  parserName,
const Origin origin = Origin::defaultOrigin(),
ErrorMessages errors = nullptr,
const io::Configuration params = io::Configuration() 
)

Loads a lanelet map from a file.

Parameters
filenamename to load from
parserNamename of the parser to use. Available parsers can be queried with supportedParsers()
originorigin for the lat/lon -> x/y conversion. This must not be the default origin if the specified format requires an origin (e.g. you must always provide an origin if you load .osm data).
errorsif this points to a valid object, errors occured during parsing the map will be passed via this parameter. If this is nullptr, an exception will be thrown if errors have occurred.
paramsoptional params for loading. It depends on the parser that is used which parameters are required. If no params are passed, default values will be used
Returns
Loaded map. Pointer is aways valid. Otherwise, an exception will be thrown
Exceptions
lanelet2::IOErrorif the file did not exist, could not be parsed, the default origin was provided for a map that requires osm conversion or extension is not supported

Definition at line 41 of file Io.cpp.

◆ load() [4/4]

std::unique_ptr< LaneletMap > lanelet::load ( const std::string &  filename,
const std::string &  parserName,
const Projector projector,
ErrorMessages errors = nullptr,
const io::Configuration params = io::Configuration() 
)

Loads a lanelet map from file.

Parameters
filenamename to load from
parserNamename of the parser to use. Available parsers can be queried with supportedParsers()
errorsif this points to a valid object, errors occured during parsing the map will be passed via this parameter. If this is nullptr, an exception will be thrown if errors have occurred.
projectorprojection object for the transformations
paramsoptional params for loading. It depends on the parser that is used which parameters are required. If no params are passed, default values will be used
Returns
Loaded map. Pointer is aways valid. Otherwise, an exception will be thrown
Exceptions
lanelet2::IOErrorif the file did not exist, could not be parsed or extension is not supported

Definition at line 46 of file Io.cpp.

◆ operator==() [1/7]

bool lanelet::operator== ( const AreaData lhs,
const AreaData rhs 
)
inline

Definition at line 34 of file TestSetup.h.

◆ operator==() [2/7]

bool lanelet::operator== ( const LaneletData lhs,
const LaneletData rhs 
)
inline

Definition at line 24 of file TestSetup.h.

◆ operator==() [3/7]

bool lanelet::operator== ( const LaneletMap rhs,
const LaneletMap lhs 
)
inline

Definition at line 62 of file TestSetup.h.

◆ operator==() [4/7]

bool lanelet::operator== ( const LineStringData lhs,
const LineStringData rhs 
)
inline

Definition at line 16 of file TestSetup.h.

◆ operator==() [5/7]

bool lanelet::operator== ( const PointData lhs,
const PointData rhs 
)
inline

Definition at line 12 of file TestSetup.h.

◆ operator==() [6/7]

template<typename T >
bool lanelet::operator== ( const PrimitiveLayer< T > &  rhs,
const PrimitiveLayer< T > &  lhs 
)
inline

Definition at line 48 of file TestSetup.h.

◆ operator==() [7/7]

bool lanelet::operator== ( const RegulatoryElementData rhs,
const RegulatoryElementData lhs 
)
inline

Definition at line 21 of file TestSetup.h.

◆ operator==<RegulatoryElementPtr >()

template<>
bool lanelet::operator==<RegulatoryElementPtr > ( const PrimitiveLayer< RegulatoryElementPtr > &  rhs,
const PrimitiveLayer< RegulatoryElementPtr > &  lhs 
)
inline

Definition at line 55 of file TestSetup.h.

◆ supportedParserExtensions()

std::vector< std::string > lanelet::supportedParserExtensions ( )

Definition at line 59 of file Io.cpp.

◆ supportedParsers()

std::vector< std::string > lanelet::supportedParsers ( )

returns the names of the currently registered parsers (parsers from plugins included)

Returns
list of names

Definition at line 57 of file Io.cpp.

◆ supportedWriterExtensions()

std::vector< std::string > lanelet::supportedWriterExtensions ( )

returns the names of the currently supported extensions for writing (including the dot)

Returns
list of extensions

Definition at line 84 of file Io.cpp.

◆ supportedWriters()

std::vector< std::string > lanelet::supportedWriters ( )

returns the names of the currently registered writing (writers from plugins included)

Returns
list of names

Definition at line 82 of file Io.cpp.

◆ write() [1/4]

void lanelet::write ( const std::string &  filename,
const lanelet::LaneletMap map,
const Origin origin = Origin::defaultOrigin(),
ErrorMessages errors = nullptr,
const io::Configuration params = io::Configuration() 
)

writes a map to a file

Parameters
filenamefile to write to (parent folders must exist!)
mapmap to be written
originorigin for x,y -> lat/lon conversion. You will receive a warning if you try to write to a format that requires lat/lon conversion and passed the defaultOrigin.
errorsif this points to a valid object, errors occured during write will be passed via this parameter. If this is nullptr, an exception will be thrown if errors have occurred.
paramsextra parameters for the writer (if required). If empty, default parameters will be used.
Exceptions
lanelet2::IOErrorif the file could not be created or writing failed. If errors is not null, the writer will instead try to recover and only throw on unrecoverable errors (ie if the file could not be created). However, the written map will be incomplete if errors occurred.

It can not be stressed enough that it is important to provide a valid origin to write/load maps with georeferenced (lat/lon) data. If no origin is specified, the written map will most likely be not correctly located and deformed.

Definition at line 61 of file Io.cpp.

◆ write() [2/4]

void lanelet::write ( const std::string &  filename,
const lanelet::LaneletMap map,
const std::string &  writerName,
const Origin origin = Origin::defaultOrigin(),
ErrorMessages errors = nullptr,
const io::Configuration params = io::Configuration() 
)

writes a map to a file

Parameters
filenamefile to write to (parent folders must exist!). The extension is used to deduce the format.
mapmap to be written
writerNamename of the writer format to use. Available writers can be queried with supportedWriters().
errorsif this points to a valid object, errors occured during write will be passed via this parameter. If this is nullptr, an exception will be thrown if errors have occurred.
originorigin definition for x,y -> lat/lon conversion
paramsextra parameters for the writer (if required). If empty, default parameters will be used.
Exceptions
lanelet2::IOErrorif the file could not be created or writing failed.

Definition at line 71 of file Io.cpp.

◆ write() [3/4]

void lanelet::write ( const std::string &  filename,
const LaneletMap map,
const Projector projector,
ErrorMessages errors = nullptr,
const io::Configuration params = io::Configuration() 
)

writes a map to a file

Parameters
filenamefile to write to (parent folders must exist!). The extension is used to deduce the format.
mapmap to be written
projectorprojector object for x,y -> lat/lon conversion. You will receive a warning if you try to write to a format that requires lat/lon conversion and passed the defaultOrigin.
errorsif this points to a valid object, errors occured during write will be passed via this parameter. If this is nullptr, an exception will be thrown if errors have occurred.
paramsextra parameters for the writer (if required). If empty, default parameters will be used.
Exceptions
lanelet2::IOErrorif the file could not be created or writing failed.

Definition at line 65 of file Io.cpp.

◆ write() [4/4]

void lanelet::write ( const std::string &  filename,
const LaneletMap map,
const std::string &  writerName,
const Projector projector,
ErrorMessages errors = nullptr,
const io::Configuration params = io::Configuration() 
)

writes a map to a file

Parameters
filenamefile to write to (parent folders must exist!). The extension is used to deduce the format.
mapmap to be written
writerNamename of the writer format to use. Available writers can be queried with supportedWriters().
projectorprojector object for x,y -> lat/lon conversion
errorsif this points to a valid object, errors occured during write will be passed via this parameter. If this is nullptr, an exception will be thrown if errors have occurred.
paramsextra parameters for the writer (if required). If empty, default parameters will be used.
Exceptions
lanelet2::IOErrorif the file could not be created or writing failed.

Definition at line 75 of file Io.cpp.



lanelet2_io
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:26:03