diff --git a/LibCarla/source/carla/road/element/Geometry.cpp b/LibCarla/source/carla/road/element/Geometry.cpp index a290d1e8c..7f0edf24a 100644 --- a/LibCarla/source/carla/road/element/Geometry.cpp +++ b/LibCarla/source/carla/road/element/Geometry.cpp @@ -132,7 +132,10 @@ namespace element { } void GeometryPoly3::PreComputeSpline() { - const double delta_u = 0.01; // interval between values of u + // Roughly the interval size in m + constexpr double interval_size = 0.5; + size_t number_intervals = std::max(static_cast(_length / interval_size), size_t(1)); + const double delta_u = 1.0 / number_intervals;; // interval between values of u double current_s = 0; double current_u = 0; double last_u = 0; @@ -187,7 +190,9 @@ namespace element { } void GeometryParamPoly3::PreComputeSpline() { - size_t number_intervals = 1000; + // Roughly the interval size in m + constexpr double interval_size = 0.5; + size_t number_intervals = std::max(static_cast(_length / interval_size), size_t(10)); double delta_p = 1.0 / number_intervals; if (_arcLength) { delta_p *= _length; diff --git a/PythonAPI/util/load_osm_map.py b/PythonAPI/util/load_osm_map.py index 1a1360655..f683b2950 100644 --- a/PythonAPI/util/load_osm_map.py +++ b/PythonAPI/util/load_osm_map.py @@ -89,6 +89,9 @@ def main(): temp_file.close() fixed_xodr = fix_opendrive(broken_xodr, args.center_map) + temp_file = open('temp_opendrive.xodr', 'w') + temp_file.write(fixed_xodr) + temp_file.close() print('OpenDRIVE file fixed, connecting to simulation...') client = carla.Client(args.host, args.port, worker_threads=1)