Added spawnning for trees (#6367)

* Added spawnning for trees

* Set trees for designer

* Tag static mesh actor from road type

* Changed format of For
This commit is contained in:
Blyron 2023-04-13 13:00:15 +02:00 committed by GitHub
parent c3e5f9c019
commit 8be9fd22dd
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
9 changed files with 126 additions and 20 deletions

View File

@ -16,6 +16,7 @@
#include "carla/road/element/RoadInfoLaneOffset.h"
#include "carla/road/element/RoadInfoLaneWidth.h"
#include "carla/road/element/RoadInfoMarkRecord.h"
#include "carla/road/element/RoadInfoSpeed.h"
#include "carla/road/element/RoadInfoSignal.h"
#include "simplify/Simplify.h"
@ -1133,7 +1134,7 @@ namespace road {
return result;
}
std::map<road::Lane::LaneType , std::vector<std::unique_ptr<geom::Mesh>>>
std::map<road::Lane::LaneType , std::vector<std::unique_ptr<geom::Mesh>>>
Map::GenerateOrderedChunkedMesh( const rpc::OpendriveGenerationParameters& params) const
{
@ -1154,7 +1155,7 @@ namespace road {
for ( size_t i = 0; i < num_threads; ++i ) {
std::thread neworker(
[this, &write_mutex, &mesh_factory, &road_out_mesh_list, i, num_roads_per_thread]() {
std::map<road::Lane::LaneType, std::vector<std::unique_ptr<geom::Mesh>>> Current =
std::map<road::Lane::LaneType, std::vector<std::unique_ptr<geom::Mesh>>> Current =
std::move(GenerateRoadsMultithreaded(mesh_factory, i, num_roads_per_thread));
std::lock_guard<std::mutex> guard(write_mutex);
for ( auto&& pair : Current ) {
@ -1220,7 +1221,38 @@ 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;
@ -1326,20 +1358,20 @@ namespace road {
}
return A1 * sin((Kx1 * posx + Ky1 * posy + F1)) +
A2 * sin((Kx2 * posx + Ky2 * posy + F2)) +
A2 * sin((Kx2 * posx + Ky2 * posy + F2)) +
A3 * bumpsoffset;
}
std::map<road::Lane::LaneType, std::vector<std::unique_ptr<geom::Mesh>>>
Map::GenerateRoadsMultithreaded( const carla::geom::MeshFactory& mesh_factory,
const size_t index, const size_t number_of_roads_per_thread) const
std::map<road::Lane::LaneType, std::vector<std::unique_ptr<geom::Mesh>>>
Map::GenerateRoadsMultithreaded( const carla::geom::MeshFactory& mesh_factory,
const size_t index, const size_t number_of_roads_per_thread) const
{
std::map<road::Lane::LaneType, std::vector<std::unique_ptr<geom::Mesh>>> out;
auto start = std::next( _data.GetRoads().begin(), (index ) * number_of_roads_per_thread);
size_t endoffset = (index+1) * number_of_roads_per_thread;
if( endoffset >= _data.GetRoads().size() ) {
endoffset = _data.GetRoads().size();
endoffset = _data.GetRoads().size();
}
auto end = std::next( _data.GetRoads().begin(), endoffset );
@ -1449,7 +1481,7 @@ namespace road {
auto start = std::next( roadsmesh.begin(), ( index ) * number_of_roads_per_thread);
size_t endoffset = (index+1) * number_of_roads_per_thread;
if( endoffset >= roadsmesh.size() ) {
endoffset = roadsmesh.size();
endoffset = roadsmesh.size();
}
auto end = std::next( roadsmesh.begin(), endoffset );
for ( auto it = start; it != end && it != roadsmesh.end(); ++it ) {
@ -1499,7 +1531,7 @@ namespace road {
current_mesh->GetIndexes().push_back((Simplification.triangles[i].v[0]) + 1);
current_mesh->GetIndexes().push_back((Simplification.triangles[i].v[1]) + 1);
current_mesh->GetIndexes().push_back((Simplification.triangles[i].v[2]) + 1);
}
}
}
}

View File

@ -160,12 +160,16 @@ 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>>>
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;
std::vector<std::pair<geom::Vector3D, std::string>> GetTreesPosition(
float distancebetweentrees,
float distancefromdrivinglineborder) const;
geom::Mesh GenerateWalls(const double distance, const float wall_height) const;
/// Buids a list of meshes related with LineMarkings
@ -214,11 +218,11 @@ private:
public:
inline float GetZPosInDeformation(float posx, float posy) const;
std::map<road::Lane::LaneType, std::vector<std::unique_ptr<geom::Mesh>>>
std::map<road::Lane::LaneType, std::vector<std::unique_ptr<geom::Mesh>>>
GenerateRoadsMultithreaded( const carla::geom::MeshFactory& mesh_factory,
const size_t index, const size_t number_of_roads_per_thread) const;
void GenerateJunctions(const carla::geom::MeshFactory& mesh_factory,
void GenerateJunctions(const carla::geom::MeshFactory& mesh_factory,
const rpc::OpendriveGenerationParameters& params,
std::map<road::Lane::LaneType, std::vector<std::unique_ptr<geom::Mesh>>>*
juntion_out_mesh_list) const;

View File

@ -17,8 +17,13 @@ namespace element {
RoadInfoSpeed(double s, double speed)
: RoadInfo(s),
_speed(speed) {}
_speed(speed),
_type("Town") {}
RoadInfoSpeed(double s, double speed, std::string& type)
: RoadInfo(s),
_speed(speed),
_type(type) {}
void AcceptVisitor(RoadInfoVisitor &v) final {
v.Visit(*this);
}
@ -27,9 +32,14 @@ namespace element {
return _speed;
}
std::string GetType() const{
return _type;
}
private:
const double _speed;
const std::string _type;
};
} // namespace element

View File

@ -126,7 +126,7 @@ void UOpenDriveToMap::CreateMap()
UE_LOG(LogCarlaToolsMapGenerator, Error, TEXT("Map Name Is Empty") );
return;
}
if ( !IsValid(FileDownloader) )
if ( !IsValid(FileDownloader) )
{
FileDownloader = NewObject<UCustomFileDownloader>();
}
@ -166,7 +166,7 @@ void UOpenDriveToMap::LoadMap()
std::string opendrive_xml = carla::rpc::FromLongFString(FileContent);
boost::optional<carla::road::Map> CarlaMap = carla::opendrive::OpenDriveParser::Load(opendrive_xml);
if (!CarlaMap.has_value())
if (!CarlaMap.has_value())
{
UE_LOG(LogCarlaToolsMapGenerator, Error, TEXT("Invalid Map"));
}
@ -179,17 +179,19 @@ void UOpenDriveToMap::LoadMap()
UE_LOG(LogCarlaToolsMapGenerator, Warning, TEXT("MapName %s"), *MapName);
GenerateAll(CarlaMap);
GenerationFinished();
}
void UOpenDriveToMap::GenerateAll(const boost::optional<carla::road::Map>& CarlaMap )
{
if (!CarlaMap.has_value())
if (!CarlaMap.has_value())
{
UE_LOG(LogCarlaToolsMapGenerator, Error, TEXT("Invalid Map"));
}else
{
GenerateRoadMesh(CarlaMap);
GenerateSpawnPoints(CarlaMap);
GenerateTreePositions(CarlaMap);
GenerateLaneMarks(CarlaMap);
}
}
@ -207,7 +209,7 @@ void UOpenDriveToMap::GenerateRoadMesh( const boost::optional<carla::road::Map>&
start = FPlatformTime::Seconds();
int index = 0;
for (const auto &PairMap : Meshes)
for (const auto &PairMap : Meshes)
{
for( const auto &Mesh : PairMap.second )
{
@ -359,6 +361,20 @@ void UOpenDriveToMap::GenerateSpawnPoints( const boost::optional<carla::road::Ma
}
}
void UOpenDriveToMap::GenerateTreePositions( const boost::optional<carla::road::Map>& CarlaMap )
{
const std::vector<std::pair<carla::geom::Vector3D, std::string>> Locations =
CarlaMap->GetTreesPosition(DistanceBetweenTrees, DistanceFromRoadEdge );
int i = 0;
for (const auto &cl : Locations)
{
AActor *Spawner = GetWorld()->SpawnActor<AStaticMeshActor>(AStaticMeshActor::StaticClass(), cl.first.ToFVector() * 100, FRotator(0,0,0));
Spawner->Tags.Add(FName("TreeSpawnPosition"));
Spawner->Tags.Add(FName(cl.second.c_str()));
Spawner->SetActorLabel("TreeSpawnPosition" + FString::FromInt(i) );
++i;
}
}
UStaticMesh* UOpenDriveToMap::CreateStaticMeshAsset( UProceduralMeshComponent* ProcMeshComp, int32 MeshIndex, FString FolderName )
{
FMeshDescription MeshDescription = BuildMeshDescription(ProcMeshComp);

View File

@ -20,7 +20,7 @@ class UMeshComponent;
class UCustomFileDownloader;
class UMaterialInstance;
/**
*
*
*/
UCLASS(Blueprintable, BlueprintType)
class CARLATOOLS_API UOpenDriveToMap : public UObject
@ -30,7 +30,7 @@ class CARLATOOLS_API UOpenDriveToMap : public UObject
public:
UFUNCTION()
void ConvertOSMInOpenDrive();
void ConvertOSMInOpenDrive();
UFUNCTION( BlueprintCallable )
void CreateMap();
@ -47,6 +47,11 @@ 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;
@ -57,6 +62,9 @@ protected:
UFUNCTION( BlueprintCallable )
void SaveMap();
UFUNCTION( BlueprintImplementableEvent )
void GenerationFinished();
private:
UFUNCTION()
@ -68,13 +76,14 @@ private:
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);
void GenerateTreePositions(const boost::optional<carla::road::Map>& CarlaMap);
void GenerateLaneMarks(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()

View File

@ -0,0 +1,35 @@
// 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 "Engine/DataTable.h"
#include "TreeTableRow.generated.h"
/**
*
*/
UENUM(BlueprintType)
enum class ELaneDescriptor : uint8 {
None = 0x0,
Town = 0x1 << 0,
Motorway = 0x1 << 1,
Rural = 0x1 << 2,
Any = 255 // 0xFE
};
USTRUCT(BlueprintType)
struct FTreeTableRow : public FTableRowBase {
GENERATED_BODY()
public:
UPROPERTY(EditAnywhere, BlueprintReadWrite, Category= "Category")
ELaneDescriptor TreesCategory;
UPROPERTY(EditAnywhere, BlueprintReadWrite, Category= "Trees")
TArray<TSoftObjectPtr<UStaticMesh>> Trees;
};