io.cpp
Go to the documentation of this file.
1 #include <lanelet2_io/Io.h>
2 
4 
5 namespace py = boost::python;
6 using namespace lanelet;
7 
9  DictToConfigurationConverter() { py::converter::registry::push_back(&convertible, &construct, py::type_id<io::Configuration>()); }
10  static void* convertible(PyObject* obj) {
11  if (!PyDict_CheckExact(obj)) { // NOLINT
12  return nullptr;
13  }
14  return obj;
15  }
16  static void construct(PyObject* obj, py::converter::rvalue_from_python_stage1_data* data) {
17  py::dict d(py::borrowed(obj));
18  py::list keys = d.keys();
19  py::list values = d.values();
20  io::Configuration attributes;
21  for (auto i = 0u; i < py::len(keys); ++i) {
22  std::string key = py::extract<std::string>(keys[i]);
23  std::string value = py::extract<std::string>(values[i]);
24  attributes.insert(std::make_pair(key, value));
25  }
26  using StorageType = py::converter::rvalue_from_python_storage<io::Configuration>;
27  void* storage = reinterpret_cast<StorageType*>(data)->storage.bytes; // NOLINT
28  new (storage) io::Configuration(attributes);
29  data->convertible = storage;
30  }
31 };
32 
33 std::shared_ptr<LaneletMap> loadWrapper(const std::string& filename, const Origin& origin) {
34  return load(filename, origin);
35 }
36 std::shared_ptr<LaneletMap> loadProjectorWrapper(const std::string& filename, const Projector& projector) {
37  return load(filename, projector);
38 }
39 py::tuple loadWithErrorWrapper(const std::string& filename, const Projector& projector) {
40  ErrorMessages errs;
41  LaneletMapPtr map = load(filename, projector, &errs);
42  return py::make_tuple(map, errs);
43 }
44 
45 void writeWrapper(const std::string& filename, const LaneletMap& map, const Origin& origin, const Optional<io::Configuration>& params) {
46  write(filename, map, origin, nullptr, params.get_value_or(io::Configuration()));
47 }
48 
49 void writeProjectorWrapper(const std::string& filename, const LaneletMap& map, const Projector& projector, const Optional<io::Configuration>& params) {
50  write(filename, map, projector, nullptr, params.get_value_or(io::Configuration()));
51 }
52 
53 ErrorMessages writeWithErrorWrapper(const std::string& filename, const LaneletMap& map, const Projector& projector, const Optional<io::Configuration>& params) {
54  ErrorMessages errs;
55  write(filename, map, projector, &errs, params.get_value_or(io::Configuration()));
56  return errs;
57 }
58 
59 BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME) { // NOLINT
60  auto core = py::import("lanelet2.core");
61  auto proj = py::import("lanelet2.projection");
62 
66 
67  py::class_<Origin, std::shared_ptr<Origin>>("Origin", py::init<>())
68  .def(py::init<GPSPoint>())
69  .def("__init__", py::make_constructor(
70  +[](double lat, double lon, double alt) {
71  return std::make_shared<Origin>(GPSPoint{lat, lon, alt});
72  },
73  py::default_call_policies(), (py::arg("lat") = 0., py::arg("lon") = 0., py::arg("lon") = 0)))
74  .def_readwrite("position", &Origin::position);
75 
76  py::def("load", loadProjectorWrapper, (py::arg("filename"), py::arg("projector") = DefaultProjector()));
77  py::def("load", loadWrapper, (py::arg("filename"), py::arg("origin")));
78  py::def("loadRobust", loadWithErrorWrapper, py::arg("filename"),
79  "Loads a map robustly. Parser errors are returned as second member of "
80  "the tuple. If there are errors, the map will be incomplete somewhere.");
81 
82  py::def("write", writeProjectorWrapper, (py::arg("filename"), py::arg("map"), py::arg("projector"), py::arg("params") = Optional<io::Configuration>{}),
83  "Writes the map to a file. The extension determines which format will "
84  "be used (usually .osm)");
85  py::def("write", writeWrapper, (py::arg("filename"), py::arg("map"), py::arg("origin"), py::arg("params") = Optional<io::Configuration>{}),
86  "Writes the map to a file. The extension determines which format will "
87  "be used (usually .osm)");
88  py::def("writeRobust", writeWithErrorWrapper, (py::arg("filename"), py::arg("map"), py::arg("projector"), py::arg("params") = Optional<io::Configuration>{}),
89  "Writes a map robustly and returns writer errors. If there are errors, "
90  "the map will be incomplete somewhere.");
91 }
ErrorMessages
std::vector< std::string > ErrorMessages
loadProjectorWrapper
std::shared_ptr< LaneletMap > loadProjectorWrapper(const std::string &filename, const Projector &projector)
Definition: io.cpp:36
LaneletMapPtr
std::shared_ptr< LaneletMap > LaneletMapPtr
lanelet
lanelet::io::Configuration
std::map< std::string, Attribute > Configuration
converters::ToOptionalConverter
Definition: converter.h:108
writeWithErrorWrapper
ErrorMessages writeWithErrorWrapper(const std::string &filename, const LaneletMap &map, const Projector &projector, const Optional< io::Configuration > &params)
Definition: io.cpp:53
DictToConfigurationConverter
Definition: io.cpp:8
Io.h
DictToConfigurationConverter::convertible
static void * convertible(PyObject *obj)
Definition: io.cpp:10
loadWrapper
std::shared_ptr< LaneletMap > loadWrapper(const std::string &filename, const Origin &origin)
Definition: io.cpp:33
lanelet::DefaultProjector
projection::SphericalMercatorProjector DefaultProjector
lanelet::Origin::position
GPSPoint position
loadWithErrorWrapper
py::tuple loadWithErrorWrapper(const std::string &filename, const Projector &projector)
Definition: io.cpp:39
BOOST_PYTHON_MODULE
BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME)
Definition: io.cpp:59
converter.h
lanelet::Projector
lanelet::LaneletMap
Optional
boost::optional< T > Optional
lanelet::load
std::unique_ptr< LaneletMap > load(const std::string &filename, const Origin &origin=Origin::defaultOrigin(), ErrorMessages *errors=nullptr, const io::Configuration &params=io::Configuration())
create_debug_routing_graph.proj
proj
Definition: create_debug_routing_graph.py:25
lanelet::Origin
make_ids_positive.map
map
Definition: make_ids_positive.py:25
DictToConfigurationConverter::construct
static void construct(PyObject *obj, py::converter::rvalue_from_python_stage1_data *data)
Definition: io.cpp:16
lanelet::write
void write(const std::string &filename, const lanelet::LaneletMap &map, const Origin &origin=Origin::defaultOrigin(), ErrorMessages *errors=nullptr, const io::Configuration &params=io::Configuration())
d
double d
DictToConfigurationConverter::DictToConfigurationConverter
DictToConfigurationConverter()
Definition: io.cpp:9
writeWrapper
void writeWrapper(const std::string &filename, const LaneletMap &map, const Origin &origin, const Optional< io::Configuration > &params)
Definition: io.cpp:45
converters::ToOptionalConverter::fromPython
ToOptionalConverter & fromPython()
Definition: converter.h:112
writeProjectorWrapper
void writeProjectorWrapper(const std::string &filename, const LaneletMap &map, const Projector &projector, const Optional< io::Configuration > &params)
Definition: io.cpp:49
lanelet::GPSPoint
converters::OptionalConverter
py::to_python_converter< lanelet::Optional< T >, OptionalToObject< T > > OptionalConverter
Definition: converter.h:222


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