Go to the documentation of this file. 1 #include <lanelet2_core/primitives/Lanelet.h>
9 #pragma GCC diagnostic ignored "-Wunused-but-set-variable"
15 std::string exampleMapPath = std::string(PKG_DIR) +
"/../lanelet2_maps/res/mapping_example.osm";
17 std::string tempfile(
const std::string& name) {
18 char tmpDir[] =
"/tmp/lanelet2_example_XXXXXX";
19 auto*
file = mkdtemp(tmpDir);
20 if (file ==
nullptr) {
23 return std::string(file) +
'/' + name;
57 map =
load(exampleMapPath, projector, &errors);
58 assert(errors.empty());
67 assert(std::abs(projection.x()) < 1e-6);
90 static constexpr
const char*
name() {
void part1LoadingAndWriting()
std::vector< std::string > ErrorMessages
std::shared_ptr< LaneletMap > LaneletMapPtr
static constexpr const char * name()
std::map< std::string, Attribute > Configuration
Eigen::Vector3d BasicPoint3d
BasicPoint3d forward(const GPSPoint &gps) const override
static constexpr const char * extension()
std::unique_ptr< LaneletMap > load(const std::string &filename, const Origin &origin=Origin::defaultOrigin(), ErrorMessages *errors=nullptr, const io::Configuration ¶ms=io::Configuration())
void write(const std::string &filename, const lanelet::LaneletMap &map, const Origin &origin=Origin::defaultOrigin(), ErrorMessages *errors=nullptr, const io::Configuration ¶ms=io::Configuration())
void part3AddingNewParsersAndWriters()
void write(const std::string &, const lanelet::LaneletMap &, lanelet::ErrorMessages &, const lanelet::io::Configuration &) const override
lanelet2_examples
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:26:15