Go to the documentation of this file.
5 namespace py = boost::python;
11 if (!PyDict_CheckExact(obj)) {
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();
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));
26 using StorageType = py::converter::rvalue_from_python_storage<io::Configuration>;
27 void* storage =
reinterpret_cast<StorageType*
>(data)->storage.bytes;
29 data->convertible = storage;
33 std::shared_ptr<LaneletMap>
loadWrapper(
const std::string& filename,
const Origin& origin) {
34 return load(filename, origin);
37 return load(filename, projector);
42 return py::make_tuple(
map, errs);
60 auto core = py::import(
"lanelet2.core");
61 auto proj = py::import(
"lanelet2.projection");
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});
73 py::default_call_policies(), (py::arg(
"lat") = 0., py::arg(
"lon") = 0., py::arg(
"lon") = 0)))
77 py::def(
"load",
loadWrapper, (py::arg(
"filename"), py::arg(
"origin")));
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.");
83 "Writes the map to a file. The extension determines which format will "
84 "be used (usually .osm)");
86 "Writes the map to a file. The extension determines which format will "
87 "be used (usually .osm)");
89 "Writes a map robustly and returns writer errors. If there are errors, "
90 "the map will be incomplete somewhere.");
std::vector< std::string > ErrorMessages
std::shared_ptr< LaneletMap > loadProjectorWrapper(const std::string &filename, const Projector &projector)
std::shared_ptr< LaneletMap > LaneletMapPtr
std::map< std::string, Attribute > Configuration
ErrorMessages writeWithErrorWrapper(const std::string &filename, const LaneletMap &map, const Projector &projector, const Optional< io::Configuration > ¶ms)
static void * convertible(PyObject *obj)
std::shared_ptr< LaneletMap > loadWrapper(const std::string &filename, const Origin &origin)
projection::SphericalMercatorProjector DefaultProjector
py::tuple loadWithErrorWrapper(const std::string &filename, const Projector &projector)
BOOST_PYTHON_MODULE(PYTHON_API_MODULE_NAME)
boost::optional< T > Optional
std::unique_ptr< LaneletMap > load(const std::string &filename, const Origin &origin=Origin::defaultOrigin(), ErrorMessages *errors=nullptr, const io::Configuration ¶ms=io::Configuration())
static void construct(PyObject *obj, py::converter::rvalue_from_python_stage1_data *data)
void write(const std::string &filename, const lanelet::LaneletMap &map, const Origin &origin=Origin::defaultOrigin(), ErrorMessages *errors=nullptr, const io::Configuration ¶ms=io::Configuration())
DictToConfigurationConverter()
void writeWrapper(const std::string &filename, const LaneletMap &map, const Origin &origin, const Optional< io::Configuration > ¶ms)
ToOptionalConverter & fromPython()
void writeProjectorWrapper(const std::string &filename, const LaneletMap &map, const Projector &projector, const Optional< io::Configuration > ¶ms)
py::to_python_converter< lanelet::Optional< T >, OptionalToObject< T > > OptionalConverter
lanelet2_python
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:26:14