Aaron/digitaltwinssidewalks (#6430)
* 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 * Osm Renderer Tool dummy version * Server creates SVG files when client request it * SVG creation and rasterization - libraries integration * Server size working * Added Simplify to LibCarla, Added timers to measure time generation. Add mesh deformation during road creation. * Fixed mesh format translations * Trying to paint bitmap into the UTexture * Bitmap sent and drawn in widget texture with bugs * Map bitmap shown on widget * Concated meshes generated in the same lane to avoid errors during simplification * Navigation added to widget * 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 * Added in separate thread junctions generation * Started dynamic database creation * Dynamic database creation temporally removed * First step of merge. Coords of bottom left corner and top right corner * Libraries added to build system * Git ignore for osmrenderer to avoid ThirdParties directory to be tracked * Lat and Lon coords for corners sent from server to client * Transformed to local coords meshes' vertices' coords * Coords format error fixed * Saving xodr and osm files inside of OpenDrive folder * Widget fixed * UI design improved * WIP Windows build system for osm-world-renderer * Socket implementation replaced by boost asio framework in osmrenderer * Added multithreaded simplification of meshes * Build system adapted to wndows * Headers fixed to avoid windows specific heraders compilation * Remove warnings * Added widget to import building from houdini * Added origin latitude and longituda to OSM to OpenDRIVE conversion functions. Fixed Houdini importer widgets. * Add Houdini plugin download to the build system * Moved houdini blueprint. Houdini plugin now dowloads by default * Added houdini download for windows * OpenDriveToMap Now is a UOBject instead of widget * Added Lane mark generation. * Roads materials and distance field scale set to 0 * M_PI macro fixed for windows osm-renderer build system * Added Lane Marking generation * Fixed compilation issue related with std pair non copyable lane * Fix bug where different lanes were concating. Fix bug where end of roadmark was creating an artifact * Lanes Marks material assignation * Fix compilation issue and reading from not valid memory crash * Middle Lane mark duplication bug fixed - temp solution * Added bumps along road * Adding marchingcubes library and added to create junctions * Added junctions generations using marching cube and smoothed * Fixed linux compilation and removed couple warnings * Using previous algorithim for two road connections * Code cleanup * Remove debug state * Format Files * Format third parties files * Spaces removal * Fix code format * Modified workflow for side walks * Added check for traffic lights and default materials for sidewalks * Change build osm script hash * Fix code format * changed buildosm2odr hash * Updated has * Format fix --------- Co-authored-by: aollero <aollero@cvc.uab.cat> Co-authored-by: aollero <adriollero@gmail.com> Co-authored-by: Axel <axellopez92@outlook.com>
This commit is contained in:
parent
07bbfe1fcc
commit
1a908dd936
|
@ -289,8 +289,7 @@ namespace geom {
|
|||
|
||||
Mesh& Mesh::ConcatMesh(const Mesh& rhs, int num_vertices_to_link) {
|
||||
|
||||
if (!rhs.IsValid())
|
||||
{
|
||||
if (!rhs.IsValid()){
|
||||
return *this += rhs;
|
||||
}
|
||||
const size_t v_num = GetVerticesNum();
|
||||
|
|
|
@ -0,0 +1,66 @@
|
|||
// 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 <memory>
|
||||
#include <vector>
|
||||
|
||||
#include <carla/geom/Mesh.h>
|
||||
#include <carla/road/Road.h>
|
||||
#include <carla/road/LaneSection.h>
|
||||
#include <carla/road/Lane.h>
|
||||
#include <carla/rpc/OpendriveGenerationParameters.h>
|
||||
|
||||
namespace carla {
|
||||
namespace geom {
|
||||
namespace deformation {
|
||||
inline float GetZPosInDeformation(float posx, float posy){
|
||||
// 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));
|
||||
}
|
||||
|
||||
inline float GetBumpDeformation(float posx, float posy){
|
||||
const float A3 = 0.15f;
|
||||
float bumpsoffset = 0;
|
||||
|
||||
const float constraintX = 15.0f;
|
||||
const float constraintY = 15.0f;
|
||||
|
||||
float BumpX = std::round(posx / constraintX);
|
||||
float BumpY = std::round(posy / constraintX);
|
||||
|
||||
BumpX *= constraintX;
|
||||
BumpY *= constraintY;
|
||||
|
||||
float DistanceToBumpOrigin = sqrt(pow(BumpX - posx, 2) + pow(BumpY - posy, 2) );
|
||||
float MaxDistance = 2;
|
||||
|
||||
if (DistanceToBumpOrigin <= MaxDistance) {
|
||||
bumpsoffset = abs((1.0f / MaxDistance) * DistanceToBumpOrigin * DistanceToBumpOrigin - MaxDistance);
|
||||
}
|
||||
|
||||
return A3 * bumpsoffset;
|
||||
}
|
||||
|
||||
|
||||
|
||||
} // namespace deformation
|
||||
} // namespace geom
|
||||
} // namespace carla
|
|
@ -9,6 +9,7 @@
|
|||
#include "carla/geom/Math.h"
|
||||
#include "carla/geom/Vector3D.h"
|
||||
#include "carla/road/MeshFactory.h"
|
||||
#include "carla/road/Deformation.h"
|
||||
#include "carla/road/element/LaneCrossingCalculator.h"
|
||||
#include "carla/road/element/RoadInfoCrosswalk.h"
|
||||
#include "carla/road/element/RoadInfoElevation.h"
|
||||
|
@ -1167,7 +1168,6 @@ namespace road {
|
|||
road_out_mesh_list[pair.first] = std::move(pair.second);
|
||||
}
|
||||
}
|
||||
|
||||
});
|
||||
workers.push_back(std::move(neworker));
|
||||
}
|
||||
|
@ -1221,38 +1221,7 @@ namespace road {
|
|||
|
||||
return road_out_mesh_list;
|
||||
}
|
||||
std::vector<std::pair<geom::Vector3D, std::string>> Map::GetTreesPosition(
|
||||
float distancebetweentrees,
|
||||
float distancefromdrivinglineborder) const {
|
||||
|
||||
std::vector<std::pair<geom::Vector3D, std::string>> positions;
|
||||
for (auto &&pair : _data.GetRoads()) {
|
||||
const auto &road = pair.second;
|
||||
if (!road.IsJunction()) {
|
||||
for (auto &&lane_section : road.GetLaneSections()) {
|
||||
const auto min_lane = lane_section.GetLanes().begin()->first == 0 ?
|
||||
1 : lane_section.GetLanes().begin()->first;
|
||||
const auto max_lane = lane_section.GetLanes().rbegin()->first == 0 ?
|
||||
-1 : lane_section.GetLanes().rbegin()->first;
|
||||
const road::Lane* lane = lane_section.GetLane(min_lane);
|
||||
if( lane ) {
|
||||
double s_current = lane_section.GetDistance();
|
||||
const double s_end = lane_section.GetDistance() + lane_section.GetLength();
|
||||
while(s_current < s_end){
|
||||
const auto edges = lane->GetCornerPositions(s_current, 0);
|
||||
geom::Vector3D director = edges.second - edges.first;
|
||||
geom::Vector3D treeposition = edges.first - director.MakeUnitVector() * distancefromdrivinglineborder;
|
||||
const carla::road::element::RoadInfoSpeed* roadinfo = lane->GetInfo<carla::road::element::RoadInfoSpeed>(s_current);
|
||||
positions.push_back(std::make_pair(treeposition,roadinfo->GetType()));
|
||||
s_current += distancebetweentrees;
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
return positions;
|
||||
}
|
||||
geom::Mesh Map::GetAllCrosswalkMesh() const {
|
||||
geom::Mesh out_mesh;
|
||||
|
||||
|
@ -1325,41 +1294,42 @@ namespace road {
|
|||
return returning;
|
||||
}
|
||||
|
||||
inline float Map::GetZPosInDeformation(float posx, float posy) const {
|
||||
// Amplitud
|
||||
const float A1 = 0.3f;
|
||||
const float A2 = 0.5f;
|
||||
const float A3 = 0.15f;
|
||||
// Fases
|
||||
const float F1 = 100.0;
|
||||
const float F2 = -1500.0;
|
||||
// Modifiers
|
||||
const float Kx1 = 0.035f;
|
||||
const float Kx2 = 0.02f;
|
||||
std::vector<std::pair<geom::Vector3D, std::string>> Map::GetTreesPosition(
|
||||
float distancebetweentrees,
|
||||
float distancefromdrivinglineborder) const {
|
||||
|
||||
const float Ky1 = -0.08f;
|
||||
const float Ky2 = 0.05f;
|
||||
std::vector<std::pair<geom::Vector3D, std::string>> positions;
|
||||
for (auto &&pair : _data.GetRoads()) {
|
||||
const auto &road = pair.second;
|
||||
if (!road.IsJunction()) {
|
||||
for (auto &&lane_section : road.GetLaneSections()) {
|
||||
const auto min_lane = lane_section.GetLanes().begin()->first == 0 ?
|
||||
1 : lane_section.GetLanes().begin()->first;
|
||||
const auto max_lane = lane_section.GetLanes().rbegin()->first == 0 ?
|
||||
-1 : lane_section.GetLanes().rbegin()->first;
|
||||
const road::Lane* lane = lane_section.GetLane(min_lane);
|
||||
if( lane ) {
|
||||
double s_current = lane_section.GetDistance();
|
||||
const double s_end = lane_section.GetDistance() + lane_section.GetLength();
|
||||
while(s_current < s_end){
|
||||
const auto edges = lane->GetCornerPositions(s_current, 0);
|
||||
geom::Vector3D director = edges.second - edges.first;
|
||||
geom::Vector3D treeposition = edges.first - director.MakeUnitVector() * distancefromdrivinglineborder;
|
||||
const carla::road::element::RoadInfoSpeed* roadinfo = lane->GetInfo<carla::road::element::RoadInfoSpeed>(s_current);
|
||||
positions.push_back(std::make_pair(treeposition,roadinfo->GetType()));
|
||||
s_current += distancebetweentrees;
|
||||
}
|
||||
|
||||
float bumpsoffset = 0;
|
||||
|
||||
const float constraintX = 15.0f;
|
||||
const float constraintY = 15.0f;
|
||||
|
||||
float BumpX = std::round(posx / constraintX);
|
||||
float BumpY = std::round(posy / constraintX);
|
||||
|
||||
BumpX *= constraintX;
|
||||
BumpY *= constraintY;
|
||||
|
||||
float DistanceToBumpOrigin = sqrt(pow(BumpX - posx, 2) + pow(BumpY - posy, 2) );
|
||||
float MaxDistance = 2;
|
||||
if (DistanceToBumpOrigin <= MaxDistance) {
|
||||
bumpsoffset = abs((1.0f / MaxDistance) * DistanceToBumpOrigin * DistanceToBumpOrigin - MaxDistance);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
return positions;
|
||||
}
|
||||
|
||||
return A1 * sin((Kx1 * posx + Ky1 * posy + F1)) +
|
||||
A2 * sin((Kx2 * posx + Ky2 * posy + F2)) +
|
||||
A3 * bumpsoffset;
|
||||
inline float Map::GetZPosInDeformation(float posx, float posy) const {
|
||||
return geom::deformation::GetZPosInDeformation(posx, posy) +
|
||||
geom::deformation::GetBumpDeformation(posx,posy);
|
||||
}
|
||||
|
||||
std::map<road::Lane::LaneType, std::vector<std::unique_ptr<geom::Mesh>>>
|
||||
|
@ -1439,6 +1409,24 @@ namespace road {
|
|||
}
|
||||
|
||||
(*junction_out_mesh_list)[road::Lane::LaneType::Driving].push_back(std::move(pmesh));
|
||||
|
||||
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) {
|
||||
sidewalk_lane_meshes.push_back(mesh_factory.GenerateSidewalk(lane));
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
std::unique_ptr<geom::Mesh> sidewalk_mesh = std::make_unique<geom::Mesh>();
|
||||
for (auto& lane : sidewalk_lane_meshes) {
|
||||
*sidewalk_mesh += *lane;
|
||||
}
|
||||
(*junction_out_mesh_list)[road::Lane::LaneType::Sidewalk].push_back(std::move(sidewalk_mesh));
|
||||
} else {
|
||||
std::vector<std::unique_ptr<geom::Mesh>> lane_meshes;
|
||||
std::vector<std::unique_ptr<geom::Mesh>> sidewalk_lane_meshes;
|
||||
|
@ -1452,7 +1440,7 @@ namespace road {
|
|||
lane_meshes.push_back(mesh_factory.GenerateTesselated(lane));
|
||||
}
|
||||
else {
|
||||
sidewalk_lane_meshes.push_back(mesh_factory.Generate(lane));
|
||||
sidewalk_lane_meshes.push_back(mesh_factory.GenerateSidewalk(lane));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
|
|
@ -12,6 +12,8 @@
|
|||
#include <carla/geom/Rtree.h>
|
||||
#include <carla/road/element/LaneMarking.h>
|
||||
#include <carla/road/element/RoadInfoMarkRecord.h>
|
||||
#include <carla/road/Map.h>
|
||||
#include <carla/road/Deformation.h>
|
||||
|
||||
namespace carla {
|
||||
namespace geom {
|
||||
|
@ -78,9 +80,7 @@ namespace geom {
|
|||
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
|
||||
|
@ -135,8 +135,7 @@ namespace geom {
|
|||
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)
|
||||
{
|
||||
for (int i = 0; i < vertices_in_width; ++i) {
|
||||
vertices.push_back(current_vertex);
|
||||
current_vertex = current_vertex + segments_size;
|
||||
}
|
||||
|
@ -148,7 +147,8 @@ namespace geom {
|
|||
// 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);
|
||||
std::pair<carla::geom::Vector3D, carla::geom::Vector3D> 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;
|
||||
|
||||
|
@ -160,6 +160,138 @@ namespace geom {
|
|||
}
|
||||
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 size_t number_of_rows = (vertices.size() / vertices_in_width);
|
||||
|
||||
for (size_t i = 0; i < (number_of_rows - 1); ++i) {
|
||||
for (size_t 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;
|
||||
std::vector<size_t> redirections;
|
||||
for (auto &&lane_pair : lane_section.GetLanes()) {
|
||||
auto it = std::find(redirections.begin(), redirections.end(), lane_pair.first);
|
||||
if ( it == redirections.end() ) {
|
||||
redirections.push_back(lane_pair.first);
|
||||
it = std::find(redirections.begin(), redirections.end(), lane_pair.first);
|
||||
}
|
||||
|
||||
size_t PosToAdd = it - redirections.begin();
|
||||
|
||||
Mesh out_mesh;
|
||||
if(lane_pair.second.GetType() == road::Lane::LaneType::Driving ){
|
||||
out_mesh += *GenerateTesselated(lane_pair.second);
|
||||
}else{
|
||||
out_mesh += *GenerateSidewalk(lane_pair.second);
|
||||
}
|
||||
|
||||
if( result[lane_pair.second.GetType()].size() <= PosToAdd ){
|
||||
result[lane_pair.second.GetType()].push_back(std::make_unique<Mesh>(out_mesh));
|
||||
} else {
|
||||
uint32_t verticesinwidth = 0;
|
||||
if(lane_pair.second.GetType() == road::Lane::LaneType::Driving) {
|
||||
verticesinwidth = vertices_in_width;
|
||||
}else if(lane_pair.second.GetType() == road::Lane::LaneType::Sidewalk){
|
||||
verticesinwidth = 4;
|
||||
}else{
|
||||
verticesinwidth = 2;
|
||||
}
|
||||
(result[lane_pair.second.GetType()][PosToAdd])->ConcatMesh(out_mesh, verticesinwidth);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
std::unique_ptr<Mesh> MeshFactory::GenerateSidewalk(const road::LaneSection &lane_section) const{
|
||||
Mesh out_mesh;
|
||||
for (auto &&lane_pair : lane_section.GetLanes()) {
|
||||
const double s_start = lane_pair.second.GetDistance() + EPSILON;
|
||||
const double s_end = lane_pair.second.GetDistance() + lane_pair.second.GetLength() - EPSILON;
|
||||
out_mesh += *GenerateSidewalk(lane_pair.second, s_start, s_end);
|
||||
}
|
||||
return std::make_unique<Mesh>(out_mesh);
|
||||
}
|
||||
std::unique_ptr<Mesh> MeshFactory::GenerateSidewalk(const road::Lane &lane) const{
|
||||
const double s_start = lane.GetDistance() + EPSILON;
|
||||
const double s_end = lane.GetDistance() + lane.GetLength() - EPSILON;
|
||||
return GenerateSidewalk(lane, s_start, s_end);
|
||||
}
|
||||
std::unique_ptr<Mesh> MeshFactory::GenerateSidewalk(
|
||||
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 = 4;
|
||||
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);
|
||||
edges.first.z += deformation::GetZPosInDeformation(edges.first.x, edges.first.y);
|
||||
edges.second.z += deformation::GetZPosInDeformation(edges.second.x, edges.second.y);
|
||||
geom::Vector3D low_vertex_first = edges.first - geom::Vector3D(0,0,1);
|
||||
geom::Vector3D low_vertex_second = edges.second - geom::Vector3D(0,0,1);
|
||||
vertices.push_back(low_vertex_first);
|
||||
vertices.push_back(edges.first);
|
||||
vertices.push_back(edges.second);
|
||||
vertices.push_back(low_vertex_second);
|
||||
|
||||
// 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) {
|
||||
std::pair<carla::geom::Vector3D, carla::geom::Vector3D> edges =
|
||||
lane.GetCornerPositions(s_end - MESH_EPSILON, road_param.extra_lane_width);
|
||||
|
||||
edges.first.z += deformation::GetZPosInDeformation(edges.first.x, edges.first.y);
|
||||
edges.second.z += deformation::GetZPosInDeformation(edges.second.x, edges.second.y);
|
||||
geom::Vector3D low_vertex_first = edges.first - geom::Vector3D(0,0,1);
|
||||
geom::Vector3D low_vertex_second = edges.second - geom::Vector3D(0,0,1);
|
||||
vertices.push_back(low_vertex_first);
|
||||
vertices.push_back(edges.first);
|
||||
vertices.push_back(edges.second);
|
||||
vertices.push_back(low_vertex_second);
|
||||
}
|
||||
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");
|
||||
|
@ -180,33 +312,6 @@ namespace geom {
|
|||
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;
|
||||
std::vector<size_t> redirections;
|
||||
for (auto &&lane_pair : lane_section.GetLanes()) {
|
||||
auto it = std::find(redirections.begin(), redirections.end(), lane_pair.first);
|
||||
if ( it == redirections.end() ) {
|
||||
redirections.push_back(lane_pair.first);
|
||||
it = std::find(redirections.begin(), redirections.end(), lane_pair.first);
|
||||
}
|
||||
|
||||
size_t PosToAdd = it - redirections.begin();
|
||||
|
||||
Mesh out_mesh = *GenerateTesselated(lane_pair.second);
|
||||
if( result[lane_pair.second.GetType()].size() <= PosToAdd ){
|
||||
result[lane_pair.second.GetType()].push_back(std::make_unique<Mesh>(out_mesh));
|
||||
} else {
|
||||
(result[lane_pair.second.GetType()][PosToAdd])->ConcatMesh(out_mesh, vertices_in_width);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
std::unique_ptr<Mesh> MeshFactory::GenerateWalls(const road::LaneSection &lane_section) const {
|
||||
Mesh out_mesh;
|
||||
|
||||
|
@ -377,7 +482,7 @@ std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> MeshFactory:
|
|||
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(
|
||||
mesh_uptr_list.insert(
|
||||
std::make_move_iterator(section_uptr_list.begin()),
|
||||
std::make_move_iterator(section_uptr_list.end()));
|
||||
}
|
||||
|
@ -399,7 +504,12 @@ std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> MeshFactory:
|
|||
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);
|
||||
Mesh lane_section_mesh;
|
||||
if(lane_pair.second.GetType() == road::Lane::LaneType::Driving ){
|
||||
lane_section_mesh += *GenerateTesselated(lane_pair.second, s_current, s_until);
|
||||
}else{
|
||||
lane_section_mesh += *GenerateSidewalk(lane_pair.second, s_current, s_until);
|
||||
}
|
||||
|
||||
auto it = std::find(redirections.begin(), redirections.end(), lane_pair.first);
|
||||
if (it == redirections.end()) {
|
||||
|
@ -411,14 +521,28 @@ std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> MeshFactory:
|
|||
if (mesh_uptr_list[lane_pair.second.GetType()].size() <= PosToAdd) {
|
||||
mesh_uptr_list[lane_pair.second.GetType()].push_back(std::make_unique<Mesh>(lane_section_mesh));
|
||||
} else {
|
||||
(mesh_uptr_list[lane_pair.second.GetType()][PosToAdd])->ConcatMesh(lane_section_mesh, vertices_in_width);
|
||||
uint32_t verticesinwidth = 0;
|
||||
if(lane_pair.second.GetType() == road::Lane::LaneType::Driving) {
|
||||
verticesinwidth = vertices_in_width;
|
||||
}else if(lane_pair.second.GetType() == road::Lane::LaneType::Sidewalk){
|
||||
verticesinwidth = 4;
|
||||
}else{
|
||||
verticesinwidth = 2;
|
||||
}
|
||||
(mesh_uptr_list[lane_pair.second.GetType()][PosToAdd])->ConcatMesh(lane_section_mesh, verticesinwidth);
|
||||
}
|
||||
}
|
||||
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);
|
||||
Mesh lane_section_mesh;
|
||||
if(lane_pair.second.GetType() == road::Lane::LaneType::Driving ){
|
||||
lane_section_mesh += *GenerateTesselated(lane_pair.second, s_current, s_end);
|
||||
}else{
|
||||
lane_section_mesh += *GenerateSidewalk(lane_pair.second, s_current, s_end);
|
||||
}
|
||||
|
||||
auto it = std::find(redirections.begin(), redirections.end(), lane_pair.first);
|
||||
if (it == redirections.end()) {
|
||||
redirections.push_back(lane_pair.first);
|
||||
|
@ -430,7 +554,15 @@ std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> MeshFactory:
|
|||
if (mesh_uptr_list[lane_pair.second.GetType()].size() <= PosToAdd) {
|
||||
mesh_uptr_list[lane_pair.second.GetType()].push_back(std::make_unique<Mesh>(lane_section_mesh));
|
||||
} else {
|
||||
(mesh_uptr_list[lane_pair.second.GetType()][PosToAdd])->ConcatMesh(lane_section_mesh, vertices_in_width);
|
||||
uint32_t verticesinwidth = 0;
|
||||
if(lane_pair.second.GetType() == road::Lane::LaneType::Driving) {
|
||||
verticesinwidth = vertices_in_width;
|
||||
}else if(lane_pair.second.GetType() == road::Lane::LaneType::Sidewalk){
|
||||
verticesinwidth = 4;
|
||||
}else{
|
||||
verticesinwidth = 2;
|
||||
}
|
||||
(mesh_uptr_list[lane_pair.second.GetType()][PosToAdd])->ConcatMesh(lane_section_mesh, verticesinwidth);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -530,11 +662,11 @@ std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> MeshFactory:
|
|||
void MeshFactory::GenerateAllOrderedWithMaxLen(
|
||||
const road::Road &road,
|
||||
std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>>& roads
|
||||
) const
|
||||
{
|
||||
) const {
|
||||
|
||||
// Get road meshes
|
||||
std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> result = GenerateOrderedWithMaxLen(road);
|
||||
for (auto &pair_map : result)
|
||||
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;
|
||||
|
@ -548,7 +680,9 @@ std::map<road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>> MeshFactory:
|
|||
for (auto&& lane_section : road.GetLaneSections()) {
|
||||
for (auto&& lane : lane_section.GetLanes()) {
|
||||
if (lane.first != 0) {
|
||||
GenerateLaneMarksForNotCenterLine(lane_section, lane.second, inout);
|
||||
if(lane.second.GetType() == road::Lane::LaneType::Driving ){
|
||||
GenerateLaneMarksForNotCenterLine(lane_section, lane.second, inout);
|
||||
}
|
||||
} else {
|
||||
GenerateLaneMarksForCenterLine(road, lane_section, lane.second, inout);
|
||||
}
|
||||
|
|
|
@ -52,8 +52,12 @@ namespace geom {
|
|||
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,
|
||||
void GenerateLaneSectionOrdered(const road::LaneSection &lane_section,
|
||||
std::map<carla::road::Lane::LaneType , std::vector<std::unique_ptr<Mesh>>>& result ) const;
|
||||
|
||||
std::unique_ptr<Mesh> GenerateSidewalk(const road::LaneSection &lane_section) const;
|
||||
std::unique_ptr<Mesh> GenerateSidewalk(const road::Lane &lane) const;
|
||||
std::unique_ptr<Mesh> GenerateSidewalk(const road::Lane &lane, const double s_start, const double s_end) const;
|
||||
// -- Walls --
|
||||
|
||||
/// Genrates a mesh representing a wall on the road corners to avoid
|
||||
|
@ -100,7 +104,7 @@ 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;
|
||||
|
||||
|
|
|
@ -32,9 +32,10 @@ void UCustomFileDownloader::ConvertOSMInOpenDrive(FString FilePath)
|
|||
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);
|
||||
|
||||
osm2odr::OSM2ODRSettings settings;
|
||||
std::string OpenDriveFile = osm2odr::ConvertOSMToOpenDRIVE(OsmFile, settings);
|
||||
|
||||
FilePath.RemoveFromEnd(".osm", ESearchCase::Type::IgnoreCase);
|
||||
FilePath += ".xodr";
|
||||
|
|
|
@ -41,9 +41,15 @@ void UTrafficLightComponent::InitializeSign(const carla::road::Map &Map)
|
|||
if(lane == 0)
|
||||
continue;
|
||||
|
||||
auto signal_waypoint = Map.GetWaypoint(
|
||||
RoadId, lane, SignalReference->GetS()).get();
|
||||
|
||||
carla::road::element::Waypoint signal_waypoint;
|
||||
boost::optional<carla::road::element::Waypoint> opt_signal_waypoint = Map.GetWaypoint(
|
||||
RoadId, lane, SignalReference->GetS());
|
||||
if(opt_signal_waypoint){
|
||||
signal_waypoint = opt_signal_waypoint.get();
|
||||
}else{
|
||||
UE_LOG(LogCarla, Error, TEXT("signal_waypoint is not valid") );
|
||||
continue;
|
||||
}
|
||||
// Prevent adding the bounding box inside the intersection
|
||||
if (Map.IsJunction(RoadId)) {
|
||||
auto predecessors = Map.GetPredecessors(signal_waypoint);
|
||||
|
|
Binary file not shown.
Binary file not shown.
|
@ -222,6 +222,7 @@ void UOpenDriveToMap::GenerateRoadMesh( const boost::optional<carla::road::Map>&
|
|||
}
|
||||
|
||||
AProceduralMeshActor* TempActor = GetWorld()->SpawnActor<AProceduralMeshActor>();
|
||||
|
||||
TempActor->SetActorLabel(FString("SM_Lane_") + FString::FromInt(index));
|
||||
|
||||
UProceduralMeshComponent *TempPMC = TempActor->MeshComponent;
|
||||
|
@ -229,9 +230,16 @@ void UOpenDriveToMap::GenerateRoadMesh( const boost::optional<carla::road::Map>&
|
|||
TempPMC->bUseComplexAsSimpleCollision = true;
|
||||
TempPMC->SetCollisionEnabled(ECollisionEnabled::QueryAndPhysics);
|
||||
|
||||
if(DefaultRoadMaterial)
|
||||
if(DefaultRoadMaterial && PairMap.first == carla::road::Lane::LaneType::Driving)
|
||||
{
|
||||
TempPMC->SetMaterial(0, DefaultRoadMaterial);
|
||||
|
||||
TempActor->SetActorLabel(FString("SM_DrivingLane_") + FString::FromInt(index));
|
||||
}
|
||||
if(DefaultSidewalksMaterial && PairMap.first == carla::road::Lane::LaneType::Sidewalk)
|
||||
{
|
||||
TempPMC->SetMaterial(0, DefaultSidewalksMaterial);
|
||||
TempActor->SetActorLabel(FString("SM_Sidewalk_") + FString::FromInt(index));
|
||||
}
|
||||
FVector MeshCentroid = FVector(0,0,0);
|
||||
for( auto Vertex : Mesh->GetVertices() )
|
||||
{
|
||||
|
|
|
@ -47,17 +47,20 @@ public:
|
|||
UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Settings")
|
||||
FVector2D OriginGeoCoordinates;
|
||||
|
||||
UPROPERTY( EditAnywhere, BlueprintReadWrite, Category="Settings" )
|
||||
float DistanceBetweenTrees = 50.0f;
|
||||
UPROPERTY( EditAnywhere, BlueprintReadWrite, Category="Settings" )
|
||||
float DistanceFromRoadEdge = 3.0f;
|
||||
|
||||
UPROPERTY(EditAnywhere, BlueprintReadWrite)
|
||||
UMaterialInstance* DefaultRoadMaterial;
|
||||
|
||||
UPROPERTY(EditAnywhere, BlueprintReadWrite)
|
||||
UMaterialInstance* DefaultLaneMarksMaterial;
|
||||
|
||||
UPROPERTY(EditAnywhere, BlueprintReadWrite)
|
||||
UMaterialInstance* DefaultSidewalksMaterial;
|
||||
|
||||
UPROPERTY( EditAnywhere, BlueprintReadWrite, Category="Settings" )
|
||||
float DistanceBetweenTrees = 50.0f;
|
||||
UPROPERTY( EditAnywhere, BlueprintReadWrite, Category="Settings" )
|
||||
float DistanceFromRoadEdge = 3.0f;
|
||||
|
||||
protected:
|
||||
|
||||
UFUNCTION( BlueprintCallable )
|
||||
|
@ -96,5 +99,4 @@ private:
|
|||
TArray<FString> RoadType;
|
||||
UPROPERTY()
|
||||
TArray<UProceduralMeshComponent*> RoadMesh;
|
||||
|
||||
};
|
||||
|
|
|
@ -20,7 +20,7 @@ set USAGE_STRING=Usage: %FILE_N% [-h^|--help] [--rebuild] [--build] [--clean] [-
|
|||
set REMOVE_INTERMEDIATE=false
|
||||
set BUILD_OSM2ODR=false
|
||||
set GIT_PULL=true
|
||||
set CURRENT_OSM2ODR_COMMIT=ee0c2b9241fef5365a6bc044ac82e6580b8ce936
|
||||
set CURRENT_OSM2ODR_COMMIT=03f2f1de6dcbfde41f2af464829d96b582fc2909
|
||||
set OSM2ODR_BRANCH=carla_osm2odr
|
||||
set OSM2ODR_REPO=https://github.com/carla-simulator/sumo.git
|
||||
|
||||
|
|
|
@ -14,7 +14,7 @@ END
|
|||
REMOVE_INTERMEDIATE=false
|
||||
BUILD_OSM2ODR=false
|
||||
GIT_PULL=true
|
||||
CURRENT_OSM2ODR_COMMIT=ee0c2b9241fef5365a6bc044ac82e6580b8ce936
|
||||
CURRENT_OSM2ODR_COMMIT=03f2f1de6dcbfde41f2af464829d96b582fc2909
|
||||
OSM2ODR_BRANCH=carla_osm2odr
|
||||
OSM2ODR_REPO=https://github.com/carla-simulator/sumo.git
|
||||
|
||||
|
|
Loading…
Reference in New Issue