From ab2f6f5bb620c7e626712ef7ee974be30825a998 Mon Sep 17 00:00:00 2001 From: nsubiron Date: Mon, 1 Jul 2019 12:09:28 +0200 Subject: [PATCH] Move third-party code in LibCarla to a third-party folder --- LibCarla/cmake/CMakeLists.txt | 2 + LibCarla/cmake/client/CMakeLists.txt | 22 +++-- LibCarla/cmake/server/CMakeLists.txt | 18 ++-- .../carla/opendrive/OpenDriveParser.cpp | 3 +- .../opendrive/parser/GeoReferenceParser.cpp | 3 +- .../carla/opendrive/parser/GeometryParser.cpp | 4 +- .../carla/opendrive/parser/JunctionParser.cpp | 4 +- .../carla/opendrive/parser/LaneParser.cpp | 4 +- .../carla/opendrive/parser/ObjectParser.cpp | 4 +- .../carla/opendrive/parser/ProfilesParser.cpp | 4 +- .../carla/opendrive/parser/RoadParser.cpp | 3 +- .../carla/opendrive/parser/SignalParser.cpp | 4 +- .../opendrive/parser/TrafficGroupParser.cpp | 4 +- .../source/carla/road/element/Geometry.cpp | 85 +++++++++++++++++++ LibCarla/source/carla/road/element/Geometry.h | 66 ++------------ .../source/test/client/test_opendrive.cpp | 3 +- .../element => third-party}/cephes/const.h | 0 .../element => third-party}/cephes/fresnel.h | 0 .../element => third-party}/cephes/fresnl.cpp | 0 .../element => third-party}/cephes/polevl.cpp | 0 .../element => third-party}/cephes/polevl.h | 0 .../moodycamel/ConcurrentQueue.h | 0 .../parser => third-party}/pugixml/LICENSE.md | 0 .../pugixml/pugiconfig.hpp | 0 .../pugixml/pugixml.cpp | 0 .../pugixml/pugixml.hpp | 0 26 files changed, 131 insertions(+), 102 deletions(-) create mode 100644 LibCarla/source/carla/road/element/Geometry.cpp rename LibCarla/source/{carla/road/element => third-party}/cephes/const.h (100%) rename LibCarla/source/{carla/road/element => third-party}/cephes/fresnel.h (100%) rename LibCarla/source/{carla/road/element => third-party}/cephes/fresnl.cpp (100%) rename LibCarla/source/{carla/road/element => third-party}/cephes/polevl.cpp (100%) rename LibCarla/source/{carla/road/element => third-party}/cephes/polevl.h (100%) rename LibCarla/source/{ => third-party}/moodycamel/ConcurrentQueue.h (100%) rename LibCarla/source/{carla/opendrive/parser => third-party}/pugixml/LICENSE.md (100%) rename LibCarla/source/{carla/opendrive/parser => third-party}/pugixml/pugiconfig.hpp (100%) rename LibCarla/source/{carla/opendrive/parser => third-party}/pugixml/pugixml.cpp (100%) rename LibCarla/source/{carla/opendrive/parser => third-party}/pugixml/pugixml.hpp (100%) diff --git a/LibCarla/cmake/CMakeLists.txt b/LibCarla/cmake/CMakeLists.txt index 34ee34ab2..99d5e4b48 100644 --- a/LibCarla/cmake/CMakeLists.txt +++ b/LibCarla/cmake/CMakeLists.txt @@ -10,8 +10,10 @@ message(STATUS "Build release: ${LIBCARLA_BUILD_RELEASE}") message(STATUS "Build test: ${LIBCARLA_BUILD_TEST}") set(libcarla_source_path "${PROJECT_SOURCE_DIR}/../source") +set(libcarla_source_thirdparty_path "${libcarla_source_path}/third-party") include_directories(${libcarla_source_path}) +include_directories(${libcarla_source_thirdparty_path}) if (CARLA_VERSION) configure_file(${libcarla_source_path}/carla/Version.h.in ${libcarla_source_path}/carla/Version.h) diff --git a/LibCarla/cmake/client/CMakeLists.txt b/LibCarla/cmake/client/CMakeLists.txt index 39748c18a..5607be22b 100644 --- a/LibCarla/cmake/client/CMakeLists.txt +++ b/LibCarla/cmake/client/CMakeLists.txt @@ -72,12 +72,11 @@ file(GLOB libcarla_carla_opendrive_parser_sources set(libcarla_sources "${libcarla_sources};${libcarla_carla_opendrive_parser_sources}") install(FILES ${libcarla_carla_opendrive_parser_sources} DESTINATION include/carla/opendrive/parser) -file(GLOB libcarla_carla_opendrive_parser_pugixml_sources - "${libcarla_source_path}/carla/opendrive/parser/pugixml/*.cpp" - "${libcarla_source_path}/carla/opendrive/parser/pugixml/*.hpp" - "${libcarla_source_path}/carla/opendrive/parser/pugixml/*.h") -set(libcarla_sources "${libcarla_sources};${libcarla_carla_opendrive_parser_pugixml_sources}") -install(FILES ${libcarla_carla_opendrive_parser_pugixml_sources} DESTINATION include/carla/opendrive/parser/pugixml) +file(GLOB libcarla_pugixml_sources + "${libcarla_source_thirdparty_path}/pugixml/*.cpp" + "${libcarla_source_thirdparty_path}/pugixml/*.hpp" + "${libcarla_source_thirdparty_path}/pugixml/*.h") +set(libcarla_sources "${libcarla_sources};${libcarla_pugixml_sources}") file(GLOB libcarla_carla_pointcloud_sources "${libcarla_source_path}/carla/pointcloud/*.cpp" @@ -101,11 +100,10 @@ file(GLOB libcarla_carla_road_element_sources set(libcarla_sources "${libcarla_sources};${libcarla_carla_road_element_sources}") install(FILES ${libcarla_carla_road_element_sources} DESTINATION include/carla/road/element) -file(GLOB libcarla_carla_road_element_cephes_sources - "${libcarla_source_path}/carla/road/element/cephes/*.cpp" - "${libcarla_source_path}/carla/road/element/cephes/*.h") -set(libcarla_sources "${libcarla_sources};${libcarla_carla_road_element_cephes_sources}") -install(FILES ${libcarla_carla_road_element_cephes_sources} DESTINATION include/carla/road/element/cephes) +file(GLOB libcarla_carla_cephes_sources + "${libcarla_source_thirdparty_path}/cephes/*.cpp" + "${libcarla_source_thirdparty_path}/cephes/*.h") +set(libcarla_sources "${libcarla_sources};${libcarla_carla_cephes_sources}") file(GLOB libcarla_carla_road_general_sources "${libcarla_source_path}/carla/road/general/*.cpp" @@ -174,7 +172,7 @@ set(libcarla_sources "${libcarla_sources};${libcarla_carla_streaming_low_level_s install(FILES ${libcarla_carla_streaming_low_level_sources} DESTINATION include/carla/streaming/low_level) file(GLOB libcarla_moodycamel_sources - "${libcarla_source_path}/moodycamel/*.h") + "${libcarla_source_thirdparty_path}/moodycamel/*.h") set(libcarla_sources "${libcarla_sources};${libcarla_moodycamel_sources}") install(FILES ${libcarla_moodycamel_sources} DESTINATION include/moodycamel) diff --git a/LibCarla/cmake/server/CMakeLists.txt b/LibCarla/cmake/server/CMakeLists.txt index 3f2cd5e80..ce44119aa 100644 --- a/LibCarla/cmake/server/CMakeLists.txt +++ b/LibCarla/cmake/server/CMakeLists.txt @@ -26,9 +26,6 @@ install(FILES ${libcarla_carla_opendrive} DESTINATION include/carla/opendrive) file(GLOB libcarla_carla_opendrive_parser "${libcarla_source_path}/carla/opendrive/parser/*.h") install(FILES ${libcarla_carla_opendrive_parser} DESTINATION include/carla/opendrive/parser) -file(GLOB libcarla_carla_opendrive_parser_pugixml "${libcarla_source_path}/carla/opendrive/parser/pugixml/*.hpp") -install(FILES ${libcarla_carla_opendrive_parser_pugixml} DESTINATION include/carla/opendrive/parser/pugixml) - file(GLOB libcarla_carla_profiler_headers "${libcarla_source_path}/carla/profiler/*.h") install(FILES ${libcarla_carla_profiler_headers} DESTINATION include/carla/profiler) @@ -38,9 +35,6 @@ install(FILES ${libcarla_carla_road_headers} DESTINATION include/carla/road) file(GLOB libcarla_carla_road_element_headers "${libcarla_source_path}/carla/road/element/*.h") install(FILES ${libcarla_carla_road_element_headers} DESTINATION include/carla/road/element) -file(GLOB libcarla_carla_road_element_cephes_headers "${libcarla_source_path}/carla/road/element/cephes/*.h") -install(FILES ${libcarla_carla_road_element_cephes_headers} DESTINATION include/carla/road/element/cephes) - file(GLOB libcarla_carla_road_general_headers "${libcarla_source_path}/carla/road/general/*.h") install(FILES ${libcarla_carla_road_general_headers} DESTINATION include/carla/road/general) @@ -96,14 +90,10 @@ file(GLOB libcarla_server_sources "${libcarla_source_path}/carla/opendrive/*.h" "${libcarla_source_path}/carla/opendrive/parser/*.cpp" "${libcarla_source_path}/carla/opendrive/parser/*.h" - "${libcarla_source_path}/carla/opendrive/parser/pugixml/*.cpp" - "${libcarla_source_path}/carla/opendrive/parser/pugixml/*.hpp" "${libcarla_source_path}/carla/road/*.cpp" "${libcarla_source_path}/carla/road/*.h" "${libcarla_source_path}/carla/road/element/*.cpp" "${libcarla_source_path}/carla/road/element/*.h" - "${libcarla_source_path}/carla/road/element/cephes/*.cpp" - "${libcarla_source_path}/carla/road/element/cephes/*.h" "${libcarla_source_path}/carla/road/general/*.cpp" "${libcarla_source_path}/carla/road/general/*.h" "${libcarla_source_path}/carla/road/object/*.cpp" @@ -120,7 +110,13 @@ file(GLOB libcarla_server_sources "${libcarla_source_path}/carla/streaming/detail/*.h" "${libcarla_source_path}/carla/streaming/detail/tcp/*.cpp" "${libcarla_source_path}/carla/streaming/detail/tcp/*.h" - "${libcarla_source_path}/carla/streaming/low_level/*.h") + "${libcarla_source_path}/carla/streaming/low_level/*.h" + "${libcarla_source_thirdparty_path}/cephes/*.cpp" + "${libcarla_source_thirdparty_path}/cephes/*.h" + "${libcarla_source_thirdparty_path}/moodycamel/*.cpp" + "${libcarla_source_thirdparty_path}/moodycamel/*.h" + "${libcarla_source_thirdparty_path}/pugixml/*.cpp" + "${libcarla_source_thirdparty_path}/pugixml/*.hpp") # ============================================================================== # Create targets for debug and release in the same build type. diff --git a/LibCarla/source/carla/opendrive/OpenDriveParser.cpp b/LibCarla/source/carla/opendrive/OpenDriveParser.cpp index 5a8183630..c2c43f1b4 100644 --- a/LibCarla/source/carla/opendrive/OpenDriveParser.cpp +++ b/LibCarla/source/carla/opendrive/OpenDriveParser.cpp @@ -16,9 +16,10 @@ #include "carla/opendrive/parser/RoadParser.h" #include "carla/opendrive/parser/SignalParser.h" #include "carla/opendrive/parser/TrafficGroupParser.h" -#include "carla/opendrive/parser/pugixml/pugixml.hpp" #include "carla/road/MapBuilder.h" +#include + namespace carla { namespace opendrive { diff --git a/LibCarla/source/carla/opendrive/parser/GeoReferenceParser.cpp b/LibCarla/source/carla/opendrive/parser/GeoReferenceParser.cpp index 12ff6374d..cc5d2c947 100644 --- a/LibCarla/source/carla/opendrive/parser/GeoReferenceParser.cpp +++ b/LibCarla/source/carla/opendrive/parser/GeoReferenceParser.cpp @@ -9,9 +9,10 @@ #include "carla/Logging.h" #include "carla/StringUtil.h" #include "carla/geom/GeoLocation.h" -#include "carla/opendrive/parser/pugixml/pugixml.hpp" #include "carla/road/MapBuilder.h" +#include + #include #include #include diff --git a/LibCarla/source/carla/opendrive/parser/GeometryParser.cpp b/LibCarla/source/carla/opendrive/parser/GeometryParser.cpp index 17d183e01..ac7c84a4b 100644 --- a/LibCarla/source/carla/opendrive/parser/GeometryParser.cpp +++ b/LibCarla/source/carla/opendrive/parser/GeometryParser.cpp @@ -6,10 +6,10 @@ #include "carla/opendrive/parser/GeometryParser.h" -#include "carla/opendrive/parser/pugixml/pugixml.hpp" - #include "carla/road/MapBuilder.h" +#include + namespace carla { namespace opendrive { namespace parser { diff --git a/LibCarla/source/carla/opendrive/parser/JunctionParser.cpp b/LibCarla/source/carla/opendrive/parser/JunctionParser.cpp index 54972d76e..3ebfb7853 100644 --- a/LibCarla/source/carla/opendrive/parser/JunctionParser.cpp +++ b/LibCarla/source/carla/opendrive/parser/JunctionParser.cpp @@ -6,10 +6,10 @@ #include "carla/opendrive/parser/JunctionParser.h" -#include "carla/opendrive/parser/pugixml/pugixml.hpp" - #include "carla/road/MapBuilder.h" +#include + namespace carla { namespace opendrive { namespace parser { diff --git a/LibCarla/source/carla/opendrive/parser/LaneParser.cpp b/LibCarla/source/carla/opendrive/parser/LaneParser.cpp index 8cf6b7966..326f0d25a 100644 --- a/LibCarla/source/carla/opendrive/parser/LaneParser.cpp +++ b/LibCarla/source/carla/opendrive/parser/LaneParser.cpp @@ -6,10 +6,10 @@ #include "carla/opendrive/parser/LaneParser.h" -#include "carla/opendrive/parser/pugixml/pugixml.hpp" - #include "carla/road/MapBuilder.h" +#include + namespace carla { namespace opendrive { namespace parser { diff --git a/LibCarla/source/carla/opendrive/parser/ObjectParser.cpp b/LibCarla/source/carla/opendrive/parser/ObjectParser.cpp index cba5c91a6..60d256dd8 100644 --- a/LibCarla/source/carla/opendrive/parser/ObjectParser.cpp +++ b/LibCarla/source/carla/opendrive/parser/ObjectParser.cpp @@ -6,10 +6,10 @@ #include "carla/opendrive/parser/ObjectParser.h" -#include "carla/opendrive/parser/pugixml/pugixml.hpp" - #include "carla/road/MapBuilder.h" +#include + namespace carla { namespace opendrive { namespace parser { diff --git a/LibCarla/source/carla/opendrive/parser/ProfilesParser.cpp b/LibCarla/source/carla/opendrive/parser/ProfilesParser.cpp index 7d8b31ec6..e539b1d85 100644 --- a/LibCarla/source/carla/opendrive/parser/ProfilesParser.cpp +++ b/LibCarla/source/carla/opendrive/parser/ProfilesParser.cpp @@ -6,10 +6,10 @@ #include "carla/opendrive/parser/ProfilesParser.h" -#include "carla/opendrive/parser/pugixml/pugixml.hpp" - #include "carla/road/MapBuilder.h" +#include + namespace carla { namespace opendrive { namespace parser { diff --git a/LibCarla/source/carla/opendrive/parser/RoadParser.cpp b/LibCarla/source/carla/opendrive/parser/RoadParser.cpp index 6a00cb765..7778fbfe7 100644 --- a/LibCarla/source/carla/opendrive/parser/RoadParser.cpp +++ b/LibCarla/source/carla/opendrive/parser/RoadParser.cpp @@ -8,10 +8,11 @@ #include "carla/Logging.h" #include "carla/StringUtil.h" -#include "carla/opendrive/parser/pugixml/pugixml.hpp" #include "carla/road/MapBuilder.h" #include "carla/road/RoadTypes.h" +#include + namespace carla { namespace opendrive { namespace parser { diff --git a/LibCarla/source/carla/opendrive/parser/SignalParser.cpp b/LibCarla/source/carla/opendrive/parser/SignalParser.cpp index c605683ab..af59967c9 100644 --- a/LibCarla/source/carla/opendrive/parser/SignalParser.cpp +++ b/LibCarla/source/carla/opendrive/parser/SignalParser.cpp @@ -6,10 +6,10 @@ #include "carla/opendrive/parser/SignalParser.h" -#include "carla/opendrive/parser/pugixml/pugixml.hpp" - #include "carla/road/MapBuilder.h" +#include + namespace carla { namespace opendrive { namespace parser { diff --git a/LibCarla/source/carla/opendrive/parser/TrafficGroupParser.cpp b/LibCarla/source/carla/opendrive/parser/TrafficGroupParser.cpp index 91b3fafc3..77757460d 100644 --- a/LibCarla/source/carla/opendrive/parser/TrafficGroupParser.cpp +++ b/LibCarla/source/carla/opendrive/parser/TrafficGroupParser.cpp @@ -6,10 +6,10 @@ #include "carla/opendrive/parser/TrafficGroupParser.h" -#include "carla/opendrive/parser/pugixml/pugixml.hpp" - #include "carla/road/MapBuilder.h" +#include + namespace carla { namespace opendrive { namespace parser { diff --git a/LibCarla/source/carla/road/element/Geometry.cpp b/LibCarla/source/carla/road/element/Geometry.cpp new file mode 100644 index 000000000..a0e09ff55 --- /dev/null +++ b/LibCarla/source/carla/road/element/Geometry.cpp @@ -0,0 +1,85 @@ +// Copyright (c) 2019 Computer Vision Center (CVC) at the Universitat Autonoma +// de Barcelona (UAB). +// +// This work is licensed under the terms of the MIT license. +// For a copy, see . + +#include "carla/road/element/Geometry.h" + +#include "carla/Debug.h" +#include "carla/Exception.h" +#include "carla/geom/Location.h" +#include "carla/geom/Math.h" + +#include + +#include +#include + +namespace carla { +namespace road { +namespace element { + + void DirectedPoint::ApplyLateralOffset(float lateral_offset) { + /// @todo Z axis?? + auto normal_x = std::sin(static_cast(tangent)); + auto normal_y = -std::cos(static_cast(tangent)); + location.x += lateral_offset * normal_x; + location.y += lateral_offset * normal_y; + } + + DirectedPoint GeometryLine::PosFromDist(double dist) const { + DEBUG_ASSERT(_length > 0.0); + dist = geom::Math::Clamp(dist, 0.0, _length); + DirectedPoint p(_start_position, _heading); + p.location.x += static_cast(dist * std::cos(p.tangent)); + p.location.y += static_cast(dist * std::sin(p.tangent)); + return p; + } + + DirectedPoint GeometryArc::PosFromDist(double dist) const { + dist = geom::Math::Clamp(dist, 0.0, _length); + DEBUG_ASSERT(_length > 0.0); + DEBUG_ASSERT(std::fabs(_curvature) > 1e-15); + const double radius = 1.0 / _curvature; + constexpr double pi_half = geom::Math::Pi() / 2.0; + DirectedPoint p(_start_position, _heading); + p.location.x += static_cast(radius * std::cos(p.tangent + pi_half)); + p.location.y += static_cast(radius * std::sin(p.tangent + pi_half)); + p.tangent += dist * _curvature; + p.location.x -= static_cast(radius * std::cos(p.tangent + pi_half)); + p.location.y -= static_cast(radius * std::sin(p.tangent + pi_half)); + return p; + } + + DirectedPoint GeometrySpiral::PosFromDist(double dist) const { + // not working yet with negative values + dist = geom::Math::Clamp(dist, 0.0, _length); + DEBUG_ASSERT(_length > 0.0); + DEBUG_ASSERT(std::fabs(_curve_end) > 1e-15); + const double radius = 1.0 / _curve_end; + const double extra_norm = 1.0 / std::sqrt(geom::Math::Pi() / 2.0); + const double norm = 1.0 / std::sqrt(2.0 * radius * _length); + const double length = dist * norm; + double S, C; + fresnl(length * extra_norm, &S, &C); + S /= (norm * extra_norm); + C /= (norm * extra_norm); + DirectedPoint p(_start_position, _heading); + const double cos_a = std::cos(p.tangent); + const double sin_a = std::sin(p.tangent); + p.location.x += static_cast(C * cos_a - S * sin_a); + p.location.y += static_cast(S * cos_a + C * sin_a); + p.tangent += length * length; + + return p; + } + + /// @todo + std::pair GeometrySpiral::DistanceTo(const geom::Location &) const { + throw_exception(std::runtime_error("not implemented")); + } + +} // namespace element +} // namespace road +} // namespace carla diff --git a/LibCarla/source/carla/road/element/Geometry.h b/LibCarla/source/carla/road/element/Geometry.h index 5d0070550..eb9c5d060 100644 --- a/LibCarla/source/carla/road/element/Geometry.h +++ b/LibCarla/source/carla/road/element/Geometry.h @@ -6,14 +6,8 @@ #pragma once -#include "carla/Debug.h" -#include "carla/Exception.h" #include "carla/geom/Location.h" #include "carla/geom/Math.h" -#include "carla/road/element/cephes/fresnel.h" - -#include -#include namespace carla { namespace road { @@ -41,13 +35,7 @@ namespace element { double tangent = 0.0; // [radians] double pitch = 0.0; // [radians] - void ApplyLateralOffset(float lateral_offset) { - /// @todo Z axis?? - auto normal_x = std::sin(static_cast(tangent)); - auto normal_y = -std::cos(static_cast(tangent)); - location.x += lateral_offset * normal_x; - location.y += lateral_offset * normal_y; - } + void ApplyLateralOffset(float lateral_offset); friend bool operator==(const DirectedPoint &lhs, const DirectedPoint &rhs) { return (lhs.location == rhs.location) && (lhs.tangent == rhs.tangent); @@ -116,14 +104,7 @@ namespace element { const geom::Location &start_pos) : Geometry(GeometryType::LINE, start_offset, length, heading, start_pos) {} - DirectedPoint PosFromDist(double dist) const override { - DEBUG_ASSERT(_length > 0.0); - dist = geom::Math::Clamp(dist, 0.0, _length); - DirectedPoint p(_start_position, _heading); - p.location.x += static_cast(dist * std::cos(p.tangent)); - p.location.y += static_cast(dist * std::sin(p.tangent)); - return p; - } + DirectedPoint PosFromDist(double dist) const override; /// Returns a pair containing: /// - @b first: distance to the nearest point in this line from the @@ -152,20 +133,7 @@ namespace element { : Geometry(GeometryType::ARC, start_offset, length, heading, start_pos), _curvature(curv) {} - DirectedPoint PosFromDist(double dist) const override { - dist = geom::Math::Clamp(dist, 0.0, _length); - DEBUG_ASSERT(_length > 0.0); - DEBUG_ASSERT(std::fabs(_curvature) > 1e-15); - const double radius = 1.0 / _curvature; - constexpr double pi_half = geom::Math::Pi() / 2.0; - DirectedPoint p(_start_position, _heading); - p.location.x += static_cast(radius * std::cos(p.tangent + pi_half)); - p.location.y += static_cast(radius * std::sin(p.tangent + pi_half)); - p.tangent += dist * _curvature; - p.location.x -= static_cast(radius * std::cos(p.tangent + pi_half)); - p.location.y -= static_cast(radius * std::sin(p.tangent + pi_half)); - return p; - } + DirectedPoint PosFromDist(double dist) const override; /// Returns a pair containing: /// - @b first: distance to the nearest point in this arc from the @@ -212,33 +180,9 @@ namespace element { return _curve_end; } - DirectedPoint PosFromDist(double dist) const override { - // not working yet with negative values - dist = geom::Math::Clamp(dist, 0.0, _length); - DEBUG_ASSERT(_length > 0.0); - DEBUG_ASSERT(std::fabs(_curve_end) > 1e-15); - const double radius = 1.0 / _curve_end; - const double extra_norm = 1.0 / std::sqrt(geom::Math::Pi() / 2.0); - const double norm = 1.0 / std::sqrt(2.0 * radius * _length); - const double length = dist * norm; - double S, C; - fresnl(length * extra_norm, &S, &C); - S /= (norm * extra_norm); - C /= (norm * extra_norm); - DirectedPoint p(_start_position, _heading); - const double cos_a = std::cos(p.tangent); - const double sin_a = std::sin(p.tangent); - p.location.x += static_cast(C * cos_a - S * sin_a); - p.location.y += static_cast(S * cos_a + C * sin_a); - p.tangent += length * length; + DirectedPoint PosFromDist(double dist) const override; - return p; - } - - /// @todo - std::pair DistanceTo(const geom::Location &) const override { - throw_exception(std::runtime_error("not implemented")); - } + std::pair DistanceTo(const geom::Location &) const override; private: diff --git a/LibCarla/source/test/client/test_opendrive.cpp b/LibCarla/source/test/client/test_opendrive.cpp index 94d1a616a..efdd037aa 100644 --- a/LibCarla/source/test/client/test_opendrive.cpp +++ b/LibCarla/source/test/client/test_opendrive.cpp @@ -13,13 +13,14 @@ #include #include #include -#include #include #include #include #include #include +#include + #include #include diff --git a/LibCarla/source/carla/road/element/cephes/const.h b/LibCarla/source/third-party/cephes/const.h similarity index 100% rename from LibCarla/source/carla/road/element/cephes/const.h rename to LibCarla/source/third-party/cephes/const.h diff --git a/LibCarla/source/carla/road/element/cephes/fresnel.h b/LibCarla/source/third-party/cephes/fresnel.h similarity index 100% rename from LibCarla/source/carla/road/element/cephes/fresnel.h rename to LibCarla/source/third-party/cephes/fresnel.h diff --git a/LibCarla/source/carla/road/element/cephes/fresnl.cpp b/LibCarla/source/third-party/cephes/fresnl.cpp similarity index 100% rename from LibCarla/source/carla/road/element/cephes/fresnl.cpp rename to LibCarla/source/third-party/cephes/fresnl.cpp diff --git a/LibCarla/source/carla/road/element/cephes/polevl.cpp b/LibCarla/source/third-party/cephes/polevl.cpp similarity index 100% rename from LibCarla/source/carla/road/element/cephes/polevl.cpp rename to LibCarla/source/third-party/cephes/polevl.cpp diff --git a/LibCarla/source/carla/road/element/cephes/polevl.h b/LibCarla/source/third-party/cephes/polevl.h similarity index 100% rename from LibCarla/source/carla/road/element/cephes/polevl.h rename to LibCarla/source/third-party/cephes/polevl.h diff --git a/LibCarla/source/moodycamel/ConcurrentQueue.h b/LibCarla/source/third-party/moodycamel/ConcurrentQueue.h similarity index 100% rename from LibCarla/source/moodycamel/ConcurrentQueue.h rename to LibCarla/source/third-party/moodycamel/ConcurrentQueue.h diff --git a/LibCarla/source/carla/opendrive/parser/pugixml/LICENSE.md b/LibCarla/source/third-party/pugixml/LICENSE.md similarity index 100% rename from LibCarla/source/carla/opendrive/parser/pugixml/LICENSE.md rename to LibCarla/source/third-party/pugixml/LICENSE.md diff --git a/LibCarla/source/carla/opendrive/parser/pugixml/pugiconfig.hpp b/LibCarla/source/third-party/pugixml/pugiconfig.hpp similarity index 100% rename from LibCarla/source/carla/opendrive/parser/pugixml/pugiconfig.hpp rename to LibCarla/source/third-party/pugixml/pugiconfig.hpp diff --git a/LibCarla/source/carla/opendrive/parser/pugixml/pugixml.cpp b/LibCarla/source/third-party/pugixml/pugixml.cpp similarity index 100% rename from LibCarla/source/carla/opendrive/parser/pugixml/pugixml.cpp rename to LibCarla/source/third-party/pugixml/pugixml.cpp diff --git a/LibCarla/source/carla/opendrive/parser/pugixml/pugixml.hpp b/LibCarla/source/third-party/pugixml/pugixml.hpp similarity index 100% rename from LibCarla/source/carla/opendrive/parser/pugixml/pugixml.hpp rename to LibCarla/source/third-party/pugixml/pugixml.hpp