diff --git a/LibCarla/cmake/server/CMakeLists.txt b/LibCarla/cmake/server/CMakeLists.txt index 098a4de82..5ce0acffe 100644 --- a/LibCarla/cmake/server/CMakeLists.txt +++ b/LibCarla/cmake/server/CMakeLists.txt @@ -104,6 +104,12 @@ file(GLOB libcarla_server_sources "${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" + "${libcarla_source_path}/carla/road/object/*.h" + "${libcarla_source_path}/carla/road/signal/*.cpp" + "${libcarla_source_path}/carla/road/signal/*.h" "${libcarla_source_path}/carla/rpc/*.cpp" "${libcarla_source_path}/carla/rpc/*.h" "${libcarla_source_path}/carla/sensor/*.h" diff --git a/LibCarla/source/carla/road/MapBuilder.cpp b/LibCarla/source/carla/road/MapBuilder.cpp index f5d964a08..c1e3770fa 100644 --- a/LibCarla/source/carla/road/MapBuilder.cpp +++ b/LibCarla/source/carla/road/MapBuilder.cpp @@ -20,6 +20,10 @@ #include "carla/road/element/RoadInfoMarkTypeLine.h" #include "carla/road/element/RoadInfoSpeed.h" #include "carla/road/element/RoadInfoVisitor.h" +#include "carla/road/general/Validity.h" +#include "carla/road/signal/Signal.h" +#include "carla/road/signal/SignalReference.h" +#include "carla/road/signal/SignalDependency.h" #include #include @@ -245,12 +249,11 @@ namespace road { } void MapBuilder::AddValidityToLastAddedSignal( - uint32_t road_id, - uint32_t signal_id, - int32_t from_lane, - int32_t to_lane) { - _map_data.GetRoad(road_id)->GetSignal(signal_id)->AddValidity(general::Validity(signal_id, from_lane, - to_lane)); + const uint32_t road_id, + const uint32_t signal_id, + const int32_t from_lane, + const int32_t to_lane) { + _map_data.GetRoad(road_id)->GetSignal(signal_id)->AddValidity(general::Validity(signal_id, from_lane, to_lane)); } // build road objects @@ -413,10 +416,10 @@ namespace road { } void MapBuilder::AddValidityToSignal( - uint32_t road_id, - uint32_t signal_id, - int32_t from_lane, - int32_t to_lane) { + const uint32_t road_id, + const uint32_t signal_id, + const int32_t from_lane, + const int32_t to_lane) { _map_data.GetRoad(road_id)->GetSignal(signal_id)->AddValidity(general::Validity(signal_id, from_lane, to_lane)); } diff --git a/LibCarla/source/carla/road/MapBuilder.h b/LibCarla/source/carla/road/MapBuilder.h index 405b59396..dbb74223c 100644 --- a/LibCarla/source/carla/road/MapBuilder.h +++ b/LibCarla/source/carla/road/MapBuilder.h @@ -156,10 +156,10 @@ namespace road { const float roll); void AddValidityToLastAddedSignal( - uint32_t road_id, - uint32_t signal_id, - int32_t from_lane, - int32_t to_lane); + const uint32_t road_id, + const uint32_t signal_id, + const int32_t from_lane, + const int32_t to_lane); // called from junction parser void AddJunction(const int32_t id, const std::string name); diff --git a/LibCarla/source/carla/road/signal/Signal.cpp b/LibCarla/source/carla/road/signal/Signal.cpp index f8903a277..ccacaf404 100644 --- a/LibCarla/source/carla/road/signal/Signal.cpp +++ b/LibCarla/source/carla/road/signal/Signal.cpp @@ -6,10 +6,18 @@ #include "Signal.h" -void carla::road::signal::Signal::AddValidity(carla::road::general::Validity &&validity) { +namespace carla { +namespace road { +namespace signal { + +void Signal::AddValidity(general::Validity &&validity) { _validities.push_back(std::move(validity)); } -void carla::road::signal::Signal::AddDependency(carla::road::signal::SignalDependency &&dependency) { +void Signal::AddDependency(SignalDependency &&dependency) { _dependencies.push_back(std::move(dependency)); +} + +} +} } \ No newline at end of file diff --git a/LibCarla/source/test/common/test_road.cpp b/LibCarla/source/test/common/test_road.cpp index 2039cf20d..49ed52042 100644 --- a/LibCarla/source/test/common/test_road.cpp +++ b/LibCarla/source/test/common/test_road.cpp @@ -10,11 +10,31 @@ #include #include #include +#include +#include +#include using namespace carla::road; using namespace carla::road::element; using namespace carla::geom; +using namespace carla::opendrive; +TEST(road, parse_file) { + + // read + std::ostringstream content; + std::ifstream file; + file.open("opentest.xodr", std::ios::in); + content << file.rdbuf(); + file.close(); + + auto map = OpenDriveParser::Load(content.str()); + + + ASSERT_TRUE(map.has_value()); + +} +/* TEST(road, add_geometry) { } @@ -42,3 +62,4 @@ TEST(road, geom_spiral) { TEST(road, get_information) { } +*/ \ No newline at end of file