Aaron/opendrivetomapineditor (#6056)

* Added way to download files from overpass api

* Save downloaded text to a file

* Changed log type for File manipulation

* Online process files when request is valid

* Correct file format

* Correct file format for UE4 class

* Fix compilation issue due to name change

* Create Widget with OpenFileDialogFunctionality

* Step xodr to map completed

* Generated Static meshes and replace procedural actors

* Created and saved assets during road generation

* Formatted file correctly

* OSM To ODR broguht to UE4

* Full pipeline working on linux

* Added osm2odr support in editor in Windos

* Added Widget to CartaTools

* Fixed Linux compilation error

* Added Carla Game Instance included to avoid compilation error

* Added Simplify to LibCarla, Added timers to measure time generation.  Add mesh deformation during road creation.

* Fixed mesh format translations

* Concated meshes generated in the same lane to avoid errors during simplification

* Avoid Simplify to remove border vertices and try to parallel assets creation process

* Road Generation 0.1 version ready

* Removing Engine Association, Formatting CarlaTools Build dependencies

* Change container type of generated procedural mesh componetns to be supported by UPROPERTY

* Fixed indices jumping by two

* Cleaning branch

* Cleanup last spaces

* Remove spaces on Opendrivetowditor.cpp
This commit is contained in:
Blyron 2023-02-15 09:50:55 +01:00 committed by GitHub
parent 7f5bb15731
commit dcca826ade
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
25 changed files with 2514 additions and 16 deletions

View File

@ -9,6 +9,8 @@
#include <string>
#include <sstream>
#include <ios>
#include <iostream>
#include <fstream>
#include <carla/geom/Math.h>
@ -266,6 +268,9 @@ namespace geom {
return _indexes;
}
std::vector<Mesh::index_type>& Mesh::GetIndexes() {
return _indexes;
}
size_t Mesh::GetIndexesNum() const {
return _indexes.size();
}
@ -282,6 +287,62 @@ namespace geom {
return _vertices.size();
}
Mesh& Mesh::ConcatMesh(const Mesh& rhs, int num_vertices_to_link) {
if (!rhs.IsValid())
{
return *this += rhs;
}
const size_t v_num = GetVerticesNum();
const size_t i_num = GetIndexesNum();
_vertices.insert(
_vertices.end(),
rhs.GetVertices().begin(),
rhs.GetVertices().end());
_normals.insert(
_normals.end(),
rhs.GetNormals().begin(),
rhs.GetNormals().end());
const int vertex_to_start_concating = v_num - num_vertices_to_link;
for( int i = 1; i < num_vertices_to_link; ++i )
{
_indexes.push_back( vertex_to_start_concating + i );
_indexes.push_back( vertex_to_start_concating + i + 1 );
_indexes.push_back( v_num + i );
_indexes.push_back( vertex_to_start_concating + i + 1);
_indexes.push_back( v_num + i + 1);
_indexes.push_back( v_num + i);
}
std::transform(
rhs.GetIndexes().begin(),
rhs.GetIndexes().end(),
std::back_inserter(_indexes),
[=](size_t index) {return index + v_num; });
_uvs.insert(
_uvs.end(),
rhs.GetUVs().begin(),
rhs.GetUVs().end());
std::transform(
rhs.GetMaterials().begin(),
rhs.GetMaterials().end(),
std::back_inserter(_materials),
[=](MeshMaterial mat) {
mat.index_start += i_num;
mat.index_end += i_num;
return mat;
});
return *this;
}
Mesh &Mesh::operator+=(const Mesh &rhs) {
const size_t v_num = GetVerticesNum();
const size_t i_num = GetIndexesNum();

View File

@ -131,7 +131,9 @@ namespace geom {
const std::vector<normal_type> &GetNormals() const;
const std::vector<index_type> &GetIndexes() const;
const std::vector<index_type>& GetIndexes() const;
std::vector<index_type> &GetIndexes();
size_t GetIndexesNum() const;
@ -142,6 +144,9 @@ namespace geom {
/// Returns the index of the last added vertex (number of vertices).
size_t GetLastVertexIndex() const;
/// Merges two meshes into a single mesh
Mesh& ConcatMesh(const Mesh& rhs, int num_vertices_to_link);
/// Merges two meshes into a single mesh
Mesh &operator+=(const Mesh &rhs);

View File

@ -7,6 +7,7 @@
#include "carla/road/Map.h"
#include "carla/Exception.h"
#include "carla/geom/Math.h"
#include "carla/geom/Vector3D.h"
#include "carla/road/MeshFactory.h"
#include "carla/road/element/LaneCrossingCalculator.h"
#include "carla/road/element/RoadInfoCrosswalk.h"
@ -17,6 +18,8 @@
#include "carla/road/element/RoadInfoMarkRecord.h"
#include "carla/road/element/RoadInfoSignal.h"
#include "simplify/Simplify.h"
#include <vector>
#include <unordered_map>
#include <stdexcept>
@ -1040,6 +1043,7 @@ namespace road {
return out_mesh;
}
std::vector<std::unique_ptr<geom::Mesh>> Map::GenerateChunkedMesh(
const rpc::OpendriveGenerationParameters& params) const {
geom::MeshFactory mesh_factory(params);
@ -1124,6 +1128,161 @@ namespace road {
return result;
}
std::map<road::Lane::LaneType , std::vector<std::unique_ptr<geom::Mesh>>>
Map::GenerateOrderedChunkedMesh( const rpc::OpendriveGenerationParameters& params) const
{
geom::MeshFactory mesh_factory(params);
std::map<road::Lane::LaneType , std::vector<std::unique_ptr<geom::Mesh>>> out_mesh_list;
std::unordered_map<JuncId, geom::Mesh> junction_map;
float simplificationrate = params.simplification_percentage * 0.01f;
for (auto &&pair : _data.GetRoads())
{
const auto &road = pair.second;
if (!road.IsJunction()) {
mesh_factory.GenerateAllOrderedWithMaxLen(road, out_mesh_list);
}
}
for (auto& current_mesh_vector : out_mesh_list)
{
if (current_mesh_vector.first != road::Lane::LaneType::Driving)
{
continue;
}
for (std::unique_ptr<geom::Mesh>& current_mesh : current_mesh_vector.second)
{
if (!current_mesh->IsValid())
{
continue;
}
for (carla::geom::Vector3D& current_vertex : current_mesh->GetVertices())
{
current_vertex.z = GetZPosInDeformation(current_vertex.x, current_vertex.y);
}
for (carla::geom::Vector3D& current_vertex : current_mesh->GetVertices())
{
Simplify::Vertex v;
v.p.x = current_vertex.x;
v.p.y = current_vertex.y;
v.p.z = current_vertex.z;
Simplify::vertices.push_back(v);
}
for (int i = 0; i < current_mesh->GetIndexes().size() - 2; i += 3)
{
Simplify::Triangle t;
t.material = 0;
auto indices = current_mesh->GetIndexes();
t.v[0] = (indices[i]) - 1;
t.v[1] = (indices[i + 1]) - 1;
t.v[2] = (indices[i + 2]) - 1;
if (i >= current_mesh->GetIndexes().size()) {
std::cout << "Not right number of Indexes Index: " << i << " Indices size: " << current_mesh->GetIndexes().size() << std::endl;
}
Simplify::triangles.push_back(t);
}
// Reduce to the X% of the polys
float target_size = Simplify::triangles.size();
Simplify::simplify_mesh( (target_size * simplificationrate) );
current_mesh->GetVertices().clear();
current_mesh->GetIndexes().clear();
for (Simplify::Vertex& current_vertex : Simplify::vertices)
{
carla::geom::Vector3D v;
v.x = current_vertex.p.x;
v.y = current_vertex.p.y;
v.z = current_vertex.p.z;
current_mesh->AddVertex(v);
}
for (int i = 0; i < Simplify::triangles.size(); ++i)
{
for (int j = 0; j < 3; ++j) {
current_mesh->GetIndexes().push_back((Simplify::triangles[i].v[j]) + 1);
}
}
Simplify::vertices.clear();
Simplify::triangles.clear();
}
}
// Generate roads within junctions and smooth them
for (const auto &junc_pair : _data.GetJunctions()) {
const auto &junction = junc_pair.second;
std::vector<std::unique_ptr<geom::Mesh>> lane_meshes;
std::vector<std::unique_ptr<geom::Mesh>> sidewalk_lane_meshes;
for(const auto &connection_pair : junction.GetConnections()) {
const auto &connection = connection_pair.second;
const auto &road = _data.GetRoads().at(connection.connecting_road);
for (auto &&lane_section : road.GetLaneSections()) {
for (auto &&lane_pair : lane_section.GetLanes()) {
const auto &lane = lane_pair.second;
if (lane.GetType() != road::Lane::LaneType::Sidewalk) {
lane_meshes.push_back(mesh_factory.Generate(lane));
} else {
sidewalk_lane_meshes.push_back(mesh_factory.Generate(lane));
}
}
}
}
if(params.smooth_junctions) {
std::unique_ptr<geom::Mesh> merged_mesh = mesh_factory.MergeAndSmooth(lane_meshes);
std::unique_ptr<geom::Mesh> sidewalk_mesh = std::make_unique<geom::Mesh>();
for(auto& lane : sidewalk_lane_meshes) {
*sidewalk_mesh += *lane;
}
for (carla::geom::Vector3D& current_vertex : merged_mesh->GetVertices())
{
current_vertex.z = GetZPosInDeformation(current_vertex.x, current_vertex.y);
}
for (carla::geom::Vector3D& current_vertex : sidewalk_mesh->GetVertices())
{
current_vertex.z = GetZPosInDeformation(current_vertex.x, current_vertex.y);
}
out_mesh_list[road::Lane::LaneType::Driving].push_back(std::move(merged_mesh));
out_mesh_list[road::Lane::LaneType::Sidewalk].push_back(std::move(sidewalk_mesh));
} else {
std::unique_ptr<geom::Mesh> junction_mesh = std::make_unique<geom::Mesh>();
std::unique_ptr<geom::Mesh> sidewalk_mesh = std::make_unique<geom::Mesh>();
for(auto& lane : lane_meshes) {
*junction_mesh += *lane;
}
for(auto& lane : sidewalk_lane_meshes) {
*sidewalk_mesh += *lane;
}
for (carla::geom::Vector3D& current_vertex : junction_mesh->GetVertices())
{
current_vertex.z = GetZPosInDeformation(current_vertex.x, current_vertex.y);
}
for (carla::geom::Vector3D& current_vertex : sidewalk_mesh->GetVertices())
{
current_vertex.z = GetZPosInDeformation(current_vertex.x, current_vertex.y);
}
out_mesh_list[road::Lane::LaneType::Driving].push_back(std::move(junction_mesh));
out_mesh_list[road::Lane::LaneType::Sidewalk].push_back(std::move(sidewalk_mesh));
}
}
return out_mesh_list;
}
geom::Mesh Map::GetAllCrosswalkMesh() const {
geom::Mesh out_mesh;
@ -1160,5 +1319,24 @@ namespace road {
return out_mesh;
}
float Map::GetZPosInDeformation(float posx, float posy) const
{
// Amplitud
const float A1 = 0.3f;
const float A2 = 0.5f;
// Fases
const float F1 = 100.0;
const float F2 = -1500.0;
// Modifiers
const float Kx1 = 0.035f;
const float Kx2 = 0.02f;
const float Ky1 = -0.08f;
const float Ky2 = 0.05f;
return A1 * sin((Kx1 * posx + Ky1 * posy + F1)) +
A2 * sin((Kx2 * posx + Ky2 * posy + F2));
}
} // namespace road
} // namespace carla

View File

@ -159,6 +159,9 @@ namespace road {
std::vector<std::unique_ptr<geom::Mesh>> GenerateChunkedMesh(
const rpc::OpendriveGenerationParameters& params) const;
std::map<road::Lane::LaneType , std::vector<std::unique_ptr<geom::Mesh>>>
GenerateOrderedChunkedMesh( const rpc::OpendriveGenerationParameters& params) const;
/// Buids a mesh of all crosswalks based on the OpenDRIVE
geom::Mesh GetAllCrosswalkMesh() const;
@ -201,6 +204,8 @@ private:
geom::Transform &current_transform,
Waypoint &current_waypoint,
Waypoint &next_waypoint);
float GetZPosInDeformation(float posx, float posy) const;
};
} // namespace road

View File

@ -19,6 +19,7 @@ namespace geom {
road_param.max_road_len = static_cast<float>(params.max_road_length);
road_param.extra_lane_width = static_cast<float>(params.additional_width);
road_param.wall_height = static_cast<float>(params.wall_height);
road_param.vertex_width_resolution = static_cast<float>(params.vertex_width_resolution);
}
/// We use this epsilon to shift the waypoints away from the edges of the lane
@ -48,6 +49,12 @@ namespace geom {
return Generate(lane, s_start, s_end);
}
std::unique_ptr<Mesh> MeshFactory::GenerateTesselated(const road::Lane& lane) const {
const double s_start = lane.GetDistance() + EPSILON;
const double s_end = lane.GetDistance() + lane.GetLength() - EPSILON;
return GenerateTesselated(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);
@ -63,13 +70,16 @@ namespace geom {
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(s_current, road_param.extra_lane_width);
vertices.push_back(edges.first);
vertices.push_back(edges.second);
} else {
}
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
@ -98,6 +108,103 @@ namespace geom {
return std::make_unique<Mesh>(out_mesh);
}
std::unique_ptr<Mesh> MeshFactory::GenerateTesselated(
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
Mesh out_mesh;
if (lane.GetId() == 0) {
return std::make_unique<Mesh>(out_mesh);
}
double s_current = s_start;
std::vector<geom::Vector3D> vertices;
// Ensure minimum vertices in width are two
const int vertices_in_width = road_param.vertex_width_resolution >= 2 ? road_param.vertex_width_resolution : 2;
const int segments_number = vertices_in_width - 1;
// 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
std::pair<geom::Vector3D, geom::Vector3D> edges = lane.GetCornerPositions(s_current, road_param.extra_lane_width);
const geom::Vector3D segments_size = ( edges.second - edges.first ) / segments_number;
geom::Vector3D current_vertex = edges.first;
for (int i = 0; i < vertices_in_width; ++i)
{
vertices.push_back(current_vertex);
current_vertex = current_vertex + segments_size;
}
// Update the current waypoint's "s"
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 (s_end - (s_current - road_param.resolution) > EPSILON) {
const auto edges = lane.GetCornerPositions(s_end - MESH_EPSILON, road_param.extra_lane_width);
const geom::Vector3D segments_size = (edges.second - edges.first) / segments_number;
geom::Vector3D current_vertex = edges.first;
for (int i = 0; i < vertices_in_width; ++i)
{
vertices.push_back(current_vertex);
current_vertex = current_vertex + segments_size;
}
}
out_mesh.AddVertices(vertices);
// Add the adient material, create the strip and close the material
out_mesh.AddMaterial(
lane.GetType() == road::Lane::LaneType::Sidewalk ? "sidewalk" : "road");
const int number_of_rows = (vertices.size() / vertices_in_width);
for (int i = 0; i < (number_of_rows - 1); ++i)
{
for (int j = 0; j < vertices_in_width - 1; ++j)
{
out_mesh.AddIndex( j + ( i * vertices_in_width ) + 1);
out_mesh.AddIndex( ( j + 1 ) + ( i * vertices_in_width ) + 1);
out_mesh.AddIndex( j + ( ( i + 1 ) * vertices_in_width ) + 1);
out_mesh.AddIndex( ( j + 1 ) + ( i * vertices_in_width ) + 1);
out_mesh.AddIndex( ( j + 1 ) + ( ( i + 1 ) * vertices_in_width ) + 1);
out_mesh.AddIndex( j + ( ( i + 1 ) * vertices_in_width ) + 1);
}
}
out_mesh.EndMaterial();
return std::make_unique<Mesh>(out_mesh);
}
void MeshFactory::GenerateLaneSectionOrdered(
const road::LaneSection &lane_section,
std::map<carla::road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>>& result)
const
{
const int vertices_in_width = road_param.vertex_width_resolution >= 2 ? road_param.vertex_width_resolution : 2;
for (auto &&lane_pair : lane_section.GetLanes())
{
Mesh out_mesh = *GenerateTesselated(lane_pair.second);
if( result[lane_pair.second.GetType()].empty() )
{
result[lane_pair.second.GetType()].push_back(std::make_unique<Mesh>(out_mesh));
}
else
{
(result[lane_pair.second.GetType()][0])->ConcatMesh(out_mesh, vertices_in_width);
}
}
}
std::unique_ptr<Mesh> MeshFactory::GenerateWalls(const road::LaneSection &lane_section) const {
Mesh out_mesh;
@ -263,6 +370,62 @@ namespace geom {
return mesh_uptr_list;
}
std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> MeshFactory::GenerateOrderedWithMaxLen(
const road::Road &road) const {
std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> mesh_uptr_list;
for (auto &&lane_section : road.GetLaneSections()) {
std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> section_uptr_list = GenerateOrderedWithMaxLen(lane_section);
mesh_uptr_list.insert(
std::make_move_iterator(section_uptr_list.begin()),
std::make_move_iterator(section_uptr_list.end()));
}
return mesh_uptr_list;
}
std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> MeshFactory::GenerateOrderedWithMaxLen(
const road::LaneSection &lane_section) const {
const int vertices_in_width = road_param.vertex_width_resolution >= 2 ? road_param.vertex_width_resolution : 2;
std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> mesh_uptr_list;
if (lane_section.GetLength() < road_param.max_road_len) {
GenerateLaneSectionOrdered(lane_section, mesh_uptr_list);
} else {
double s_current = lane_section.GetDistance() + EPSILON;
const double s_end = lane_section.GetDistance() + lane_section.GetLength() - EPSILON;
while(s_current + road_param.max_road_len < s_end) {
const auto s_until = s_current + road_param.max_road_len;
for (auto &&lane_pair : lane_section.GetLanes()) {
Mesh lane_section_mesh = *GenerateTesselated(lane_pair.second, s_current, s_until);
if( mesh_uptr_list[lane_pair.second.GetType()].empty() )
{
mesh_uptr_list[lane_pair.second.GetType()].push_back(std::make_unique<Mesh>(lane_section_mesh));
}
else
{
(mesh_uptr_list[lane_pair.second.GetType()][0])->ConcatMesh(lane_section_mesh, vertices_in_width);
}
}
s_current = s_until;
}
if (s_end - s_current > EPSILON) {
for (auto &&lane_pair : lane_section.GetLanes()) {
Mesh lane_section_mesh = *GenerateTesselated(lane_pair.second, s_current, s_end);
if( mesh_uptr_list[lane_pair.second.GetType()].empty() )
{
mesh_uptr_list[lane_pair.second.GetType()].push_back(std::make_unique<Mesh>(lane_section_mesh));
}
else
{
(mesh_uptr_list[lane_pair.second.GetType()][0])->ConcatMesh(lane_section_mesh, vertices_in_width);
}
}
}
}
return mesh_uptr_list;
}
std::vector<std::unique_ptr<Mesh>> MeshFactory::GenerateWallsWithMaxLen(
const road::Road &road) const {
std::vector<std::unique_ptr<Mesh>> mesh_uptr_list;
@ -352,6 +515,21 @@ namespace geom {
return mesh_uptr_list;
}
void MeshFactory::GenerateAllOrderedWithMaxLen(
const road::Road &road,
std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>>& roads
) const
{
// Get road meshes
std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> result = GenerateOrderedWithMaxLen(road);
for (auto &pair_map : result)
{
std::vector<std::unique_ptr<Mesh>>& origin = roads[pair_map.first];
std::vector<std::unique_ptr<Mesh>>& source = pair_map.second;
std::move(source.begin(), source.end(), std::back_inserter(origin));
}
}
struct VertexWeight {
Mesh::vertex_type* vertex;
double weight;

View File

@ -41,9 +41,19 @@ namespace geom {
std::unique_ptr<Mesh> Generate(
const road::Lane &lane, const double s_start, const double s_end) const;
/// Generates a mesh that defines a lane from a given s start and end with bigger tesselation
std::unique_ptr<Mesh> GenerateTesselated(
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 the whole lane with bigger tesselation
std::unique_ptr<Mesh> GenerateTesselated(const road::Lane& lane) const;
/// Generates a mesh that defines a lane section
void GenerateLaneSectionOrdered(const road::LaneSection &lane_section,
std::map<carla::road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>>& result ) const;
// -- Walls --
/// Genrates a mesh representing a wall on the road corners to avoid
@ -68,6 +78,14 @@ namespace geom {
std::vector<std::unique_ptr<Mesh>> GenerateWithMaxLen(
const road::LaneSection &lane_section) const;
/// Generates a list of meshes that defines a road with a maximum length
std::map<carla::road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> GenerateOrderedWithMaxLen(
const road::Road &road) const;
/// Generates a list of meshes that defines a lane_section with a maximum length
std::map<carla::road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> GenerateOrderedWithMaxLen(
const road::LaneSection &lane_section) const;
/// Generates a list of meshes that defines a road safety wall with a maximum length
std::vector<std::unique_ptr<Mesh>> GenerateWallsWithMaxLen(
const road::Road &road) const;
@ -82,6 +100,10 @@ namespace geom {
std::vector<std::unique_ptr<Mesh>> GenerateAllWithMaxLen(
const road::Road &road) const;
void GenerateAllOrderedWithMaxLen(const road::Road &road,
std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>>& roads) const;
std::unique_ptr<Mesh> MergeAndSmooth(std::vector<std::unique_ptr<Mesh>> &lane_meshes) const;
// =========================================================================
@ -94,6 +116,7 @@ namespace geom {
float max_road_len = 50.0f;
float extra_lane_width = 1.0f;
float wall_height = 0.6f;
float vertex_width_resolution = 4.0f;
// Road mesh smoothness:
float max_weight_distance = 5.0f;
float same_lane_weight_multiplier = 2.0f;

View File

@ -35,6 +35,8 @@ namespace rpc {
double max_road_length = 50.0;
double wall_height = 1.0;
double additional_width = 0.6;
double vertex_width_resolution = 4.0f;
float simplification_percentage = 20.0f;
bool smooth_junctions = true;
bool enable_mesh_visibility = true;
bool enable_pedestrian_navigation = true;

File diff suppressed because it is too large Load Diff

View File

@ -72,7 +72,8 @@ public class Carla : ModuleRules
"RenderCore",
"RHI",
"Renderer",
"ProceduralMeshComponent"
"ProceduralMeshComponent",
"MeshDescription"
// ... add other public dependencies that you statically link with here ...
}
);
@ -94,6 +95,8 @@ public class Carla : ModuleRules
"CoreUObject",
"Engine",
"Foliage",
"HTTP",
"StaticMeshDescription",
"ImageWriteQueue",
"Json",
"JsonUtilities",
@ -201,6 +204,13 @@ public class Carla : ModuleRules
AddDllDependency(Path.Combine(LibCarlaInstallPath, "dll"), "ChronoModels_robot.dll");
bUseRTTI = true;
}
//OsmToODR
PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", "sqlite3.lib"));
PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", "xerces-c_3.lib"));
PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", "proj.lib"));
PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", "osm2odr.lib"));
PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", "zlibstatic.lib"));
}
else
{
@ -219,6 +229,7 @@ public class Carla : ModuleRules
AddDynamicLibrary(Path.Combine(LibCarlaInstallPath, "lib", "libChronoEngine_vehicle.so"));
AddDynamicLibrary(Path.Combine(LibCarlaInstallPath, "lib", "libChronoModels_vehicle.so"));
AddDynamicLibrary(Path.Combine(LibCarlaInstallPath, "lib", "libChronoModels_robot.so"));
bUseRTTI = true;
}
@ -295,7 +306,15 @@ public class Carla : ModuleRules
PublicAdditionalLibraries.Add("stdc++");
PublicAdditionalLibraries.Add("/usr/lib/x86_64-linux-gnu/libpython3.9.so");
}
//OsmToODR
PublicAdditionalLibraries.Add("/usr/lib/x86_64-linux-gnu/libc.so");
PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", "libsqlite3.so"));
PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", "libxerces-c.a"));
PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", "libproj.a"));
PublicAdditionalLibraries.Add(Path.Combine(LibCarlaInstallPath, "lib", "libosm2odr.a"));
}
bEnableExceptions = true;

View File

@ -0,0 +1,128 @@
// Copyright (c) 2017 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>.
#undef CreateDirectory
#include "Online/CustomFileDownloader.h"
#include "HttpModule.h"
#include "Http.h"
#include "Misc/FileHelper.h"
#include <OSM2ODR.h>
void UCustomFileDownloader::ConvertOSMInOpenDrive(FString FilePath)
{
IPlatformFile &FileManager = FPlatformFileManager::Get().GetPlatformFile();
FString FileContent;
// Always first check if the file that you want to manipulate exist.
if (FileManager.FileExists(*FilePath))
{
// We use the LoadFileToString to load the file into
if (FFileHelper::LoadFileToString(FileContent, *FilePath, FFileHelper::EHashOptions::None))
{
UE_LOG(LogCarla, Warning, TEXT("FileManipulation: Text From File: %s"), *FilePath);
}
else
{
UE_LOG(LogCarla, Warning, TEXT("FileManipulation: Did not load text from file"));
}
}
else
{
UE_LOG(LogCarla, Warning, TEXT("File: %s does not exist"), *FilePath);
return;
}
std::string OsmFile = std::string(TCHAR_TO_UTF8(*FileContent));
std::string OpenDriveFile = osm2odr::ConvertOSMToOpenDRIVE(OsmFile);
FilePath.RemoveFromEnd(".osm", ESearchCase::Type::IgnoreCase);
FilePath += ".xodr";
UE_LOG(LogCarla, Warning, TEXT("File: %s does not exist"), *FilePath);
// We use the LoadFileToString to load the file into
if (FFileHelper::SaveStringToFile(FString(OpenDriveFile.c_str()), *FilePath))
{
UE_LOG(LogCarla, Warning, TEXT("FileManipulation: Sucsesfuly Written: \"%s\" to the text file"), *FilePath);
}
else
{
UE_LOG(LogCarla, Warning, TEXT("FileManipulation: Failed to write FString to file."));
}
}
void UCustomFileDownloader::StartDownload()
{
UE_LOG(LogCarla, Log, TEXT("FHttpDownloader CREATED"));
FHttpDownloader *Download = new FHttpDownloader("GET", Url, ResultFileName, DownloadDelegate);
Download->Run();
}
FHttpDownloader::FHttpDownloader(const FString &InVerb, const FString &InUrl, const FString &InFilename, FDownloadComplete &Delegate)
: Verb(InVerb), Url(InUrl), Filename(InFilename), DelegateToCall(Delegate)
{
}
void FHttpDownloader::Run(void)
{
UE_LOG(LogCarla, Log, TEXT("Starting download [%s] Url=[%s]"), *Verb, *Url);
TSharedPtr<IHttpRequest, ESPMode::ThreadSafe> Request = FHttpModule::Get().CreateRequest();
Request->OnProcessRequestComplete().BindRaw(this, &FHttpDownloader::RequestComplete);
Request->SetURL(Url);
Request->SetVerb(Verb);
Request->ProcessRequest();
}
void FHttpDownloader::RequestComplete(FHttpRequestPtr HttpRequest, FHttpResponsePtr HttpResponse, bool bSucceeded)
{
if (!HttpResponse.IsValid())
{
UE_LOG(LogCarla, Log, TEXT("Download failed. NULL response"));
}
else
{
// If we do not get success responses codes we do not do anything
if (HttpResponse->GetResponseCode() < 200 || 300 <= HttpResponse->GetResponseCode())
{
UE_LOG(LogCarla, Error, TEXT("Error during download [%s] Url=[%s] Response=[%d]"),
*HttpRequest->GetVerb(),
*HttpRequest->GetURL(),
HttpResponse->GetResponseCode());
delete this;
return;
}
UE_LOG(LogCarla, Log, TEXT("Completed download [%s] Url=[%s] Response=[%d]"),
*HttpRequest->GetVerb(),
*HttpRequest->GetURL(),
HttpResponse->GetResponseCode());
HttpRequest->OnProcessRequestComplete().Unbind();
FString CurrentFile = FPaths::ProjectContentDir() + "CustomMaps/" + Filename + "/";
// We will use this FileManager to deal with the file.
IPlatformFile &FileManager = FPlatformFileManager::Get().GetPlatformFile();
if (!FileManager.DirectoryExists(*CurrentFile))
{
FileManager.CreateDirectory(*CurrentFile);
}
CurrentFile += Filename + ".osm";
FString StringToWrite = HttpResponse->GetContentAsString();
// We use the LoadFileToString to load the file into
if (FFileHelper::SaveStringToFile(StringToWrite, *CurrentFile, FFileHelper::EEncodingOptions::ForceUTF8WithoutBOM))
{
UE_LOG(LogCarla, Warning, TEXT("FileManipulation: Sucsesfuly Written "));
}
else
{
UE_LOG(LogCarla, Warning, TEXT("FileManipulation: Failed to write FString to file."));
}
}
DelegateToCall.ExecuteIfBound();
delete this;
}

View File

@ -0,0 +1,63 @@
// Copyright (c) 2017 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 "CoreMinimal.h"
#include "Interfaces/IHttpRequest.h"
#include "CustomFileDownloader.generated.h"
/**
*
*/
DECLARE_DELEGATE(FDownloadComplete)
UCLASS(Blueprintable)
class CARLA_API UCustomFileDownloader : public UObject
{
GENERATED_BODY()
public:
UFUNCTION(BlueprintCallable)
void StartDownload();
UFUNCTION(BlueprintCallable)
void ConvertOSMInOpenDrive(FString FilePath);
FString ResultFileName;
FString Url;
FDownloadComplete DownloadDelegate;
private:
void RequestComplete(FHttpRequestPtr HttpRequest, FHttpResponsePtr HttpResponse, bool bSucceeded);
FString Payload;
};
class FHttpDownloader
{
public:
/**
*
* @param Verb - verb to use for request (GET,POST,DELETE,etc)
* @param Url - url address to connect to
*/
FHttpDownloader( const FString& InVerb, const FString& InUrl, const FString& InFilename, FDownloadComplete& Delegate );
// Kick off the Http request and wait for delegate to be called
void Run(void);
/**
* Delegate called when the request completes
*
* @param HttpRequest - object that started/processed the request
* @param HttpResponse - optional response object if request completed
* @param bSucceeded - true if Url connection was made and response was received
*/
void RequestComplete(FHttpRequestPtr HttpRequest, FHttpResponsePtr HttpResponse, bool bSucceeded);
private:
FString Verb;
FString Url;
FString Filename;
FDownloadComplete DelegateToCall;
};

View File

@ -3,7 +3,7 @@
#include "Carla/Game/CarlaGameInstance.h"
#include "Carla/Settings/CarlaSettings.h"
#include "Carla/Game/CarlaGameInstance.h"
#include "Async.h"
#include "Components/StaticMeshComponent.h"
#include "Engine/DirectionalLight.h"

View File

@ -33,6 +33,10 @@
{
"Name": "PhysXVehicles",
"Enabled": true
},
{
"Name": "ProceduralMeshComponent",
"Enabled": true
}
]
}

View File

@ -39,7 +39,11 @@ public class CarlaTools : ModuleRules
PublicDependencyModuleNames.AddRange(
new string[]
{
"Core"
"Core",
"ProceduralMeshComponent",
"MeshDescription",
"RawMesh",
"AssetTools"
// ... add other public dependencies that you statically link with here ...
}
);

View File

@ -0,0 +1,504 @@
// Copyright (c) 2023 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>.
#include "OpenDriveToMap.h"
#include "Components/Button.h"
#include "DesktopPlatform/Public/IDesktopPlatform.h"
#include "DesktopPlatform/Public/DesktopPlatformModule.h"
#include "Misc/FileHelper.h"
#include "Runtime/Core/Public/Async/ParallelFor.h"
#include "Carla/Game/CarlaStatics.h"
#include "Traffic/TrafficLightManager.h"
#include "Online/CustomFileDownloader.h"
#include "Util/ProceduralCustomMesh.h"
#include "OpenDrive/OpenDriveGenerator.h"
#include <compiler/disable-ue4-macros.h>
#include <carla/opendrive/OpenDriveParser.h>
#include <carla/road/Map.h>
#include <carla/rpc/String.h>
#include <OSM2ODR.h>
#include <compiler/enable-ue4-macros.h>
#include "Engine/Classes/Interfaces/Interface_CollisionDataProvider.h"
#include "PhysicsCore/Public/BodySetupEnums.h"
#include "RawMesh.h"
#include "AssetRegistryModule.h"
#include "Engine/StaticMesh.h"
#include "Engine/StaticMeshActor.h"
#include "MeshDescription.h"
#include "ProceduralMeshConversion.h"
FString LaneTypeToFString(carla::road::Lane::LaneType LaneType)
{
switch (LaneType)
{
case carla::road::Lane::LaneType::Driving:
return FString("Driving");
break;
case carla::road::Lane::LaneType::Stop:
return FString("Stop");
break;
case carla::road::Lane::LaneType::Shoulder:
return FString("Shoulder");
break;
case carla::road::Lane::LaneType::Biking:
return FString("Biking");
break;
case carla::road::Lane::LaneType::Sidewalk:
return FString("Sidewalk");
break;
case carla::road::Lane::LaneType::Border:
return FString("Border");
break;
case carla::road::Lane::LaneType::Restricted:
return FString("Restricted");
break;
case carla::road::Lane::LaneType::Parking:
return FString("Parking");
break;
case carla::road::Lane::LaneType::Bidirectional:
return FString("Bidirectional");
break;
case carla::road::Lane::LaneType::Median:
return FString("Median");
break;
case carla::road::Lane::LaneType::Special1:
return FString("Special1");
break;
case carla::road::Lane::LaneType::Special2:
return FString("Special2");
break;
case carla::road::Lane::LaneType::Special3:
return FString("Special3");
break;
case carla::road::Lane::LaneType::RoadWorks:
return FString("RoadWorks");
break;
case carla::road::Lane::LaneType::Tram:
return FString("Tram");
break;
case carla::road::Lane::LaneType::Rail:
return FString("Rail");
break;
case carla::road::Lane::LaneType::Entry:
return FString("Entry");
break;
case carla::road::Lane::LaneType::Exit:
return FString("Exit");
break;
case carla::road::Lane::LaneType::OffRamp:
return FString("OffRamp");
break;
case carla::road::Lane::LaneType::OnRamp:
return FString("OnRamp");
break;
case carla::road::Lane::LaneType::Any:
return FString("Any");
break;
}
return FString("Empty");
}
void UOpenDriveToMap::ConvertOSMInOpenDrive()
{
FilePath = FPaths::ProjectContentDir() + "CustomMaps/" + MapName + "/" + MapName + ".osm";
FileDownloader->ConvertOSMInOpenDrive( FilePath );
FilePath.RemoveFromEnd(".osm", ESearchCase::Type::IgnoreCase);
FilePath += ".xodr";
LoadMap();
}
void UOpenDriveToMap::NativeConstruct()
{
if( !IsValid(FileDownloader) ){
FileDownloader = NewObject<UCustomFileDownloader>();
}
}
void UOpenDriveToMap::NativeDestruct()
{
Super::NativeDestruct();
if( IsValid(FileDownloader) ){
// UObjects are not being destroyed, they are collected by GarbageCollector
// Should we force garbage collection here?
}
}
void UOpenDriveToMap::CreateMap()
{
if( MapName.IsEmpty() )
{
UE_LOG(LogCarlaToolsMapGenerator, Error, TEXT("Map Name Is Empty") );
return;
}
if ( !IsValid(FileDownloader) )
{
FileDownloader = NewObject<UCustomFileDownloader>();
}
FileDownloader->ResultFileName = MapName;
FileDownloader->Url = Url;
FileDownloader->DownloadDelegate.BindUObject( this, &UOpenDriveToMap::ConvertOSMInOpenDrive );
FileDownloader->StartDownload();
RoadType.Empty();
RoadMesh.Empty();
MeshesToSpawn.Empty();
ActorMeshList.Empty();
}
void UOpenDriveToMap::OpenFileDialog()
{
TArray<FString> OutFileNames;
void* ParentWindowPtr = FSlateApplication::Get().GetActiveTopLevelWindow()->GetNativeWindow()->GetOSWindowHandle();
IDesktopPlatform* DesktopPlatform = FDesktopPlatformModule::Get();
if (DesktopPlatform)
{
DesktopPlatform->OpenFileDialog(ParentWindowPtr, "Select xodr file", FPaths::ProjectDir(), FString(""), ".xodr", 1, OutFileNames);
}
for(FString& CurrentString : OutFileNames)
{
FilePath = CurrentString;
UE_LOG(LogCarlaToolsMapGenerator, Log, TEXT("FileObtained %s"), *CurrentString );
}
}
void UOpenDriveToMap::LoadMap()
{
FString FileContent;
UE_LOG(LogCarlaToolsMapGenerator, Log, TEXT("UOpenDriveToMap::LoadMap(): File to load %s"), *FilePath );
FFileHelper::LoadFileToString(FileContent, *FilePath);
std::string opendrive_xml = carla::rpc::FromLongFString(FileContent);
boost::optional<carla::road::Map> CarlaMap = carla::opendrive::OpenDriveParser::Load(opendrive_xml);
if (!CarlaMap.has_value())
{
UE_LOG(LogCarlaToolsMapGenerator, Error, TEXT("Invalid Map"));
}else
{
UE_LOG(LogCarlaToolsMapGenerator, Log, TEXT("Valid Map loaded"));
}
MapName = FPaths::GetCleanFilename(FilePath);
MapName.RemoveFromEnd(".xodr", ESearchCase::Type::IgnoreCase);
UE_LOG(LogCarlaToolsMapGenerator, Warning, TEXT("MapName %s"), *MapName);
GenerateAll(CarlaMap);
}
void UOpenDriveToMap::GenerateAll(const boost::optional<carla::road::Map>& CarlaMap )
{
if (!CarlaMap.has_value())
{
UE_LOG(LogCarlaToolsMapGenerator, Error, TEXT("Invalid Map"));
}else
{
GenerateRoadMesh(CarlaMap);
GenerateSpawnPoints(CarlaMap);
}
}
void UOpenDriveToMap::GenerateRoadMesh( const boost::optional<carla::road::Map>& CarlaMap )
{
opg_parameters.vertex_distance = 0.5f;
opg_parameters.vertex_width_resolution = 8.0f;
opg_parameters.simplification_percentage = 15.0f;
double start = FPlatformTime::Seconds();
const auto Meshes = CarlaMap->GenerateOrderedChunkedMesh(opg_parameters);
double end = FPlatformTime::Seconds();
UE_LOG(LogCarlaToolsMapGenerator, Log, TEXT(" GenerateOrderedChunkedMesh code executed in %f seconds. Simplification percentage is %f"), end - start, opg_parameters.simplification_percentage);
start = FPlatformTime::Seconds();
for (const auto &PairMap : Meshes)
{
for( const auto &Mesh : PairMap.second )
{
if (!Mesh->GetVertices().size())
{
continue;
}
if (!Mesh->IsValid()) {
continue;
}
AProceduralMeshActor* TempActor = GetWorld()->SpawnActor<AProceduralMeshActor>();
UProceduralMeshComponent *TempPMC = TempActor->MeshComponent;
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);
RoadType.Add(LaneTypeToFString(PairMap.first));
RoadMesh.Add(TempPMC);
}
}
end = FPlatformTime::Seconds();
UE_LOG(LogCarlaToolsMapGenerator, Log, TEXT("Mesh spawnning and translation code executed in %f seconds."), end - start);
}
void UOpenDriveToMap::GenerateSpawnPoints( const boost::optional<carla::road::Map>& CarlaMap )
{
float SpawnersHeight = 300.f;
const auto Waypoints = CarlaMap->GenerateWaypointsOnRoadEntries();
for (const auto &Wp : Waypoints)
{
const FTransform Trans = CarlaMap->ComputeTransform(Wp);
AVehicleSpawnPoint *Spawner = GetWorld()->SpawnActor<AVehicleSpawnPoint>();
Spawner->SetActorRotation(Trans.GetRotation());
Spawner->SetActorLocation(Trans.GetTranslation() + FVector(0.f, 0.f, SpawnersHeight));
}
}
UStaticMesh* UOpenDriveToMap::CreateStaticMeshAsset( UProceduralMeshComponent* ProcMeshComp, int32 MeshIndex, FString FolderName )
{
FMeshDescription MeshDescription = BuildMeshDescription(ProcMeshComp);
IPlatformFile& PlatformFile = FPlatformFileManager::Get().GetPlatformFile();
// If we got some valid data.
if (MeshDescription.Polygons().Num() > 0)
{
FString MeshName = *(FolderName + FString::FromInt(MeshIndex) );
FString PackageName = "/Game/CustomMaps/" + MapName + "/Static/" + FolderName + "/" + MeshName;
if( !PlatformFile.DirectoryExists(*PackageName) )
{
PlatformFile.CreateDirectory(*PackageName);
}
// Then find/create it.
UPackage* Package = CreatePackage(*PackageName);
check(Package);
// Create StaticMesh object
UStaticMesh* StaticMesh = NewObject<UStaticMesh>(Package, *MeshName, RF_Public | RF_Standalone);
StaticMesh->InitResources();
StaticMesh->LightingGuid = FGuid::NewGuid();
// Add source to new StaticMesh
FStaticMeshSourceModel& SrcModel = StaticMesh->AddSourceModel();
SrcModel.BuildSettings.bRecomputeNormals = false;
SrcModel.BuildSettings.bRecomputeTangents = false;
SrcModel.BuildSettings.bRemoveDegenerates = false;
SrcModel.BuildSettings.bUseHighPrecisionTangentBasis = false;
SrcModel.BuildSettings.bUseFullPrecisionUVs = false;
SrcModel.BuildSettings.bGenerateLightmapUVs = true;
SrcModel.BuildSettings.SrcLightmapIndex = 0;
SrcModel.BuildSettings.DstLightmapIndex = 1;
StaticMesh->CreateMeshDescription(0, MoveTemp(MeshDescription));
StaticMesh->CommitMeshDescription(0);
//// SIMPLE COLLISION
if (!ProcMeshComp->bUseComplexAsSimpleCollision )
{
StaticMesh->CreateBodySetup();
UBodySetup* NewBodySetup = StaticMesh->BodySetup;
NewBodySetup->BodySetupGuid = FGuid::NewGuid();
NewBodySetup->AggGeom.ConvexElems = ProcMeshComp->ProcMeshBodySetup->AggGeom.ConvexElems;
NewBodySetup->bGenerateMirroredCollision = false;
NewBodySetup->bDoubleSidedGeometry = true;
NewBodySetup->CollisionTraceFlag = CTF_UseDefault;
NewBodySetup->CreatePhysicsMeshes();
}
//// MATERIALS
TSet<UMaterialInterface*> UniqueMaterials;
const int32 NumSections = ProcMeshComp->GetNumSections();
for (int32 SectionIdx = 0; SectionIdx < NumSections; SectionIdx++)
{
FProcMeshSection *ProcSection =
ProcMeshComp->GetProcMeshSection(SectionIdx);
UMaterialInterface *Material = ProcMeshComp->GetMaterial(SectionIdx);
UniqueMaterials.Add(Material);
}
// Copy materials to new mesh
for (auto* Material : UniqueMaterials)
{
StaticMesh->StaticMaterials.Add(FStaticMaterial(Material));
}
//Set the Imported version before calling the build
StaticMesh->ImportVersion = EImportStaticMeshVersion::LastVersion;
StaticMesh->Build(false);
StaticMesh->PostEditChange();
// Notify asset registry of new asset
FAssetRegistryModule::AssetCreated(StaticMesh);
UPackage::SavePackage(Package, StaticMesh, EObjectFlags::RF_Public | EObjectFlags::RF_Standalone, *MeshName, GError, nullptr, true, true, SAVE_NoError);
return StaticMesh;
}
return nullptr;
}
TArray<UStaticMesh*> UOpenDriveToMap::CreateStaticMeshAssets()
{
double start = FPlatformTime::Seconds();
double end = FPlatformTime::Seconds();
IPlatformFile& PlatformFile = FPlatformFileManager::Get().GetPlatformFile();
TArray<UStaticMesh*> StaticMeshes;
double BuildMeshDescriptionTime = 0.0f;
double PackgaesCreatingTime = 0.0f;
double MeshInitTime = 0.0f;
double MatAndCollInitTime = 0.0f;
double MeshBuildTime = 0.0f;
double PackSaveTime = 0.0f;
for (int i = 0; i < RoadMesh.Num(); ++i)
{
FString MeshName = RoadType[i] + FString::FromInt(i);
FString PackageName = "/Game/CustomMaps/" + MapName + "/Static/" + RoadType[i] + "/" + MeshName;
if (!PlatformFile.DirectoryExists(*PackageName))
{
PlatformFile.CreateDirectory(*PackageName);
}
UProceduralMeshComponent* ProcMeshComp = RoadMesh[i];
start = FPlatformTime::Seconds();
FMeshDescription MeshDescription = BuildMeshDescription(ProcMeshComp);
end = FPlatformTime::Seconds();
BuildMeshDescriptionTime += end - start;
// If we got some valid data.
if (MeshDescription.Polygons().Num() > 0)
{
start = FPlatformTime::Seconds();
// Then find/create it.
UPackage* Package = CreatePackage(*PackageName);
check(Package);
end = FPlatformTime::Seconds();
PackgaesCreatingTime += end - start;
start = FPlatformTime::Seconds();
// Create StaticMesh object
UStaticMesh* CurrentStaticMesh = NewObject<UStaticMesh>(Package, *MeshName, RF_Public | RF_Standalone);
CurrentStaticMesh->InitResources();
CurrentStaticMesh->LightingGuid = FGuid::NewGuid();
// Add source to new StaticMesh
FStaticMeshSourceModel& SrcModel = CurrentStaticMesh->AddSourceModel();
SrcModel.BuildSettings.bRecomputeNormals = false;
SrcModel.BuildSettings.bRecomputeTangents = false;
SrcModel.BuildSettings.bRemoveDegenerates = false;
SrcModel.BuildSettings.bUseHighPrecisionTangentBasis = false;
SrcModel.BuildSettings.bUseFullPrecisionUVs = false;
SrcModel.BuildSettings.bGenerateLightmapUVs = true;
SrcModel.BuildSettings.SrcLightmapIndex = 0;
SrcModel.BuildSettings.DstLightmapIndex = 1;
CurrentStaticMesh->CreateMeshDescription(0, MoveTemp(MeshDescription));
CurrentStaticMesh->CommitMeshDescription(0);
end = FPlatformTime::Seconds();
MeshInitTime += end - start;
start = FPlatformTime::Seconds();
//// SIMPLE COLLISION
if (!ProcMeshComp->bUseComplexAsSimpleCollision)
{
CurrentStaticMesh->CreateBodySetup();
UBodySetup* NewBodySetup = CurrentStaticMesh->BodySetup;
NewBodySetup->BodySetupGuid = FGuid::NewGuid();
NewBodySetup->AggGeom.ConvexElems = ProcMeshComp->ProcMeshBodySetup->AggGeom.ConvexElems;
NewBodySetup->bGenerateMirroredCollision = false;
NewBodySetup->bDoubleSidedGeometry = true;
NewBodySetup->CollisionTraceFlag = CTF_UseDefault;
NewBodySetup->CreatePhysicsMeshes();
}
//// MATERIALS
TSet<UMaterialInterface*> UniqueMaterials;
const int32 NumSections = ProcMeshComp->GetNumSections();
for (int32 SectionIdx = 0; SectionIdx < NumSections; SectionIdx++)
{
FProcMeshSection* ProcSection =
ProcMeshComp->GetProcMeshSection(SectionIdx);
UMaterialInterface* Material = ProcMeshComp->GetMaterial(SectionIdx);
UniqueMaterials.Add(Material);
}
// Copy materials to new mesh
for (auto* Material : UniqueMaterials)
{
CurrentStaticMesh->StaticMaterials.Add(FStaticMaterial(Material));
}
end = FPlatformTime::Seconds();
MatAndCollInitTime += end - start;
start = FPlatformTime::Seconds();
//Set the Imported version before calling the build
CurrentStaticMesh->ImportVersion = EImportStaticMeshVersion::LastVersion;
CurrentStaticMesh->Build(false);
CurrentStaticMesh->PostEditChange();
end = FPlatformTime::Seconds();
MeshBuildTime += end - start;
start = FPlatformTime::Seconds();
FString MeshName = *(RoadType[i] + FString::FromInt(i));
// Notify asset registry of new asset
FAssetRegistryModule::AssetCreated(CurrentStaticMesh);
UPackage::SavePackage(Package, CurrentStaticMesh, EObjectFlags::RF_Public | EObjectFlags::RF_Standalone, *MeshName, GError, nullptr, true, true, SAVE_NoError);
end = FPlatformTime::Seconds();
PackSaveTime += end - start;
StaticMeshes.Add( CurrentStaticMesh );
}
}
UE_LOG(LogCarlaToolsMapGenerator, Log, TEXT(" UOpenDriveToMap::CreateStaticMeshAssets total time in BuildMeshDescriptionTime %f. Time per mesh %f"), BuildMeshDescriptionTime, BuildMeshDescriptionTime/ RoadMesh.Num());
UE_LOG(LogCarlaToolsMapGenerator, Log, TEXT(" UOpenDriveToMap::CreateStaticMeshAssets total time in PackgaesCreatingTime %f. Time per mesh %f"), PackgaesCreatingTime, PackgaesCreatingTime / RoadMesh.Num());
UE_LOG(LogCarlaToolsMapGenerator, Log, TEXT(" UOpenDriveToMap::CreateStaticMeshAssets total time in MeshInitTime %f. Time per mesh %f"), MeshInitTime, MeshInitTime / RoadMesh.Num());
UE_LOG(LogCarlaToolsMapGenerator, Log, TEXT(" UOpenDriveToMap::CreateStaticMeshAssets total time in MatAndCollInitTime %f. Time per mesh %f"), MatAndCollInitTime, MatAndCollInitTime / RoadMesh.Num());
UE_LOG(LogCarlaToolsMapGenerator, Log, TEXT(" UOpenDriveToMap::CreateStaticMeshAssets total time in MeshBuildTime %f. Time per mesh %f"), MeshBuildTime, MeshBuildTime / RoadMesh.Num());
UE_LOG(LogCarlaToolsMapGenerator, Log, TEXT(" UOpenDriveToMap::CreateStaticMeshAssets total time in PackSaveTime %f. Time per mesh %f"), PackSaveTime, PackSaveTime / RoadMesh.Num());
return StaticMeshes;
}
void UOpenDriveToMap::SaveMap()
{
double start = FPlatformTime::Seconds();
MeshesToSpawn = CreateStaticMeshAssets();
double end = FPlatformTime::Seconds();
UE_LOG(LogCarlaToolsMapGenerator, Log, TEXT(" Meshes created static mesh code executed in %f seconds."), end - start);
for (auto CurrentActor : ActorMeshList)
{
CurrentActor->Destroy();
}
start = FPlatformTime::Seconds();
for (auto CurrentMesh : MeshesToSpawn)
{
AStaticMeshActor* TempActor = GetWorld()->SpawnActor<AStaticMeshActor>();
// Build mesh from source
TempActor->GetStaticMeshComponent()->SetStaticMesh(CurrentMesh);
TempActor->SetActorLabel(FString("SM_") + CurrentMesh->GetName());
}
end = FPlatformTime::Seconds();
UE_LOG(LogCarlaToolsMapGenerator, Log, TEXT(" Spawning Static Meshes code executed in %f seconds."), end - start);
}

View File

@ -0,0 +1,83 @@
// Copyright (c) 2017 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 "CoreMinimal.h"
#include "Blueprint/UserWidget.h"
#include "ProceduralMeshComponent.h"
#include <compiler/disable-ue4-macros.h>
#include <boost/optional.hpp>
#include <carla/road/Map.h>
#include <compiler/enable-ue4-macros.h>
#include "OpenDriveToMap.generated.h"
class UProceduralMeshComponent;
class UCustomFileDownloader;
/**
*
*/
UCLASS()
class CARLATOOLS_API UOpenDriveToMap : public UUserWidget
{
GENERATED_BODY()
public:
UFUNCTION()
void ConvertOSMInOpenDrive();
UPROPERTY( meta = (BindWidget) )
class UButton* StartButton;
UPROPERTY(meta = (BindWidget))
class UButton* SaveButton;
UPROPERTY(EditAnywhere, BlueprintReadWrite, Category="File")
FString FilePath;
UPROPERTY(EditAnywhere, BlueprintReadWrite, Category="File")
FString MapName;
UPROPERTY( EditAnywhere, BlueprintReadWrite, Category="Settings" )
FString Url;
protected:
virtual void NativeConstruct() override;
virtual void NativeDestruct() override;
UFUNCTION( BlueprintCallable )
void CreateMap();
UFUNCTION( BlueprintCallable )
void SaveMap();
private:
UFUNCTION()
void OpenFileDialog();
UFUNCTION()
void LoadMap();
void GenerateAll(const boost::optional<carla::road::Map>& CarlaMap);
void GenerateRoadMesh(const boost::optional<carla::road::Map>& CarlaMap);
void GenerateSpawnPoints(const boost::optional<carla::road::Map>& CarlaMap);
carla::rpc::OpendriveGenerationParameters opg_parameters;
UStaticMesh* CreateStaticMeshAsset(UProceduralMeshComponent* ProcMeshComp, int32 MeshIndex, FString FolderName);
TArray<UStaticMesh*> CreateStaticMeshAssets();
UPROPERTY()
UCustomFileDownloader* FileDownloader;
UPROPERTY()
TArray<AActor*> ActorMeshList;
UPROPERTY()
TArray<UStaticMesh*> MeshesToSpawn;
UPROPERTY()
TArray<FString> RoadType;
UPROPERTY()
TArray<UProceduralMeshComponent*> RoadMesh;
};

View File

@ -69,6 +69,8 @@ rem
set OSM2ODR_VSPROJECT_PATH=%INSTALLATION_DIR:/=\%osm2odr-visualstudio\
set OSM2ODR_SOURCE_PATH=%INSTALLATION_DIR:/=\%om2odr-source\
set OSM2ODR_INSTALL_PATH=%ROOT_PATH:/=\%PythonAPI\carla\dependencies\
set OSM2ODR__SERVER_INSTALL_PATH=%ROOT_PATH:/=\%Unreal\CarlaUE4\Plugins\Carla\CarlaDependencies
set CARLA_DEPENDENCIES_FOLDER=%ROOT_PATH:/=\%Unreal\CarlaUE4\Plugins\Carla\CarlaDependencies\
if %REMOVE_INTERMEDIATE% == true (
rem Remove directories
@ -107,6 +109,9 @@ if %BUILD_OSM2ODR% == true (
cmake --build . --config Release --target install | findstr /V "Up-to-date:"
if %errorlevel% neq 0 goto error_install
copy %OSM2ODR_INSTALL_PATH%\lib\osm2odr.lib %CARLA_DEPENDENCIES_FOLDER%\lib
copy %OSM2ODR_INSTALL_PATH%\include\OSM2ODR.h %CARLA_DEPENDENCIES_FOLDER%\include
)
goto success

View File

@ -105,6 +105,25 @@ if ${BUILD_OSM2ODR} ; then
ninja osm2odr
ninja install
mkdir -p ${OSM2ODR_SERVER_BUILD_FOLDER}
cd ${OSM2ODR_SERVER_BUILD_FOLDER}
LLVM_BASENAME=llvm-8.0
LLVM_INCLUDE="$UE4_ROOT/Engine/Source/ThirdParty/Linux/LibCxx/include/c++/v1"
LLVM_LIBPATH="$UE4_ROOT/Engine/Source/ThirdParty/Linux/LibCxx/lib/Linux/x86_64-unknown-linux-gnu"
cmake ${OSM2ODR_SOURCE_FOLDER} \
-G "Eclipse CDT4 - Ninja" \
-DCMAKE_CXX_FLAGS="-fPIC -std=c++14 -stdlib=libc++ -I${LLVM_INCLUDE} -L${LLVM_LIBPATH}" \
-DCMAKE_INSTALL_PREFIX=${LIBCARLA_INSTALL_SERVER_FOLDER} \
-DPROJ_INCLUDE_DIR=${CARLA_BUILD_FOLDER}/proj-install-server/include \
-DPROJ_LIBRARY=${CARLA_BUILD_FOLDER}/proj-install-server/lib/libproj.a \
-DXercesC_INCLUDE_DIR=${CARLA_BUILD_FOLDER}/xerces-c-3.2.3-install-server/include \
-DXercesC_LIBRARY=${CARLA_BUILD_FOLDER}/xerces-c-3.2.3-install-server/lib/libxerces-c.a
ninja osm2odr
ninja install
fi
log "Success!"
log " OSM2ODR Success!"

View File

@ -3,7 +3,7 @@ default: help
help:
@less ${CARLA_BUILD_TOOLS_FOLDER}/Linux.mk.help
launch: LibCarla.server.release
launch: LibCarla.server.release osm2odr
@${CARLA_BUILD_TOOLS_FOLDER}/BuildCarlaUE4.sh --build --launch $(ARGS)
launch-only:
@ -79,7 +79,7 @@ examples:
run-examples:
@for D in ${CARLA_EXAMPLES_FOLDER}/*; do [ -d "$${D}" ] && make -C $${D} run.only; done
CarlaUE4Editor: LibCarla.server.release
CarlaUE4Editor: LibCarla.server.release osm2odr
@${CARLA_BUILD_TOOLS_FOLDER}/BuildCarlaUE4.sh --build $(ARGS)
.PHONY: PythonAPI

View File

@ -190,15 +190,16 @@ echo %FILE_N% Installing Xercesc...
call "%INSTALLERS_DIR%install_xercesc.bat"^
--build-dir "%INSTALLATION_DIR%"
copy %INSTALLATION_DIR%\xerces-c-3.2.3-install\lib\xerces-c_3.lib %CARLA_PYTHON_DEPENDENCIES%\lib
copy %INSTALLATION_DIR%\xerces-c-3.2.3-install\lib\xerces-c_3.lib %CARLA_DEPENDENCIES_FOLDER%\lib
rem ============================================================================
rem -- Download and install Sqlite3 --------------------------------------------
rem ============================================================================
echo %FILE_N% Installing Sqlite3
call "%INSTALLERS_DIR%install_sqlite3.bat"^
--build-dir "%INSTALLATION_DIR%"
copy %INSTALLATION_DIR%\sqlite3-install\lib\sqlite3.lib %CARLA_PYTHON_DEPENDENCIES%\lib
copy %INSTALLATION_DIR%\sqlite3-install\lib\sqlite3.lib %CARLA_DEPENDENCIES_FOLDER%\lib
rem ============================================================================
rem -- Download and install PROJ --------------------------------------------
@ -208,6 +209,7 @@ echo %FILE_N% Installing PROJ
call "%INSTALLERS_DIR%install_proj.bat"^
--build-dir "%INSTALLATION_DIR%"
copy %INSTALLATION_DIR%\proj-install\lib\proj.lib %CARLA_PYTHON_DEPENDENCIES%\lib
copy %INSTALLATION_DIR%\proj-install\lib\proj.lib %CARLA_DEPENDENCIES_FOLDER%\lib
rem ============================================================================
rem -- Download and install Eigen ----------------------------------------------

View File

@ -380,9 +380,11 @@ XERCESC_REPO=https://archive.apache.org/dist/xerces/c/3/sources/xerces-c-${XERCE
XERCESC_SRC_DIR=${XERCESC_BASENAME}-source
XERCESC_INSTALL_DIR=${XERCESC_BASENAME}-install
XERCESC_INSTALL_SERVER_DIR=${XERCESC_BASENAME}-install-server
XERCESC_LIB=${XERCESC_INSTALL_DIR}/lib/libxerces-c.a
XERCESC_SERVER_LIB=${XERCESC_INSTALL_SERVER_DIR}/lib/libxerces-c.a
if [[ -d ${XERCESC_INSTALL_DIR} ]] ; then
if [[ -d ${XERCESC_INSTALL_DIR} && -d ${XERCESC_INSTALL_SERVER_DIR} ]] ; then
log "Xerces-c already installed."
else
log "Retrieving xerces-c."
@ -415,6 +417,23 @@ else
popd >/dev/null
mkdir -p ${XERCESC_INSTALL_SERVER_DIR}
pushd ${XERCESC_SRC_DIR}/build >/dev/null
cmake -G "Ninja" \
-DCMAKE_CXX_FLAGS="-std=c++14 -stdlib=libc++ -fPIC -w -I${LLVM_INCLUDE} -L${LLVM_LIBPATH}" \
-DCMAKE_INSTALL_PREFIX="../../${XERCESC_INSTALL_SERVER_DIR}" \
-DCMAKE_BUILD_TYPE=Release \
-DBUILD_SHARED_LIBS=OFF \
-Dtranscoder=gnuiconv \
-Dnetwork=OFF \
..
ninja
ninja install
popd >/dev/null
rm -Rf ${XERCESC_BASENAME}.tar.gz
rm -Rf ${XERCESC_SRC_DIR}
fi
@ -422,6 +441,9 @@ fi
mkdir -p ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/
cp ${XERCESC_LIB} ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/
mkdir -p ${LIBCARLA_INSTALL_SERVER_FOLDER}/lib/
cp -p ${XERCESC_SERVER_LIB} ${LIBCARLA_INSTALL_SERVER_FOLDER}/lib/
# ==============================================================================
# -- Get Eigen headers 3.1.0 (CARLA dependency) -------------------------------------
# ==============================================================================
@ -545,6 +567,7 @@ SQLITE_INSTALL_DIR=sqlite-install
SQLITE_INCLUDE_DIR=${PWD}/${SQLITE_INSTALL_DIR}/include
SQLITE_LIB=${PWD}/${SQLITE_INSTALL_DIR}/lib/libsqlite3.a
SQLITE_FULL_LIB=${PWD}/${SQLITE_INSTALL_DIR}/lib/
SQLITE_EXE=${PWD}/${SQLITE_INSTALL_DIR}/bin/sqlite3
if [[ -d ${SQLITE_INSTALL_DIR} ]] ; then
@ -561,7 +584,7 @@ else
pushd ${SQLITE_SOURCE_DIR} >/dev/null
export CFLAGS="-fPIC"
export CFLAGS="-fPIC -w"
./configure --prefix=${PWD}/../sqlite-install/
make
make install
@ -575,6 +598,9 @@ fi
mkdir -p ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/
cp ${SQLITE_LIB} ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/
mkdir -p ${LIBCARLA_INSTALL_SERVER_FOLDER}/lib/
cp -p -r ${SQLITE_FULL_LIB} ${LIBCARLA_INSTALL_SERVER_FOLDER}
# ==============================================================================
# -- Get and compile PROJ ------------------------------------------------------
# ==============================================================================
@ -585,10 +611,13 @@ PROJ_REPO=https://download.osgeo.org/proj/${PROJ_VERSION}.tar.gz
PROJ_TAR=${PROJ_VERSION}.tar.gz
PROJ_SRC_DIR=proj-src
PROJ_INSTALL_DIR=proj-install
PROJ_INSTALL_SERVER_DIR=proj-install-server
PROJ_INSTALL_DIR_FULL=${PWD}/${PROJ_INSTALL_DIR}
PROJ_INSTALL_SERVER_DIR_FULL=${PWD}/${PROJ_INSTALL_SERVER_DIR}
PROJ_LIB=${PROJ_INSTALL_DIR_FULL}/lib/libproj.a
PROJ_SERVER_LIB=${PROJ_INSTALL_SERVER_DIR_FULL}/lib/libproj.a
if [[ -d ${PROJ_INSTALL_DIR} ]] ; then
if [[ -d ${PROJ_INSTALL_DIR} && -d ${PROJ_INSTALL_SERVER_DIR_FULL} ]] ; then
log "PROJ already installed."
else
log "Retrieving PROJ"
@ -598,8 +627,8 @@ else
tar -xzf ${PROJ_TAR}
mv ${PROJ_VERSION} ${PROJ_SRC_DIR}
mkdir ${PROJ_SRC_DIR}/build
mkdir ${PROJ_INSTALL_DIR}
mkdir -p ${PROJ_SRC_DIR}/build
mkdir -p ${PROJ_INSTALL_DIR}
pushd ${PROJ_SRC_DIR}/build >/dev/null
@ -617,6 +646,24 @@ else
popd >/dev/null
mkdir -p ${PROJ_INSTALL_SERVER_DIR}
pushd ${PROJ_SRC_DIR}/build >/dev/null
cmake -G "Ninja" .. \
-DCMAKE_CXX_FLAGS="-std=c++14 -fPIC -stdlib=libc++ -I${LLVM_INCLUDE} -Wl,-L${LLVM_LIBPATH}" \
-DSQLITE3_INCLUDE_DIR=${SQLITE_INCLUDE_DIR} -DSQLITE3_LIBRARY=${SQLITE_LIB} \
-DEXE_SQLITE3=${SQLITE_EXE} \
-DENABLE_TIFF=OFF -DENABLE_CURL=OFF -DBUILD_SHARED_LIBS=OFF -DBUILD_PROJSYNC=OFF \
-DCMAKE_BUILD_TYPE=Release -DBUILD_PROJINFO=OFF \
-DBUILD_CCT=OFF -DBUILD_CS2CS=OFF -DBUILD_GEOD=OFF -DBUILD_GIE=OFF \
-DBUILD_PROJ=OFF -DBUILD_TESTING=OFF \
-DCMAKE_INSTALL_PREFIX=${PROJ_INSTALL_SERVER_DIR_FULL}
ninja
ninja install
popd >/dev/null
rm -Rf ${PROJ_TAR}
rm -Rf ${PROJ_SRC_DIR}
@ -624,6 +671,9 @@ fi
cp ${PROJ_LIB} ${LIBCARLA_INSTALL_CLIENT_FOLDER}/lib/
mkdir -p ${LIBCARLA_INSTALL_SERVER_FOLDER}/lib/
cp -p ${PROJ_SERVER_LIB} ${LIBCARLA_INSTALL_SERVER_FOLDER}/lib/
# ==============================================================================
# -- Get and compile patchelf --------------------------------------------------
# ==============================================================================

View File

@ -21,6 +21,7 @@ LIBCARLA_INSTALL_SERVER_FOLDER=${CARLAUE4_PLUGIN_ROOT_FOLDER}/CarlaDependencies
LIBCARLA_INSTALL_CLIENT_FOLDER=${CARLA_PYTHONAPI_SOURCE_FOLDER}/dependencies
OSM2ODR_BUILD_FOLDER=${CARLA_BUILD_FOLDER}/libosm2dr-build
OSM2ODR_SERVER_BUILD_FOLDER=${CARLA_BUILD_FOLDER}/libosm2dr-build-server
OSM2ODR_SOURCE_FOLDER=${CARLA_BUILD_FOLDER}/libosm2dr-source
CARLAUE4_PLUGIN_DEPS_FOLDER=${CARLAUE4_PLUGIN_ROOT_FOLDER}/CarlaDependencies

View File

@ -16,7 +16,7 @@ help:
import: server
@"${CARLA_BUILD_TOOLS_FOLDER}/Import.py" $(ARGS)
CarlaUE4Editor: LibCarla
CarlaUE4Editor: LibCarla osm2odr
@"${CARLA_BUILD_TOOLS_FOLDER}/BuildCarlaUE4.bat" --build $(ARGS)
launch: CarlaUE4Editor

View File

@ -172,6 +172,7 @@ rem ============================================================================
:good_exit
echo %FILE_N% Exiting...
rem A return value used for checking for errors
copy %ZLIB_INSTALL_DIR%\lib\zlibstatic.lib %CARLA_DEPENDENCIES_FOLDER%\lib
endlocal & set install_zlib=%ZLIB_INSTALL_DIR%
exit /b 0