Review fixes. Added default lane validity if missing record in OpenDRIVE. Added Automatic spawn of traffic lights and signals to the map generation without geometry.

This commit is contained in:
Axel1092 2020-03-26 13:12:17 +01:00 committed by Axel1092
parent 12a5f6f5d0
commit 1b108a027c
9 changed files with 131 additions and 14 deletions

View File

@ -776,8 +776,8 @@ namespace road {
std::unordered_map<road::RoadId, std::unordered_set<road::RoadId>>
Map::ComputeJunctionConflicts(JuncId id) const {
const float epsilon = 0.0001f; // small delta in the road (set to 1
// milimeter to prevent numeric errors)
const float epsilon = 0.0001f; // small delta in the road (set to 0.1
// millimeters to prevent numeric errors)
const Junction *junction = GetJunction(id);
std::unordered_map<road::RoadId, std::unordered_set<road::RoadId>>
conflicts;
@ -911,7 +911,6 @@ namespace road {
std::vector<Rtree::TreeElement> &rtree_elements,
geom::Transform &current_transform,
Waypoint &current_waypoint,
Waypoint &next_waypoint) {
geom::Transform next_transform = ComputeTransform(next_waypoint);
AddElementToRtree(rtree_elements, current_transform, next_transform,

View File

@ -283,7 +283,7 @@ namespace road {
const std::string signal_reference_orientation) {
_temp_road_info_container[road].emplace_back(std::make_unique<element::RoadInfoSignal>(
signal_id, s_position, t_position, signal_reference_orientation));
signal_id, road->GetId(), s_position, t_position, signal_reference_orientation));
auto road_info_signal = static_cast<element::RoadInfoSignal*>(
_temp_road_info_container[road].back().get());
_temp_signal_reference_container.emplace_back(road_info_signal);
@ -761,6 +761,8 @@ namespace road {
}
_map_data._signals = std::move(_temp_signal_container);
GenerateDefaultValiditiesForSignalReferences();
}
void MapBuilder::SolveControllerAndJuntionReferences() {
@ -877,5 +879,72 @@ void MapBuilder::CreateController(
}
}
void MapBuilder::GenerateDefaultValiditiesForSignalReferences() {
for (auto * signal_reference : _temp_signal_reference_container) {
if (signal_reference->_validities.size() == 0) {
Road* road = GetRoad(signal_reference->GetRoadId());
auto lanes = road->GetLanesByDistance(signal_reference->GetS());
switch (signal_reference->GetOrientation()) {
case SignalOrientation::Positive: {
LaneId min_lane = 1;
LaneId max_lane = 0;
for (const auto* lane : lanes) {
auto lane_id = lane->GetId();
if(lane_id > max_lane) {
max_lane = lane_id;
}
}
if(min_lane <= max_lane) {
AddValidityToSignalReference(signal_reference, min_lane, max_lane);
}
break;
}
case SignalOrientation::Negative: {
LaneId min_lane = 0;
LaneId max_lane = -1;
for (const auto* lane : lanes) {
auto lane_id = lane->GetId();
if(lane_id < min_lane) {
min_lane = lane_id;
}
}
if(min_lane <= max_lane) {
AddValidityToSignalReference(signal_reference, min_lane, max_lane);
}
break;
}
case SignalOrientation::Both: {
// Get positive lanes
LaneId min_lane = 1;
LaneId max_lane = 0;
for (const auto* lane : lanes) {
auto lane_id = lane->GetId();
if(lane_id > max_lane) {
max_lane = lane_id;
}
}
if(min_lane <= max_lane) {
AddValidityToSignalReference(signal_reference, min_lane, max_lane);
}
// get negative lanes
min_lane = 0;
max_lane = -1;
for (const auto* lane : lanes) {
auto lane_id = lane->GetId();
if(lane_id < min_lane) {
min_lane = lane_id;
}
}
if(min_lane <= max_lane) {
AddValidityToSignalReference(signal_reference, min_lane, max_lane);
}
break;
}
}
}
}
}
} // namespace road
} // namespace carla

View File

@ -362,6 +362,9 @@ namespace road {
/// Compute the conflicts of the roads (intersecting roads)
void ComputeJunctionRoadConflicts(Map &map);
/// Generates a default validity field for signal references with missing validity record in OpenDRIVE
void GenerateDefaultValiditiesForSignalReferences();
/// Return the pointer to a lane object.
Lane *GetEdgeLanePointer(RoadId road_id, bool from_start, LaneId lane_id);

View File

@ -85,6 +85,28 @@ namespace road {
return const_cast<Road *>(this)->GetLaneByDistance(s, lane_id);
}
std::vector<Lane*> Road::GetLanesByDistance(double s) {
std::vector<Lane*> result;
auto lane_sections = GetLaneSectionsAt(s);
for (auto &lane_section : lane_sections) {
for (auto & lane_pair : lane_section.GetLanes()) {
result.emplace_back(&lane_pair.second);
}
}
return result;
}
std::vector<const Lane*> Road::GetLanesByDistance(double s) const {
std::vector<const Lane*> result;
const auto lane_sections = GetLaneSectionsAt(s);
for (const auto &lane_section : lane_sections) {
for (const auto & lane_pair : lane_section.GetLanes()) {
result.emplace_back(&lane_pair.second);
}
}
return result;
}
Lane &Road::GetLaneById(SectionId section_id, LaneId lane_id) {
return GetLaneSectionById(section_id).GetLanes().at(lane_id);
}

View File

@ -49,6 +49,11 @@ namespace road {
const Lane &GetLaneByDistance(double s, LaneId lane_id) const;
/// Get all lanes from all lane sections in a specific s
std::vector<Lane*> GetLanesByDistance(double s);
std::vector<const Lane*> GetLanesByDistance(double s) const;
RoadId GetSuccessor() const;
RoadId GetPredecessor() const;
@ -157,6 +162,8 @@ namespace road {
return _lane_sections.GetById(id);
}
/// Return the upper bound "s", i.e., the end distance of the lane section
/// at @a s (clamped at road's length).
double UpperBound(double s) const {

View File

@ -19,23 +19,27 @@ namespace element {
RoadInfoSignal(
SignId signal_id,
Signal* signal,
RoadId road_id,
double s,
double t,
std::string orientation)
: RoadInfo(s),
_signal_id(signal_id),
_signal(signal),
_road_id(road_id),
_s(s),
_t(t),
_orientation(orientation) {}
RoadInfoSignal(
SignId signal_id,
RoadId road_id,
double s,
double t,
std::string orientation)
: RoadInfo(s),
_signal_id(signal_id),
_road_id(road_id),
_s(s),
_t(t),
_orientation(orientation) {}
@ -52,6 +56,10 @@ namespace element {
return _signal;
}
RoadId GetRoadId() const {
return _road_id;
}
bool IsDynamic() const {
return _signal->GetDynamic();
}
@ -85,6 +93,8 @@ namespace element {
Signal* _signal;
RoadId _road_id;
double _s;
double _t;

View File

@ -6,6 +6,7 @@
#include "Carla.h"
#include "OpenDriveGenerator.h"
#include "Traffic/TrafficLightManager.h"
#include <compiler/disable-ue4-macros.h>
#include <carla/opendrive/OpenDriveParser.h>
@ -169,4 +170,7 @@ void AOpenDriveGenerator::BeginPlay()
LoadOpenDrive(XodrContent);
GenerateAll();
// Autogenerate signals
GetWorld()->SpawnActor<ATrafficLightManager>();
}

View File

@ -35,20 +35,20 @@ void USignComponent::SetSignId(const FString &Id) {
SignId = Id;
}
void USignComponent::InitializeSign(const carla::road::Map &Map)
void USignComponent::InitializeSign(const cr::Map &Map)
{
}
TArray<std::pair<carla::road::RoadId, const carla::road::element::RoadInfoSignal*>>
USignComponent::GetAllReferencesToThisSignal(const carla::road::Map &Map)
TArray<std::pair<cr::RoadId, const cre::RoadInfoSignal*>>
USignComponent::GetAllReferencesToThisSignal(const cr::Map &Map)
{
TArray<std::pair<carla::road::RoadId, const carla::road::element::RoadInfoSignal*>> Result;
TArray<std::pair<cr::RoadId, const cre::RoadInfoSignal*>> Result;
auto waypoints = Map.GenerateWaypointsOnRoadEntries();
std::unordered_set<carla::road::RoadId> ExploredRoads;
std::unordered_set<cr::RoadId> ExploredRoads;
for (auto & waypoint : waypoints)
{
// Check if we alredy explored this road
// Check if we already explored this road
if (ExploredRoads.count(waypoint.road_id) > 0)
{
continue;
@ -57,7 +57,7 @@ TArray<std::pair<carla::road::RoadId, const carla::road::element::RoadInfoSignal
// Multiple times for same road (performance impact, not in behavior)
auto SignalReferences = Map.GetLane(waypoint).
GetRoad()->GetInfos<carla::road::element::RoadInfoSignal>();
GetRoad()->GetInfos<cre::RoadInfoSignal>();
for (auto *SignalReference : SignalReferences)
{
FString SignalId(SignalReference->GetSignalId().c_str());

View File

@ -25,6 +25,9 @@ namespace element
}
}
namespace cr = carla::road;
namespace cre = carla::road::element;
/// Class representing an OpenDRIVE Signal
UCLASS( ClassGroup=(Custom), meta=(BlueprintSpawnableComponent) )
class CARLA_API USignComponent : public USceneComponent
@ -41,7 +44,7 @@ public:
void SetSignId(const FString &Id);
// Initialize sign (e.g. generate trigger boxes)
virtual void InitializeSign(const carla::road::Map &Map);
virtual void InitializeSign(const cr::Map &Map);
protected:
// Called when the game starts
@ -50,8 +53,8 @@ protected:
// Called every frame
virtual void TickComponent(float DeltaTime, ELevelTick TickType, FActorComponentTickFunction* ThisTickFunction) override;
TArray<std::pair<carla::road::RoadId, const carla::road::element::RoadInfoSignal*>>
GetAllReferencesToThisSignal(const carla::road::Map &Map);
TArray<std::pair<cr::RoadId, const cre::RoadInfoSignal*>>
GetAllReferencesToThisSignal(const cr::Map &Map);
/// Generates a trigger box component in the parent actor
/// BoxSize should be in Unreal units