Autoware.Auto
autoware::lanelet2_map_provider::Lanelet2MapProvider Class Reference

Provides functoins to load and access a lanelet2 OSM map. More...

#include <lanelet2_map_provider.hpp>

Public Member Functions

 Lanelet2MapProvider (const std::string &map_filename, const geometry_msgs::msg::TransformStamped &stf, const float64_t offset_lat=0.0, const float64_t offset_lon=0.0)
 Constructor from a transform between earth and map frames. More...
 
 Lanelet2MapProvider (const std::string &map_filename, const LatLonAlt map_frame_origin, const float64_t offset_lat=0.0, const float64_t offset_lon=0.0)
 Constructor from latitude, longitude, altitude. More...
 

Public Attributes

std::shared_ptr< lanelet::LaneletMap > m_map
 

Detailed Description

Provides functoins to load and access a lanelet2 OSM map.

Constructor & Destructor Documentation

◆ Lanelet2MapProvider() [1/2]

autoware::lanelet2_map_provider::Lanelet2MapProvider::Lanelet2MapProvider ( const std::string &  map_filename,
const geometry_msgs::msg::TransformStamped &  stf,
const float64_t  offset_lat = 0.0,
const float64_t  offset_lon = 0.0 
)

Constructor from a transform between earth and map frames.

Parameters
map_filenameThe lanelet map filename
stfThe earth to map transform for projection of map data
offset_latLatitude offset in degrees to be added to the map frame origin
offset_lonLongitude offset in degrees to be added to the map origin

◆ Lanelet2MapProvider() [2/2]

autoware::lanelet2_map_provider::Lanelet2MapProvider::Lanelet2MapProvider ( const std::string &  map_filename,
const LatLonAlt  map_frame_origin,
const float64_t  offset_lat = 0.0,
const float64_t  offset_lon = 0.0 
)

Constructor from latitude, longitude, altitude.

Parameters
map_filenameThe lanelet map filename
map_frame_originThe map frame origin
offset_latLatitude offset in degrees to be added to the map frame origin
offset_lonLongitude offset in degrees to be added to the map frame origin

Member Data Documentation

◆ m_map

std::shared_ptr<lanelet::LaneletMap> autoware::lanelet2_map_provider::Lanelet2MapProvider::m_map

The map itself. After the constructor logic has been done, this is guaranteed to be initialized.


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