Splited the map generation in chunks

This commit is contained in:
Marc Garcia Puig 2020-04-08 14:25:30 +02:00 committed by bernat
parent 832b293a33
commit 00a73c4f02
11 changed files with 282 additions and 98 deletions

View File

@ -11,7 +11,6 @@
#include <ios>
#include <carla/geom/Math.h>
#include <carla/geom/Location.h>
namespace carla {
namespace geom {

View File

@ -11,6 +11,10 @@
#include <carla/geom/Vector3D.h>
#include <carla/geom/Vector2D.h>
#ifdef LIBCARLA_INCLUDED_FROM_UE4
#include "Util/ProceduralCustomMesh.h"
#endif // LIBCARLA_INCLUDED_FROM_UE4
namespace carla {
namespace geom {
@ -139,6 +143,65 @@ namespace geom {
friend Mesh operator+(const Mesh &lhs, const Mesh &rhs);
// =========================================================================
// -- Conversions to UE4 types ---------------------------------------------
// =========================================================================
#ifdef LIBCARLA_INCLUDED_FROM_UE4
operator FProceduralCustomMesh() const {
FProceduralCustomMesh Mesh;
// Build the mesh
for (const auto Vertex : GetVertices())
{
// From meters to centimeters
Mesh.Vertices.Add(FVector{1e2f * Vertex.x, 1e2f * Vertex.y, 1e2f * Vertex.z});
}
const auto Indexes = GetIndexes();
TArray<FTriIndices> TriIndices;
for (auto i = 0u; i < Indexes.size(); i += 3)
{
FTriIndices Triangle;
// "-1" since mesh indexes in Unreal starts from index 0.
Mesh.Triangles.Add(Indexes[i] - 1);
// Since Unreal's coords are left handed, invert the last 2 indices.
Mesh.Triangles.Add(Indexes[i + 2] - 1);
Mesh.Triangles.Add(Indexes[i + 1] - 1);
Triangle.v0 = Indexes[i] - 1;
Triangle.v1 = Indexes[i + 2] - 1;
Triangle.v2 = Indexes[i + 1] - 1;
TriIndices.Add(Triangle);
}
// Compute the normals
TArray<FVector> Normals;
Mesh.Normals.Init(FVector::UpVector, Mesh.Vertices.Num());
for (const auto &Triangle : TriIndices) {
FVector Normal;
const FVector U = Mesh.Vertices[Triangle.v1] - Mesh.Vertices[Triangle.v0];
const FVector V = Mesh.Vertices[Triangle.v2] - Mesh.Vertices[Triangle.v0];
Normal.X = (U.Y * V.Z) - (U.Z * V.Y);
Normal.Y = (U.Z * V.X) - (U.X * V.Z);
Normal.Z = (U.X * V.Y) - (U.Y * V.X);
Normal = -Normal;
Normal = Normal.GetSafeNormal(.0001f);
if (Normal != FVector::ZeroVector)
{
Mesh.Normals[Triangle.v0] = Normal;
Mesh.Normals[Triangle.v1] = Normal;
Mesh.Normals[Triangle.v2] = Normal;
}
}
return Mesh;
}
#endif // LIBCARLA_INCLUDED_FROM_UE4
private:
// =========================================================================

View File

@ -18,7 +18,7 @@ namespace geom {
static constexpr double EPSILON = 10.0 * std::numeric_limits<double>::epsilon();
std::unique_ptr<Mesh> MeshFactory::Generate(const road::Road &road) const {
geom::Mesh out_mesh;
Mesh out_mesh;
for (auto &&lane_section : road.GetLaneSections()) {
out_mesh += *Generate(lane_section);
}
@ -26,7 +26,7 @@ namespace geom {
}
std::unique_ptr<Mesh> MeshFactory::Generate(const road::LaneSection &lane_section) const {
geom::Mesh out_mesh;
Mesh out_mesh;
for (auto &&lane_pair : lane_section.GetLanes()) {
out_mesh += *Generate(lane_pair.second);
}
@ -34,40 +34,50 @@ namespace geom {
}
std::unique_ptr<Mesh> MeshFactory::Generate(const road::Lane &lane) const {
const double s_start = lane.GetDistance() + EPSILON;
const double s_end = lane.GetDistance() + lane.GetLength() - EPSILON;
return Generate(lane, s_start, s_end);
}
std::unique_ptr<Mesh> MeshFactory::Generate(
const road::Lane &lane, const double s_start, const double s_end) const {
RELEASE_ASSERT(road_param.resolution > 0.0);
DEBUG_ASSERT(s_start >= 0.0);
DEBUG_ASSERT(s_end <= lane.GetDistance() + lane.GetLength());
DEBUG_ASSERT(s_end >= EPSILON);
DEBUG_ASSERT(s_start < s_end);
// The lane with lane_id 0 have no physical representation in OpenDRIVE
geom::Mesh out_mesh;
Mesh out_mesh;
if (lane.GetId() == 0) {
return std::make_unique<Mesh>(out_mesh);
}
const auto end_distance = lane.GetDistance() + lane.GetLength() - EPSILON;
double current_s = lane.GetLaneSection()->GetDistance() + EPSILON;
double s_current = s_start;
std::vector<geom::Vector3D> vertices;
if (lane.IsStraight()) {
// Mesh optimization: If the lane is straight just add vertices at the
// begining and at the end of it
const auto edges = lane.GetCornerPositions(current_s, road_param.extra_lane_width);
const auto edges = lane.GetCornerPositions(s_current, road_param.extra_lane_width);
vertices.push_back(edges.first);
vertices.push_back(edges.second);
} else {
// Iterate over the lane's 's' and store the vertices based on it's width
do {
// Get the location of the edges of the current lane at the current waypoint
const auto edges = lane.GetCornerPositions(current_s, road_param.extra_lane_width);
const auto edges = lane.GetCornerPositions(s_current, road_param.extra_lane_width);
vertices.push_back(edges.first);
vertices.push_back(edges.second);
// Update the current waypoint's "s"
current_s += road_param.resolution;
} while(current_s < end_distance);
s_current += road_param.resolution;
} while(s_current < s_end);
}
// This ensures the mesh is constant and have no gaps between roads,
// adding geometry at the very end of the lane
if (end_distance - (current_s - road_param.resolution) > EPSILON) {
current_s = end_distance;
const auto edges = lane.GetCornerPositions(current_s, road_param.extra_lane_width);
if (s_end - (s_current - road_param.resolution) > EPSILON) {
const auto edges = lane.GetCornerPositions(s_end, road_param.extra_lane_width);
vertices.push_back(edges.first);
vertices.push_back(edges.second);
}
@ -80,5 +90,44 @@ namespace geom {
return std::make_unique<Mesh>(out_mesh);
}
std::vector<std::unique_ptr<Mesh>> MeshFactory::GenerateWithMaxLen(
const road::Road &road, const double max_len) const {
std::vector<std::unique_ptr<Mesh>> mesh_uptr_list;
for (auto &&lane_section : road.GetLaneSections()) {
auto section_uptr_list = GenerateWithMaxLen(lane_section, max_len);
mesh_uptr_list.insert(
mesh_uptr_list.end(),
std::make_move_iterator(section_uptr_list.begin()),
std::make_move_iterator(section_uptr_list.end()));
}
return mesh_uptr_list;
}
std::vector<std::unique_ptr<Mesh>> MeshFactory::GenerateWithMaxLen(
const road::LaneSection &lane_section, const double max_len) const {
std::vector<std::unique_ptr<Mesh>> mesh_uptr_list;
if (lane_section.GetLength() < max_len) {
mesh_uptr_list.emplace_back(Generate(lane_section));
} else {
double s_current = lane_section.GetDistance() + EPSILON;
const double s_end = lane_section.GetDistance() + lane_section.GetLength() - EPSILON;
while(s_current + max_len < s_end) {
const auto s_until = s_current + max_len;
Mesh lane_section_mesh;
for (auto &&lane_pair : lane_section.GetLanes()) {
lane_section_mesh += *Generate(lane_pair.second, s_current, s_until);
}
mesh_uptr_list.emplace_back(std::make_unique<Mesh>(lane_section_mesh));
s_current = s_until;
}
if (s_end - s_current > EPSILON) {
for (auto &&lane_pair : lane_section.GetLanes()) {
mesh_uptr_list.emplace_back(Generate(lane_pair.second, s_current, s_end));
}
}
}
return mesh_uptr_list;
}
} // namespace geom
} // namespace carla

View File

@ -7,6 +7,7 @@
#pragma once
#include <memory>
#include <vector>
#include <carla/geom/Mesh.h>
#include <carla/road/Road.h>
@ -32,9 +33,21 @@ namespace geom {
/// Generates a mesh that defines a lane section
std::unique_ptr<Mesh> Generate(const road::LaneSection &lane_section) const;
/// Generates a mesh that defines a lane
/// Generates a mesh that defines a lane from a given s start and end
std::unique_ptr<Mesh> Generate(
const road::Lane &lane, const double s_start, const double s_end) const;
/// Generates a mesh that defines the whole lane
std::unique_ptr<Mesh> Generate(const road::Lane &lane) const;
/// Generates a mesh that defines a lane
std::vector<std::unique_ptr<Mesh>> GenerateWithMaxLen(
const road::Road &road, const double max_len) const;
/// Generates a mesh that defines a lane
std::vector<std::unique_ptr<Mesh>> GenerateWithMaxLen(
const road::LaneSection &lane_section, const double max_len) const;
// =========================================================================
// -- Generation parameters ------------------------------------------------
// =========================================================================

View File

@ -5,6 +5,7 @@
// For a copy, see <https://opensource.org/licenses/MIT>.
#include "carla/road/LaneSection.h"
#include "carla/road/Road.h"
namespace carla {
namespace road {
@ -13,7 +14,13 @@ namespace road {
return _s;
}
Road *LaneSection::GetRoad() {
double LaneSection::GetLength() const {
const auto *road = GetRoad();
DEBUG_ASSERT(road != nullptr);
return road->UpperBound(_s) - _s;
}
Road *LaneSection::GetRoad() const {
return _road;
}

View File

@ -28,7 +28,9 @@ namespace road {
double GetDistance() const;
Road *GetRoad();
double GetLength() const;
Road *GetRoad() const;
Lane *GetLane(const LaneId id);

View File

@ -18,6 +18,8 @@
#include "carla/road/element/RoadInfoMarkRecord.h"
#include "carla/road/element/RoadInfoSignal.h"
#include <vector>
#include <unordered_map>
#include <stdexcept>
namespace carla {
@ -978,6 +980,53 @@ namespace road {
return out_mesh;
}
std::vector<std::unique_ptr<geom::Mesh>> Map::GenerateChunkedMesh(
const double distance, const float max_road_len, const float extra_width) const {
RELEASE_ASSERT(distance > 0.0);
RELEASE_ASSERT(extra_width >= 0.0);
RELEASE_ASSERT(max_road_len > 0.0);
geom::MeshFactory mesh_factory;
mesh_factory.road_param.resolution = static_cast<float>(distance);
mesh_factory.road_param.extra_lane_width = extra_width;
std::vector<std::unique_ptr<geom::Mesh>> out_mesh_list;
std::unordered_map<JuncId, geom::Mesh> junction_map;
for (auto &&pair : _data.GetRoads()) {
const auto &road = pair.second;
std::vector<std::unique_ptr<geom::Mesh>> road_mesh_list =
mesh_factory.GenerateWithMaxLen(road, max_road_len);
// If the road in in a junction, add the road to the junction mesh instead of
// doing it separately, this is needed for the road mesh smooth algorithm
if (road.IsJunction()) {
const auto junction_id = road.GetJunctionId();
geom::Mesh junction_mesh;
for (auto &&i : road_mesh_list) {
junction_mesh += *i;
}
// If the junction id already exists on the map
if (junction_map.count(junction_id)) {
junction_map[junction_id] += junction_mesh;
} else {
// Otherwise create it
junction_map[junction_id] = std::move(junction_mesh);
}
} else {
out_mesh_list.insert(
out_mesh_list.end(),
std::make_move_iterator(road_mesh_list.begin()),
std::make_move_iterator(road_mesh_list.end()));
}
}
// Merge the map meshes with out_mesh_list
for (auto &&pair : junction_map) {
out_mesh_list.push_back(std::make_unique<geom::Mesh>(pair.second));
}
return out_mesh_list;
}
geom::Mesh Map::GetAllCrosswalkMesh() const {
geom::Mesh out_mesh;

View File

@ -152,6 +152,9 @@ namespace road {
/// Buids a mesh based on the OpenDRIVE
geom::Mesh GenerateMesh(const double distance, const float extra_width = 0.f) const;
std::vector<std::unique_ptr<geom::Mesh>> GenerateChunkedMesh(
const double distance, const float max_road_len, const float extra_width = 0.f) const;
/// Buids a mesh of all crosswalks based on the OpenDRIVE
geom::Mesh GetAllCrosswalkMesh() const;

View File

@ -7,6 +7,7 @@
#include "Carla.h"
#include "OpenDriveGenerator.h"
#include "Traffic/TrafficLightManager.h"
#include "Util/ProceduralCustomMesh.h"
#include <compiler/disable-ue4-macros.h>
#include <carla/opendrive/OpenDriveParser.h>
@ -15,20 +16,14 @@
#include "Engine/Classes/Interfaces/Interface_CollisionDataProvider.h"
#include "PhysicsEngine/BodySetupEnums.h"
#include "ProceduralMeshComponent.h"
AOpenDriveGenerator::AOpenDriveGenerator(const FObjectInitializer &ObjectInitializer)
: Super(ObjectInitializer)
{
PrimaryActorTick.bCanEverTick = false;
RootComponent = CreateDefaultSubobject<USceneComponent>(TEXT("SceneComponent"));
SetRootComponent(RootComponent);
RootComponent->Mobility = EComponentMobility::Static;
RoadMesh = CreateDefaultSubobject<UProceduralMeshComponent>("RoadMesh");
SetRootComponent(RoadMesh);
RoadMesh->bUseAsyncCooking = true;
RoadMesh->bUseComplexAsSimpleCollision = true;
RoadMesh->SetCollisionEnabled(ECollisionEnabled::QueryAndPhysics);
}
bool AOpenDriveGenerator::LoadOpenDrive(const FString &OpenDrive)
@ -72,9 +67,9 @@ void AOpenDriveGenerator::GenerateRoadMesh()
static const FString ConfigFilePath =
FPaths::ProjectContentDir() + "Carla/Maps/OpenDrive/OpenDriveMap.conf";
float Resolution = 2.f;
float WallHeight = 1.f;
float AdditionalWidth = .6f;
float Resolution = 2.0f;
float WallHeight = 1.0f;
float AdditionalWidth = 0.6f;
if (FPaths::FileExists(ConfigFilePath)) {
FString ConfigData;
TArray<FString> Lines;
@ -98,81 +93,50 @@ void AOpenDriveGenerator::GenerateRoadMesh()
}
}
const auto MeshData =
CarlaMap->GenerateMesh(Resolution, AdditionalWidth) +
CarlaMap->GenerateWalls(Resolution, WallHeight);
// const FProceduralCustomMesh MeshData =
// CarlaMap->GenerateMesh(Resolution, AdditionalWidth) +
// CarlaMap->GenerateWalls(Resolution, WallHeight);
// Build the mesh
TArray<FVector> Vertices;
for (const auto vertex : MeshData.GetVertices())
{
// From meters to centimeters
Vertices.Add(FVector(vertex.x, vertex.y, vertex.z) * 1e2f);
const auto Meshes = CarlaMap->GenerateChunkedMesh(Resolution, 50.0f, AdditionalWidth);
for (const auto &Mesh : Meshes) {
AActor *TempActor = GetWorld()->SpawnActor<AActor>();
UProceduralMeshComponent *TempPMC = NewObject<UProceduralMeshComponent>(TempActor);
TempPMC->RegisterComponent();
TempPMC->AttachToComponent(
TempActor->GetRootComponent(), FAttachmentTransformRules::KeepRelativeTransform);
TempPMC->bUseAsyncCooking = true;
TempPMC->bUseComplexAsSimpleCollision = true;
TempPMC->SetCollisionEnabled(ECollisionEnabled::QueryAndPhysics);
const FProceduralCustomMesh MeshData = *Mesh;
TempPMC->CreateMeshSection_LinearColor(
0,
MeshData.Vertices,
MeshData.Triangles,
MeshData.Normals,
TArray<FVector2D>(), // UV0
TArray<FLinearColor>(), // VertexColor
TArray<FProcMeshTangent>(), // Tangents
true); // Create collision
ActorMeshList.Add(TempActor);
}
const auto Indexes = MeshData.GetIndexes();
TArray<int32> Triangles;
TArray<FTriIndices> TriIndices;
for (auto i = 0u; i < Indexes.size(); i += 3)
{
FTriIndices Triangle;
// "-1" since mesh indexes in Unreal starts from index 0.
Triangles.Add(Indexes[i] - 1);
// Since Unreal's coords are left handed, invert the last 2 indices.
Triangles.Add(Indexes[i + 2] - 1);
Triangles.Add(Indexes[i + 1] - 1);
// // Build collision data
// FTriMeshCollisionData CollisitonData;
// CollisitonData.bDeformableMesh = false;
// CollisitonData.bDisableActiveEdgePrecompute = false;
// CollisitonData.bFastCook = false;
// CollisitonData.bFlipNormals = false;
// CollisitonData.Indices = TriIndices;
// CollisitonData.Vertices = Vertices;
Triangle.v0 = Indexes[i] - 1;
Triangle.v1 = Indexes[i + 2] - 1;
Triangle.v2 = Indexes[i + 1] - 1;
TriIndices.Add(Triangle);
}
TArray<FVector> Normals;
Normals.Init(FVector::UpVector, Vertices.Num());
for (const auto &Triangle : TriIndices) {
FVector Normal;
const FVector U = Vertices[Triangle.v1] - Vertices[Triangle.v0];
const FVector V = Vertices[Triangle.v2] - Vertices[Triangle.v0];
Normal.X = (U.Y * V.Z) - (U.Z * V.Y);
Normal.Y = (U.Z * V.X) - (U.X * V.Z);
Normal.Z = (U.X * V.Y) - (U.Y * V.X);
Normal = -Normal;
Normal = Normal.GetSafeNormal(.0001f);
if (Normal != FVector::ZeroVector)
{
Normals[Triangle.v0] = Normal;
Normals[Triangle.v1] = Normal;
Normals[Triangle.v2] = Normal;
}
}
RoadMesh->CreateMeshSection_LinearColor(
0,
Vertices,
Triangles,
Normals, // Normals
TArray<FVector2D>(), // UV0
TArray<FLinearColor>(), // VertexColor
TArray<FProcMeshTangent>(), // Tangents
true); // Create collision
// Build collision data
FTriMeshCollisionData CollisitonData;
CollisitonData.bDeformableMesh = false;
CollisitonData.bDisableActiveEdgePrecompute = false;
CollisitonData.bFastCook = false;
CollisitonData.bFlipNormals = false;
CollisitonData.Indices = TriIndices;
CollisitonData.Vertices = Vertices;
RoadMesh->ContainsPhysicsTriMeshData(true);
bool Success = RoadMesh->GetPhysicsTriMeshData(&CollisitonData, true);
if (!Success)
{
UE_LOG(LogCarla, Error, TEXT("The road collision mesh could not be generated!"));
}
// RoadMesh->ContainsPhysicsTriMeshData(true);
// bool Success = RoadMesh->GetPhysicsTriMeshData(&CollisitonData, true);
// if (!Success)
// {
// UE_LOG(LogCarla, Error, TEXT("The road collision mesh could not be generated!"));
// }
}
void AOpenDriveGenerator::GeneratePoles()

View File

@ -64,7 +64,7 @@ protected:
FString OpenDriveData;
UPROPERTY(EditAnywhere)
UProceduralMeshComponent *RoadMesh;
TArray<AActor *> ActorMeshList;
boost::optional<carla::road::Map> CarlaMap;

View File

@ -0,0 +1,35 @@
// Copyright (c) 2020 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 <https://opensource.org/licenses/MIT>.
#pragma once
#include "ProceduralCustomMesh.generated.h"
/// A definition of a Carla Mesh.
USTRUCT()
struct CARLA_API FProceduralCustomMesh
{
GENERATED_BODY()
UPROPERTY()
TArray<FVector> Vertices;
UPROPERTY()
TArray<int32> Triangles;
UPROPERTY()
TArray<FVector> Normals;
UPROPERTY()
TArray<FVector2D> UV0;
UPROPERTY()
TArray<FLinearColor> VertexColor;
// This is commented due to an strange bug including ProceduralMeshComponent.h
// UPROPERTY()
// TArray<FProcMeshTangent> Tangents;
};