Added line and arc geometry to temporal road info

This commit is contained in:
Manish 2019-03-18 18:32:18 +01:00 committed by nsubiron
parent e88dc61779
commit 516e4cb16a
3 changed files with 98 additions and 10 deletions

View File

@ -116,16 +116,17 @@ namespace parser {
// map_builder calls
for (auto const geo : geometry) {
carla::road::Road* road = map_builder.GetRoad(geo.road_id);
if (geo.type == "line")
map_builder.AddRoadGeometryLine(geo.road_id, geo.s, geo.x, geo.y, geo.hdg, geo.length);
map_builder.AddRoadGeometryLine(road, geo.s, geo.x, geo.y, geo.hdg, geo.length);
else if (geo.type == "arc")
map_builder.AddRoadGeometryArc(geo.road_id, geo.s, geo.x, geo.y, geo.hdg, geo.length, geo.arc.curvature);
map_builder.AddRoadGeometryArc(road, geo.s, geo.x, geo.y, geo.hdg, geo.length, geo.arc.curvature);
else if (geo.type == "spiral")
map_builder.AddRoadGeometrySpiral(geo.road_id, geo.s, geo.x, geo.y, geo.hdg, geo.length, geo.spiral.curvStart, geo.spiral.curvEnd);
map_builder.AddRoadGeometrySpiral(road, geo.s, geo.x, geo.y, geo.hdg, geo.length, geo.spiral.curvStart, geo.spiral.curvEnd);
else if (geo.type == "poly3")
map_builder.AddRoadGeometryPoly3(geo.road_id, geo.s, geo.x, geo.y, geo.hdg, geo.length, geo.poly3.a, geo.poly3.b, geo.poly3.c, geo.poly3.d);
map_builder.AddRoadGeometryPoly3(road, geo.s, geo.x, geo.y, geo.hdg, geo.length, geo.poly3.a, geo.poly3.b, geo.poly3.c, geo.poly3.d);
else if (geo.type == "paramPoly3")
map_builder.AddRoadGeometryParamPoly3(geo.road_id, geo.s, geo.x, geo.y, geo.hdg, geo.length, geo.param_poly3.aU, geo.param_poly3.bU, geo.param_poly3.cU, geo.param_poly3.dU, geo.param_poly3.aV, geo.param_poly3.bV, geo.param_poly3.cV, geo.param_poly3.dV, geo.param_poly3.p_range);
map_builder.AddRoadGeometryParamPoly3(road, geo.s, geo.x, geo.y, geo.hdg, geo.length, geo.param_poly3.aU, geo.param_poly3.bU, geo.param_poly3.cU, geo.param_poly3.dU, geo.param_poly3.aV, geo.param_poly3.bV, geo.param_poly3.cV, geo.param_poly3.dV, geo.param_poly3.p_range);
}
}

View File

@ -7,6 +7,7 @@
#include "carla/StringUtil.h"
#include "carla/road/MapBuilder.h"
#include "carla/road/element/RoadElevationInfo.h"
#include "carla/road/element/RoadInfoGeometry.h"
#include "carla/road/element/RoadInfoLaneAccess.h"
#include "carla/road/element/RoadInfoLaneBorder.h"
#include "carla/road/element/RoadInfoLaneHeight.h"
@ -301,6 +302,81 @@ namespace road {
lane->_prev_lanes.emplace_back(reinterpret_cast<Lane *>(predecessor));
}
void MapBuilder::AddRoadGeometryLine(
carla::road::Road *road,
const double s,
const double x,
const double y,
const double hdg,
const double length) {
auto line_geometry = std::make_unique<GeometryLine>(s,
length,
hdg,
geom::Location(x, y, 0.0f));
_road_info[road].emplace_back(std::unique_ptr<RoadInfo>(new RoadInfoGeometry(s,
std::move(line_geometry))));
}
void MapBuilder::AddRoadGeometryArc(
carla::road::Road *road,
const double s,
const double x,
const double y,
const double hdg,
const double length,
const double curvature) {
auto arc_geometry = std::make_unique<GeometryArc>(s,
length,
hdg,
geom::Location(x, y, 0.0f),
curvature);
_road_info[road].emplace_back(std::unique_ptr<RoadInfo>(new RoadInfoGeometry(s,
std::move(arc_geometry))));
}
void MapBuilder::AddRoadGeometrySpiral(
carla::road::Road * /*road*/,
const double /*s*/,
const double /*x*/,
const double /*y*/,
const double /*hdg*/,
const double /*length*/,
const double /*curvStart*/,
const double /*curvEnd*/) {}
void MapBuilder::AddRoadGeometryPoly3(
carla::road::Road * /*road*/,
const double /*s*/,
const double /*x*/,
const double /*y*/,
const double /*hdg*/,
const double /*length*/,
const double /*a*/,
const double /*b*/,
const double /*c*/,
const double /*d*/) {}
void MapBuilder::AddRoadGeometryParamPoly3(
carla::road::Road * /*road*/,
const double /*s*/,
const double /*x*/,
const double /*y*/,
const double /*hdg*/,
const double /*length*/,
const double /*aU*/,
const double /*bU*/,
const double /*cU*/,
const double /*dU*/,
const double /*aV*/,
const double /*bV*/,
const double /*cV*/,
const double /*dV*/,
const std::string /*p_range*/) {}
void MapBuilder::AddJunction(const int32_t id, const std::string name) {
_map_data.GetJunctions().emplace(id, Junction(id, name));
}
@ -370,5 +446,9 @@ namespace road {
return _map_data.GetLane(road_id, lane_id, s);
}
Road *MapBuilder::GetRoad(
const RoadId road_id) {
return _map_data.GetRoad(road_id);
}
} // namespace road
} // namespace carla

View File

@ -51,7 +51,7 @@ namespace road {
// called from geometry parser
void AddRoadGeometryLine(
const int32_t road_id,
carla::road::Road *road,
const double s,
const double x,
const double y,
@ -59,7 +59,7 @@ namespace road {
const double length);
void AddRoadGeometryArc(
const int32_t road_id,
carla::road::Road *road,
const double s,
const double x,
const double y,
@ -68,7 +68,7 @@ namespace road {
const double curvature);
void AddRoadGeometrySpiral(
const int32_t road_id,
carla::road::Road *road,
const double s,
const double x,
const double y,
@ -78,7 +78,7 @@ namespace road {
const double curvEnd);
void AddRoadGeometryPoly3(
const int32_t road_id,
carla::road::Road *road,
const double s,
const double x,
const double y,
@ -90,7 +90,7 @@ namespace road {
const double d);
void AddRoadGeometryParamPoly3(
const int32_t road_id,
carla::road::Road *road,
const double s,
const double x,
const double y,
@ -313,6 +313,10 @@ namespace road {
const uint32_t dependency_id,
const std::string dependency_type);
Road *GetRoad(
const RoadId road_id
);
Lane *GetLane(
const RoadId road_id,
const LaneId lane_id,
@ -333,6 +337,9 @@ namespace road {
/// can be added all together
std::unordered_map<const Lane *, std::vector<std::unique_ptr<element::RoadInfo>>>
_temp_lane_info_container;
std::unordered_map<carla::road::Road *, std::vector<std::unique_ptr<carla::road::element::RoadInfo>>> _road_info;
};
} // namespace road