diff --git a/Examples/CppClient/main.cpp b/Examples/CppClient/main.cpp index 0bfdeacc485..f02e344b3e2 100644 --- a/Examples/CppClient/main.cpp +++ b/Examples/CppClient/main.cpp @@ -18,6 +18,7 @@ #include #include +// 使用 Carla 模块的命名空间简化代码。 namespace cc = carla::client; namespace cg = carla::geom; namespace csd = carla::sensor::data; @@ -25,66 +26,60 @@ namespace csd = carla::sensor::data; using namespace std::chrono_literals; using namespace std::string_literals; +// 简化断言宏,用于验证条件是否满足。 #define EXPECT_TRUE(pred) if (!(pred)) { throw std::runtime_error(#pred); } -/// Pick a random element from @a range. +/// 从给定范围中随机选择一个元素。 +/// @param range 包含元素的范围。 +/// @param generator 随机数生成器。 template static auto &RandomChoice(const RangeT &range, RNG &&generator) { - EXPECT_TRUE(range.size() > 0u); + EXPECT_TRUE(range.size() > 0u); // 验证范围非空。 std::uniform_int_distribution dist{0u, range.size() - 1u}; return range[dist(std::forward(generator))]; } -/// Save a semantic segmentation image to disk converting to CityScapes palette. -/* -static void SaveSemSegImageToDisk(const csd::Image &image) { - using namespace carla::image; - - char buffer[9u]; - std::snprintf(buffer, sizeof(buffer), "%08zu", image.GetFrame()); - auto filename = "_images/"s + buffer + ".png"; - - auto view = ImageView::MakeColorConvertedView( - ImageView::MakeView(image), - ColorConverter::CityScapesPalette()); - ImageIO::WriteView(filename, view); -} -*/ - +/// 解析命令行参数,返回主机名和端口号。 +/// @param argc 参数个数。 +/// @param argv 参数值。 +/// @return 包含主机名和端口号的元组。 static auto ParseArguments(int argc, const char *argv[]) { - EXPECT_TRUE((argc == 1u) || (argc == 3u)); + EXPECT_TRUE((argc == 1u) || (argc == 3u)); // 参数必须为 1 或 3。 using ResultType = std::tuple; return argc == 3u ? ResultType{argv[1u], std::stoi(argv[2u])} : - ResultType{"localhost", 2000u}; + ResultType{"localhost", 2000u}; // 默认连接到 localhost:2000。 } int main(int argc, const char *argv[]) { try { - + // 解析命令行参数,获取主机名和端口号。 std::string host; uint16_t port; std::tie(host, port) = ParseArguments(argc, argv); + // 初始化随机数生成器。 std::mt19937_64 rng((std::random_device())()); + // 创建客户端并设置超时时间。 auto client = cc::Client(host, port); client.SetTimeout(40s); + // 输出客户端和服务端的 API 版本。 std::cout << "Client API version : " << client.GetClientVersion() << '\n'; std::cout << "Server API version : " << client.GetServerVersion() << '\n'; - // Load a random town. + // 随机选择一个可用的地图并加载。 auto town_name = RandomChoice(client.GetAvailableMaps(), rng); std::cout << "Loading world: " << town_name << std::endl; auto world = client.LoadWorld(town_name); - // Get a random vehicle blueprint. + // 从蓝图库中随机选择一个车辆蓝图。 auto blueprint_library = world.GetBlueprintLibrary(); auto vehicles = blueprint_library->Filter("vehicle"); auto blueprint = RandomChoice(*vehicles, rng); - // Randomize the blueprint. + // 随机化车辆蓝图的属性(如颜色)。 if (blueprint.ContainsAttribute("color")) { auto &attribute = blueprint.GetAttribute("color"); blueprint.SetAttribute( @@ -92,59 +87,64 @@ int main(int argc, const char *argv[]) { RandomChoice(attribute.GetRecommendedValues(), rng)); } - // Find a valid spawn point. + // 从推荐的生成点中随机选择一个位置。 auto map = world.GetMap(); auto transform = RandomChoice(map->GetRecommendedSpawnPoints(), rng); - // Spawn the vehicle. + // 在选定位置生成车辆。 auto actor = world.SpawnActor(blueprint, transform); std::cout << "Spawned " << actor->GetDisplayId() << '\n'; auto vehicle = boost::static_pointer_cast(actor); - // Apply control to vehicle. + // 应用控制命令以使车辆前进。 cc::Vehicle::Control control; - control.throttle = 1.0f; + control.throttle = 1.0f; // 油门设为最大值。 vehicle->ApplyControl(control); - // Move spectator so we can see the vehicle from the simulator window. + // 调整观察者的位置以查看车辆。 auto spectator = world.GetSpectator(); transform.location += 32.0f * transform.GetForwardVector(); - transform.location.z += 2.0f; - transform.rotation.yaw += 180.0f; - transform.rotation.pitch = -15.0f; + transform.location.z += 2.0f; // 提升视角高度。 + transform.rotation.yaw += 180.0f; // 调整观察方向。 + transform.rotation.pitch = -15.0f; // 向下倾斜视角。 spectator->SetTransform(transform); /* - // Find a camera blueprint. + // 获取语义分割相机的蓝图。 auto camera_bp = blueprint_library->Find("sensor.camera.semantic_segmentation"); EXPECT_TRUE(camera_bp != nullptr); - // Spawn a camera attached to the vehicle. + // 在车辆上安装相机。 auto camera_transform = cg::Transform{ cg::Location{-5.5f, 0.0f, 2.8f}, // x, y, z. cg::Rotation{-15.0f, 0.0f, 0.0f}}; // pitch, yaw, roll. auto cam_actor = world.SpawnActor(*camera_bp, camera_transform, actor.get()); auto camera = boost::static_pointer_cast(cam_actor); - // Register a callback to save images to disk. + // 注册回调函数,将语义分割图像保存到磁盘。 camera->Listen([](auto data) { auto image = boost::static_pointer_cast(data); EXPECT_TRUE(image != nullptr); SaveSemSegImageToDisk(*image); }); + // 模拟运行一段时间以捕获图像。 std::this_thread::sleep_for(10s); - // Remove actors from the simulation. + // 销毁相机。 camera->Destroy(); */ + + // 销毁车辆。 vehicle->Destroy(); std::cout << "Actors destroyed." << std::endl; } catch (const cc::TimeoutException &e) { + // 处理客户端超时异常。 std::cout << '\n' << e.what() << std::endl; return 1; } catch (const std::exception &e) { + // 处理其他异常。 std::cout << "\nException: " << e.what() << std::endl; return 2; } diff --git a/LibCarla/source/carla/Exception.cpp b/LibCarla/source/carla/Exception.cpp index 1ed5c796561..8a19405e081 100644 --- a/LibCarla/source/carla/Exception.cpp +++ b/LibCarla/source/carla/Exception.cpp @@ -22,6 +22,20 @@ namespace boost { void throw_exception( const std::exception &e, boost::source_location const & loc) { +// ============================================================================= +// -- 异常处理兼容性调整:Boost 和 Boost.Asio 的支持 --------------------------- +// ============================================================================= + +// 如果 Boost 被配置为禁用异常(BOOST_NO_EXCEPTIONS), +// 提供一个自定义的异常抛出实现。 +#ifdef BOOST_NO_EXCEPTIONS + +namespace boost { + + // 自定义异常抛出函数。 + // 需要开发者提供具体的异常抛出逻辑。 + void throw_exception(const std::exception& e) { + // 在用户代码中实现具体逻辑。 throw_exception(e); } @@ -30,9 +44,11 @@ namespace boost { #endif // BOOST_NO_EXCEPTIONS // ============================================================================= -// -- Workaround for Boost.Asio bundled with rpclib ---------------------------- +// -- 针对 rpclib 使用的 Boost.Asio 的兼容性调整 ------------------------------- // ============================================================================= +// 如果 Asio 被配置为禁用异常(ASIO_NO_EXCEPTIONS), +// 定义兼容性层以处理 Asio 中的异常抛出。 #ifdef ASIO_NO_EXCEPTIONS #include @@ -42,11 +58,13 @@ namespace boost { namespace clmdep_asio { namespace detail { + // 模板函数,用于抛出指定类型的异常。 template void throw_exception(const Exception& e) { - carla::throw_exception(e); + carla::throw_exception(e); // 调用 Carla 库提供的异常抛出实现。 } + // 针对常见异常类型的显式模板实例化。 template void throw_exception(const std::bad_cast &); template void throw_exception(const std::exception &); template void throw_exception(const std::system_error &); diff --git a/Unreal/CarlaUE4/Plugins/CarlaTools/Source/CarlaTools/Private/HoudiniImporterWidget.cpp b/Unreal/CarlaUE4/Plugins/CarlaTools/Source/CarlaTools/Private/HoudiniImporterWidget.cpp index c75887058c4..ae35cbaf69a 100644 --- a/Unreal/CarlaUE4/Plugins/CarlaTools/Source/CarlaTools/Private/HoudiniImporterWidget.cpp +++ b/Unreal/CarlaUE4/Plugins/CarlaTools/Source/CarlaTools/Private/HoudiniImporterWidget.cpp @@ -13,188 +13,207 @@ #include "EditorLevelLibrary.h" #include "Components/PrimitiveComponent.h" +// Create sublevels for managing a large map. +// The implementation is currently empty and needs further development. void UHoudiniImporterWidget::CreateSubLevels(ALargeMapManager* LargeMapManager) { - } +// Move actors to specific sublevels based on their location in the large map. void UHoudiniImporterWidget::MoveActorsToSubLevelWithLargeMap(TArray Actors, ALargeMapManager* LargeMapManager) { - TMap> ActorsToMove; - for (AActor* Actor : Actors) - { - if (Actor == nullptr) { - continue; - } - UHierarchicalInstancedStaticMeshComponent* Component - = Cast( - Actor->GetComponentByClass( - UHierarchicalInstancedStaticMeshComponent::StaticClass())); - FVector ActorLocation = Actor->GetActorLocation(); - if (Component) - { - ActorLocation = FVector(0); - for(int32 i = 0; i < Component->GetInstanceCount(); ++i) - { - FTransform Transform; - Component->GetInstanceTransform(i, Transform, true); - ActorLocation = ActorLocation + Transform.GetTranslation(); - } - ActorLocation = ActorLocation / Component->GetInstanceCount(); - } - UE_LOG(LogCarlaTools, Log, TEXT("Actor at location %s"), - *ActorLocation.ToString()); - FCarlaMapTile* Tile = LargeMapManager->GetCarlaMapTile(ActorLocation); - if(!Tile) - { - UE_LOG(LogCarlaTools, Error, TEXT("Error: actor %s in location %s is outside the map"), - *Actor->GetName(),*ActorLocation.ToString()); - continue; - } + TMap> ActorsToMove; - if(Component) + // Categorize actors by their respective map tiles. + for (AActor* Actor : Actors) { - UpdateInstancedMeshCoordinates(Component, Tile->Location); + if (!Actor) continue; + + // Check for hierarchical instanced mesh components and calculate location. + UHierarchicalInstancedStaticMeshComponent* Component = Cast( + Actor->GetComponentByClass(UHierarchicalInstancedStaticMeshComponent::StaticClass())); + FVector ActorLocation = Actor->GetActorLocation(); + + if (Component) + { + // Calculate average location for all instances in the mesh. + ActorLocation = FVector(0); + for (int32 i = 0; i < Component->GetInstanceCount(); ++i) + { + FTransform Transform; + Component->GetInstanceTransform(i, Transform, true); + ActorLocation += Transform.GetTranslation(); + } + ActorLocation /= Component->GetInstanceCount(); + } + + // Log actor location and determine the corresponding map tile. + UE_LOG(LogCarlaTools, Log, TEXT("Actor at location %s"), *ActorLocation.ToString()); + FCarlaMapTile* Tile = LargeMapManager->GetCarlaMapTile(ActorLocation); + + if (!Tile) + { + UE_LOG(LogCarlaTools, Error, TEXT("Error: actor %s in location %s is outside the map"), *Actor->GetName(), *ActorLocation.ToString()); + continue; + } + + // Update actor coordinates based on tile origin. + if (Component) + { + UpdateInstancedMeshCoordinates(Component, Tile->Location); + } + else + { + UpdateGenericActorCoordinates(Actor, Tile->Location); + } + + // Add the actor to the corresponding tile's list. + ActorsToMove.FindOrAdd(Tile).Add(Actor); } - else + + // Move categorized actors to their respective levels. + for (auto& Element : ActorsToMove) { - UpdateGenericActorCoordinates(Actor, Tile->Location); + FCarlaMapTile* Tile = Element.Key; + TArray ActorList = Element.Value; + + if (ActorList.Num() == 0) continue; + + UWorld* World = UEditorLevelLibrary::GetEditorWorld(); + ULevelStreamingDynamic* StreamingLevel = Tile->StreamingLevel; + + StreamingLevel->bShouldBlockOnLoad = true; + StreamingLevel->SetShouldBeVisible(true); + StreamingLevel->SetShouldBeLoaded(true); + + ULevelStreaming* Level = UEditorLevelUtils::AddLevelToWorld( + World, *Tile->Name, ULevelStreamingDynamic::StaticClass(), FTransform()); + + int MovedActors = UEditorLevelUtils::MoveActorsToLevel(ActorList, Level, false, false); + + UE_LOG(LogCarlaTools, Log, TEXT("Moved %d actors"), MovedActors); + + // Save and unload the level. + FEditorFileUtils::SaveDirtyPackages(false, true, true, false, false, false, nullptr); + UEditorLevelUtils::RemoveLevelFromWorld(Level->GetLoadedLevel()); } - ActorsToMove.FindOrAdd(Tile).Add(Actor); - } - - for (auto& Element : ActorsToMove) - { - FCarlaMapTile* Tile = Element.Key; - TArray ActorList = Element.Value; - if(!ActorList.Num()) + + // Perform garbage collection and cleanup. + GEngine->PerformGarbageCollectionAndCleanupActors(); + FText TransResetText(FText::FromString("Clean up after Move actors to sublevels")); + + if (GEditor->Trans) { - continue; + GEditor->Trans->Reset(TransResetText); + GEditor->Cleanse(true, true, TransResetText); } - - UWorld* World = UEditorLevelLibrary::GetEditorWorld(); - ULevelStreamingDynamic* StreamingLevel = Tile->StreamingLevel; - StreamingLevel->bShouldBlockOnLoad = true; - StreamingLevel->SetShouldBeVisible(true); - StreamingLevel->SetShouldBeLoaded(true); - ULevelStreaming* Level = - UEditorLevelUtils::AddLevelToWorld( - World, *Tile->Name, ULevelStreamingDynamic::StaticClass(), FTransform()); - int MovedActors = UEditorLevelUtils::MoveActorsToLevel(ActorList, Level, false, false); - // StreamingLevel->SetShouldBeLoaded(false); - UE_LOG(LogCarlaTools, Log, TEXT("Moved %d actors"), MovedActors); - FEditorFileUtils::SaveDirtyPackages(false, true, true, false, false, false, nullptr); - UEditorLevelUtils::RemoveLevelFromWorld(Level->GetLoadedLevel()); - } - - GEngine->PerformGarbageCollectionAndCleanupActors(); - FText TransResetText(FText::FromString("Clean up after Move actors to sublevels")); - if ( GEditor->Trans ) - { - GEditor->Trans->Reset(TransResetText); - GEditor->Cleanse(true, true, TransResetText); - } } -void UHoudiniImporterWidget::ForceStreamingLevelsToUnload( ALargeMapManager* LargeMapManager ) +// Force the unloading of all streaming levels managed by the large map manager. +void UHoudiniImporterWidget::ForceStreamingLevelsToUnload(ALargeMapManager* LargeMapManager) { - UWorld* World = UEditorLevelLibrary::GetGameWorld(); - - FIntVector NumTilesInXY = LargeMapManager->GetNumTilesInXY(); + UWorld* World = UEditorLevelLibrary::GetGameWorld(); + FIntVector NumTilesInXY = LargeMapManager->GetNumTilesInXY(); - for(int x = 0; x < NumTilesInXY.X; ++x) - { - for(int y = 0; y < NumTilesInXY.Y; ++y) + for (int x = 0; x < NumTilesInXY.X; ++x) { - FIntVector CurrentTileVector(x, y, 0); - FCarlaMapTile CarlaTile = LargeMapManager->GetCarlaMapTile(CurrentTileVector); - ULevelStreamingDynamic* StreamingLevel = CarlaTile.StreamingLevel; - ULevelStreaming* Level = - UEditorLevelUtils::AddLevelToWorld( - World, *CarlaTile.Name, ULevelStreamingDynamic::StaticClass(), FTransform()); - FEditorFileUtils::SaveDirtyPackages(false, true, true, false, false, false, nullptr); - UEditorLevelUtils::RemoveLevelFromWorld(Level->GetLoadedLevel()); + for (int y = 0; y < NumTilesInXY.Y; ++y) + { + FIntVector CurrentTileVector(x, y, 0); + FCarlaMapTile CarlaTile = LargeMapManager->GetCarlaMapTile(CurrentTileVector); + + ULevelStreamingDynamic* StreamingLevel = CarlaTile.StreamingLevel; + ULevelStreaming* Level = UEditorLevelUtils::AddLevelToWorld( + World, *CarlaTile.Name, ULevelStreamingDynamic::StaticClass(), FTransform()); + + FEditorFileUtils::SaveDirtyPackages(false, true, true, false, false, false, nullptr); + UEditorLevelUtils::RemoveLevelFromWorld(Level->GetLoadedLevel()); + } } - } - } +// Move a list of actors to a specified sublevel. void UHoudiniImporterWidget::MoveActorsToSubLevel(TArray Actors, ULevelStreaming* Level) { - int MovedActors = UEditorLevelUtils::MoveActorsToLevel(Actors, Level, false, false); - - UE_LOG(LogCarlaTools, Log, TEXT("Moved %d actors"), MovedActors); - FEditorFileUtils::SaveDirtyPackages(false, true, true, false, false, false, nullptr); - UEditorLevelUtils::RemoveLevelFromWorld(Level->GetLoadedLevel()); - FText TransResetText(FText::FromString("Clean up after Move actors to sublevels")); - if ( GEditor->Trans ) - { - GEditor->Trans->Reset(TransResetText); - } + int MovedActors = UEditorLevelUtils::MoveActorsToLevel(Actors, Level, false, false); + + UE_LOG(LogCarlaTools, Log, TEXT("Moved %d actors"), MovedActors); + + FEditorFileUtils::SaveDirtyPackages(false, true, true, false, false, false, nullptr); + UEditorLevelUtils::RemoveLevelFromWorld(Level->GetLoadedLevel()); + + FText TransResetText(FText::FromString("Clean up after Move actors to sublevels")); + if (GEditor->Trans) + { + GEditor->Trans->Reset(TransResetText); + } } -void UHoudiniImporterWidget::UpdateGenericActorCoordinates( - AActor* Actor, FVector TileOrigin) +// Update actor coordinates to be relative to the given tile origin. +void UHoudiniImporterWidget::UpdateGenericActorCoordinates(AActor* Actor, FVector TileOrigin) { - FVector LocalLocation = Actor->GetActorLocation() - TileOrigin; - Actor->SetActorLocation(LocalLocation); - UE_LOG(LogCarlaTools, Log, TEXT("%s New location %s"), - *Actor->GetName(), *LocalLocation.ToString()); + FVector LocalLocation = Actor->GetActorLocation() - TileOrigin; + Actor->SetActorLocation(LocalLocation); + + UE_LOG(LogCarlaTools, Log, TEXT("%s New location %s"), *Actor->GetName(), *LocalLocation.ToString()); } -void UHoudiniImporterWidget::UpdateInstancedMeshCoordinates( - UHierarchicalInstancedStaticMeshComponent* Component, FVector TileOrigin) +// Update the transforms of all instances in a hierarchical instanced mesh component. +void UHoudiniImporterWidget::UpdateInstancedMeshCoordinates(UHierarchicalInstancedStaticMeshComponent* Component, FVector TileOrigin) { - TArray NewTransforms; - for(int32 i = 0; i < Component->GetInstanceCount(); ++i) - { - FTransform Transform; - Component->GetInstanceTransform(i, Transform, true); - Transform.AddToTranslation(-TileOrigin); - NewTransforms.Add(Transform); - UE_LOG(LogCarlaTools, Log, TEXT("New instance location %s"), - *Transform.GetTranslation().ToString()); - } - Component->BatchUpdateInstancesTransforms(0, NewTransforms, true, true, true); + TArray NewTransforms; + + for (int32 i = 0; i < Component->GetInstanceCount(); ++i) + { + FTransform Transform; + Component->GetInstanceTransform(i, Transform, true); + Transform.AddToTranslation(-TileOrigin); + NewTransforms.Add(Transform); + + UE_LOG(LogCarlaTools, Log, TEXT("New instance location %s"), *Transform.GetTranslation().ToString()); + } + + Component->BatchUpdateInstancesTransforms(0, NewTransforms, true, true, true); } +// Set actor location to its center of mass for a given list of actors. void UHoudiniImporterWidget::UseCOMasActorLocation(TArray Actors) { - for (AActor* Actor : Actors) - { - UPrimitiveComponent* Primitive = Cast( - Actor->GetComponentByClass(UPrimitiveComponent::StaticClass())); - if(Primitive) + for (AActor* Actor : Actors) { - FBodyInstance* BodyInstance = Primitive->GetBodyInstance(); - FVector CenterOfMass = BodyInstance->COMNudge; - Actor->SetActorLocation(CenterOfMass); + UPrimitiveComponent* Primitive = Cast( + Actor->GetComponentByClass(UPrimitiveComponent::StaticClass())); + + if (Primitive) + { + FBodyInstance* BodyInstance = Primitive->GetBodyInstance(); + FVector CenterOfMass = BodyInstance->COMNudge; + Actor->SetActorLocation(CenterOfMass); + } } - } } -bool UHoudiniImporterWidget::GetNumberOfClusters( - TArray ActorList, int& OutNumClusters) +// Extract the number of clusters based on actor naming convention. +bool UHoudiniImporterWidget::GetNumberOfClusters(TArray ActorList, int& OutNumClusters) { - - for (AActor* Actor : ActorList) - { - FString ObjectName = UKismetSystemLibrary::GetObjectName(Actor); - UE_LOG(LogCarlaTools, Log, TEXT("Searching in string %s"), *ObjectName); - if(ObjectName.StartsWith("b")) + for (AActor* Actor : ActorList) { - int Index = ObjectName.Find("of"); - if(Index == -1) - { - continue; - } - UE_LOG(LogCarlaTools, Log, TEXT("found of substr at %d"), Index); - FString NumClusterString = ObjectName.Mid(Index+2, ObjectName.Len()); - OutNumClusters = FCString::Atoi(*NumClusterString); - return true; + FString ObjectName = UKismetSystemLibrary::GetObjectName(Actor); + UE_LOG(LogCarlaTools, Log, TEXT("Searching in string %s"), *ObjectName); + + if (ObjectName.StartsWith("b")) + { + int Index = ObjectName.Find("of"); + if (Index == -1) continue; + + UE_LOG(LogCarlaTools, Log, TEXT("found 'of' substring at %d"), Index); + FString NumClusterString = ObjectName.Mid(Index + 2, ObjectName.Len()); + OutNumClusters = FCString::Atoi(*NumClusterString); + return true; + } } - } - UE_LOG(LogCarlaTools, Warning, TEXT("Num clusters not found")); - OutNumClusters = -1; - return false; + + UE_LOG(LogCarlaTools, Warning, TEXT("Num clusters not found")); + OutNumClusters = -1; + return false; } diff --git a/Util/Patches/omniverse_4.26/USDCARLAInterface.cpp b/Util/Patches/omniverse_4.26/USDCARLAInterface.cpp index e809151a425..bd765fc64da 100644 --- a/Util/Patches/omniverse_4.26/USDCARLAInterface.cpp +++ b/Util/Patches/omniverse_4.26/USDCARLAInterface.cpp @@ -1,24 +1,31 @@ - #include "USDCARLAInterface.h" #include "OmniversePxr.h" #include "OmniverseUSDImporter.h" #include "OmniverseUSDHelper.h" - +// Import a USD file with the specified settings. bool UUSDCARLAInterface::ImportUSD( const FString& Path, const FString& Dest, bool bImportUnusedReferences, bool bImportAsBlueprint) { + // Configure the import settings. FOmniverseImportSettings Settings; Settings.bImportUnusedReferences = bImportUnusedReferences; Settings.bImportAsBlueprint = bImportAsBlueprint; + + // Perform the USD import. return FOmniverseUSDImporter::LoadUSD(Path, Dest, Settings); } +// Retrieve all light data from a USD file at the specified path. TArray UUSDCARLAInterface::GetUSDLights(const FString& Path) { TArray Result; + + // Load the USD stage from the file path. pxr::UsdStageRefPtr Stage = FOmniverseUSDHelper::LoadUSDStageFromPath(Path); + + // Traverse the stage to find all light primitives. std::vector LightPrims; const auto& PrimRange = Stage->Traverse(); for (const auto& Prim : PrimRange) { @@ -26,149 +33,130 @@ TArray UUSDCARLAInterface::GetUSDLights(const FString& Path) LightPrims.push_back(Prim); } } + + // Extract and convert light attributes into a readable format. for (pxr::UsdPrim& LightPrim : LightPrims) { pxr::UsdLuxLight Light(LightPrim); - std::string StdName = LightPrim.GetName(); + // Extract light name and attributes. + std::string StdName = LightPrim.GetName(); pxr::GfVec3f PxColor; pxr::VtValue vtValue; if (Light.GetColorAttr().Get(&vtValue)) { PxColor = vtValue.Get(); } + + // Extract the world transform of the light. pxr::UsdGeomXformCache Cache; pxr::GfMatrix4d Transform = Cache.GetLocalToWorldTransform(LightPrim); pxr::GfVec3d PxLocation = Transform.ExtractTranslation(); + // Convert extracted attributes to Unreal's formats. FString Name(StdName.size(), UTF8_TO_TCHAR(StdName.c_str())); FLinearColor Color(PxColor[0], PxColor[1], PxColor[2]); - FVector Location(PxLocation[0], -PxLocation[1], PxLocation[2]); - Location *= 100.f; + FVector Location(PxLocation[0], -PxLocation[1], PxLocation[2]); // Adjust for Unreal's coordinate system. + Location *= 100.f; // Convert from meters to centimeters. FUSDCARLALight LightParams {Name, Location, Color}; Result.Add(LightParams); } + return Result; } +// Retrieve wheel data for a vehicle from a USD file. TArray UUSDCARLAInterface::GetUSDWheelData(const FString& Path) { - pxr::UsdStageRefPtr Stage = - FOmniverseUSDHelper::LoadUSDStageFromPath(Path); + // Load the USD stage from the file path. + pxr::UsdStageRefPtr Stage = FOmniverseUSDHelper::LoadUSDStageFromPath(Path); - // Get the wheel data + // Paths for wheel and suspension data within the USD file. const std::string UsdPhysxWheelPath = "/vehicle/_physx/_physxWheels/"; const std::string UsdPhysxSuspensionPath = "/vehicle/_physx/_physxSuspensions/"; + + // Helper function to get a float attribute value from a USD primitive. auto GetFloatAttributeValue = [](pxr::UsdPrim& Prim, const std::string& AttrName) -> float { - pxr::UsdAttribute Attribute = - Prim.GetAttribute(pxr::TfToken(AttrName)); - if(!Attribute) - { - return 0.f; - } + pxr::UsdAttribute Attribute = Prim.GetAttribute(pxr::TfToken(AttrName)); + if(!Attribute) return 0.f; + float Value = 0.f; Attribute.Get(&Value); return Value; }; + + // Helper function to get a USD primitive from a relationship. auto GetPrimFromRelationship = [&]( pxr::UsdRelationship& Relationship) -> pxr::UsdPrim { std::vector Targets; Relationship.GetTargets(&Targets); - if (!Targets.size()) - { - return pxr::UsdPrim(); - } - return Stage->GetPrimAtPath(Targets.front()); + return Targets.empty() ? pxr::UsdPrim() : Stage->GetPrimAtPath(Targets.front()); }; + + // Helper function to parse wheel data for a specific wheel. auto ParseWheelData = [&]( const std::string& WheelName, FUSDCARLAWheelData& OutWheelData) -> bool { + // Retrieve the wheel USD primitive. pxr::SdfPath WheelPath(UsdPhysxWheelPath + WheelName); pxr::UsdPrim WheelPrim = Stage->GetPrimAtPath(WheelPath); - if(!WheelPrim) - { - UE_LOG(LogOmniverseUsd, Warning, TEXT("Wheel prim fail")); + if(!WheelPrim) { + UE_LOG(LogOmniverseUsd, Warning, TEXT("Wheel prim not found: %s"), *FString(WheelName.c_str())); return false; } - pxr::UsdRelationship WheelRelationship; - pxr::UsdRelationship TireRelationship; - pxr::UsdRelationship SuspensionRelationship; - for (pxr::UsdProperty& Property : WheelPrim.GetProperties()) - { + + // Retrieve relationships for wheel, tire, and suspension data. + pxr::UsdRelationship WheelRelationship, TireRelationship, SuspensionRelationship; + for (pxr::UsdProperty& Property : WheelPrim.GetProperties()) { FString Name (Property.GetBaseName().GetText()); - if(Name == "wheel") - { - WheelRelationship = Property.As(); - } - if(Name == "tire") - { - TireRelationship = Property.As(); - } - if(Name == "suspension") - { - SuspensionRelationship = - Property.As(); - } + if(Name == "wheel") WheelRelationship = Property.As(); + if(Name == "tire") TireRelationship = Property.As(); + if(Name == "suspension") SuspensionRelationship = Property.As(); } - if(!WheelRelationship || !TireRelationship || !SuspensionRelationship) - { - UE_LOG(LogOmniverseUsd, Warning, TEXT("Relationships fail: %d %d %d"), - bool(WheelRelationship), bool(TireRelationship), bool(SuspensionRelationship)); + + if(!WheelRelationship || !TireRelationship || !SuspensionRelationship) { + UE_LOG(LogOmniverseUsd, Warning, TEXT("Failed to find required relationships for wheel: %s"), *FString(WheelName.c_str())); return false; } + + // Retrieve the primitives for the relationships. pxr::UsdPrim PhysxWheelPrim = GetPrimFromRelationship(WheelRelationship); pxr::UsdPrim PhysxTirePrim = GetPrimFromRelationship(TireRelationship); - pxr::UsdPrim PhysxSuspensionlPrim = GetPrimFromRelationship(SuspensionRelationship); + pxr::UsdPrim PhysxSuspensionPrim = GetPrimFromRelationship(SuspensionRelationship); - if (!PhysxWheelPrim || !PhysxTirePrim || !PhysxSuspensionlPrim) - { - UE_LOG(LogOmniverseUsd, Warning, TEXT("Prims fail: %d %d %d"), - bool(PhysxWheelPrim), bool(PhysxTirePrim), bool(PhysxSuspensionlPrim)); + if (!PhysxWheelPrim || !PhysxTirePrim || !PhysxSuspensionPrim) { + UE_LOG(LogOmniverseUsd, Warning, TEXT("Failed to find primitives for wheel: %s"), *FString(WheelName.c_str())); return false; } - OutWheelData.MaxBrakeTorque = - GetFloatAttributeValue(PhysxWheelPrim, "physxVehicleWheel:maxBrakeTorque"); - OutWheelData.MaxHandBrakeTorque = - GetFloatAttributeValue(PhysxWheelPrim, "physxVehicleWheel:maxHandBrakeTorque"); - OutWheelData.MaxSteerAngle = - GetFloatAttributeValue(PhysxWheelPrim, "physxVehicleWheel:maxSteerAngle"); - OutWheelData.SpringStrength = - GetFloatAttributeValue(PhysxSuspensionlPrim, "physxVehicleSuspension:springStrength"); - OutWheelData.MaxCompression = - GetFloatAttributeValue(PhysxSuspensionlPrim, "physxVehicleSuspension:maxCompression"); - OutWheelData.MaxDroop = - GetFloatAttributeValue(PhysxSuspensionlPrim, "physxVehicleSuspension:maxDroop"); - OutWheelData.LateralStiffnessX = - GetFloatAttributeValue(PhysxTirePrim, "physxVehicleTire:latStiffX"); - OutWheelData.LateralStiffnessY = - GetFloatAttributeValue(PhysxTirePrim, "physxVehicleTire:latStiffY"); - OutWheelData.LongitudinalStiffness = - GetFloatAttributeValue( - PhysxTirePrim, "physxVehicleTire:longitudinalStiffnessPerUnitGravity"); - - UE_LOG(LogOmniverseUsd, Warning, TEXT("USD values: %f %f %f %f %f %f %f %f %f"), - OutWheelData.MaxBrakeTorque, OutWheelData.MaxHandBrakeTorque, OutWheelData.MaxSteerAngle, - OutWheelData.SpringStrength, OutWheelData.MaxCompression, OutWheelData.MaxDroop, - OutWheelData.LateralStiffnessX, OutWheelData.LateralStiffnessY, OutWheelData.LongitudinalStiffness); + + // Extract and set wheel parameters. + OutWheelData.MaxBrakeTorque = GetFloatAttributeValue(PhysxWheelPrim, "physxVehicleWheel:maxBrakeTorque"); + OutWheelData.MaxHandBrakeTorque = GetFloatAttributeValue(PhysxWheelPrim, "physxVehicleWheel:maxHandBrakeTorque"); + OutWheelData.MaxSteerAngle = GetFloatAttributeValue(PhysxWheelPrim, "physxVehicleWheel:maxSteerAngle"); + OutWheelData.SpringStrength = GetFloatAttributeValue(PhysxSuspensionPrim, "physxVehicleSuspension:springStrength"); + OutWheelData.MaxCompression = GetFloatAttributeValue(PhysxSuspensionPrim, "physxVehicleSuspension:maxCompression"); + OutWheelData.MaxDroop = GetFloatAttributeValue(PhysxSuspensionPrim, "physxVehicleSuspension:maxDroop"); + OutWheelData.LateralStiffnessX = GetFloatAttributeValue(PhysxTirePrim, "physxVehicleTire:latStiffX"); + OutWheelData.LateralStiffnessY = GetFloatAttributeValue(PhysxTirePrim, "physxVehicleTire:latStiffY"); + OutWheelData.LongitudinalStiffness = GetFloatAttributeValue(PhysxTirePrim, "physxVehicleTire:longitudinalStiffnessPerUnitGravity"); return true; }; - // default wheel values, overriden by ParseWheelData if physx data is present - FUSDCARLAWheelData Wheel0 = - {8.f, 16.f, 0.61f, 0.f, 0.f, 0.1f, 0.f, 20.f, 3000.f}; // front left - FUSDCARLAWheelData Wheel1 = - {8.f, 16.f, 0.61f, 0.f, 0.f, 0.1f, 0.f, 20.f, 3000.f}; // front right - FUSDCARLAWheelData Wheel2 = - {8.f, 16.f, 0.f, 0.f, 5.f, 0.1f, 0.f, 20.f, 3000.f}; // rear left - FUSDCARLAWheelData Wheel3 = - {8.f, 16.f, 0.f, 0.f, 5.f, 0.1f, 0.f, 20.f, 3000.f}; // rear right + + // Define default wheel data, which will be overridden if parsed successfully. + FUSDCARLAWheelData Wheel0 = {8.f, 16.f, 0.61f, 0.f, 0.f, 0.1f, 0.f, 20.f, 3000.f}; // front left + FUSDCARLAWheelData Wheel1 = {8.f, 16.f, 0.61f, 0.f, 0.f, 0.1f, 0.f, 20.f, 3000.f}; // front right + FUSDCARLAWheelData Wheel2 = {8.f, 16.f, 0.f, 0.f, 5.f, 0.1f, 0.f, 20.f, 3000.f}; // rear left + FUSDCARLAWheelData Wheel3 = {8.f, 16.f, 0.f, 0.f, 5.f, 0.1f, 0.f, 20.f, 3000.f}; // rear right + + // Parse the data for each wheel. ParseWheelData("wheel_0", Wheel0); ParseWheelData("wheel_1", Wheel1); ParseWheelData("wheel_2", Wheel2); ParseWheelData("wheel_3", Wheel3); return {Wheel0, Wheel1, Wheel2, Wheel3}; -} \ No newline at end of file +}