diff --git a/LibCarla/source/carla/client/Map.cpp b/LibCarla/source/carla/client/Map.cpp index f11c97a0c..8a26457a6 100644 --- a/LibCarla/source/carla/client/Map.cpp +++ b/LibCarla/source/carla/client/Map.cpp @@ -29,6 +29,12 @@ namespace client { : _description(std::move(description)), _map(MakeMap(_description.open_drive_file)) {} + Map::Map(std::string name, std::string xodr_content) + : Map(rpc::MapInfo{ + std::move(name), + std::move(xodr_content), + std::vector{}}) {} + Map::~Map() = default; SharedPtr Map::GetWaypoint( diff --git a/LibCarla/source/carla/client/Map.h b/LibCarla/source/carla/client/Map.h index 3375ecf0b..23961380f 100644 --- a/LibCarla/source/carla/client/Map.h +++ b/LibCarla/source/carla/client/Map.h @@ -27,6 +27,8 @@ namespace client { explicit Map(rpc::MapInfo description); + explicit Map(std::string name, std::string xodr_content); + ~Map(); const std::string &GetName() const { diff --git a/PythonAPI/source/libcarla/Map.cpp b/PythonAPI/source/libcarla/Map.cpp index da1c1b93b..b23d49b94 100644 --- a/PythonAPI/source/libcarla/Map.cpp +++ b/PythonAPI/source/libcarla/Map.cpp @@ -59,6 +59,7 @@ void export_map() { namespace cg = carla::geom; class_>("Map", no_init) + .def(init((arg("name"), arg("xodr_content")))) .add_property("name", CALL_RETURNING_COPY(cc::Map, GetName)) .def("get_spawn_points", CALL_RETURNING_LIST(cc::Map, GetRecommendedSpawnPoints)) .def("get_waypoint", &cc::Map::GetWaypoint, (arg("location"), arg("project_to_road")=true))