Compare commits
No commits in common. "main" and "Noah_DataTransfer_1.0" have entirely different histories.
main
...
Noah_DataT
Binary file not shown.
Binary file not shown.
Binary file not shown.
@ -111,12 +111,7 @@ template <typename ComponentType> void AMujocoVolumeActor::AssignComponentsToArr
|
|||||||
|
|
||||||
void AMujocoVolumeActor::InitializeMujoco()
|
void AMujocoVolumeActor::InitializeMujoco()
|
||||||
{
|
{
|
||||||
InitializeMujocoScene_WithContactExclusion(TMap<FString, FString>{});
|
if (!Options)
|
||||||
}
|
|
||||||
|
|
||||||
void AMujocoVolumeActor::InitializeMujocoScene_WithContactExclusion(const TMap<FString, FString>& ContactExclusion)
|
|
||||||
{
|
|
||||||
if (!Options)
|
|
||||||
{
|
{
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -154,7 +149,7 @@ void AMujocoVolumeActor::InitializeMujocoScene_WithContactExclusion(const TMap<F
|
|||||||
}
|
}
|
||||||
|
|
||||||
TUniquePtr<FMujocoXmlGenerator> Generator = MakeUnique<FMujocoXmlGenerator>();
|
TUniquePtr<FMujocoXmlGenerator> Generator = MakeUnique<FMujocoXmlGenerator>();
|
||||||
TUniquePtr<tinyxml2::XMLDocument> Doc = Generator->GenerateMujocoXml(Options, Objects, ExportFilename, ContactExclusion);
|
TUniquePtr<tinyxml2::XMLDocument> Doc = Generator->GenerateMujocoXml(Options, Objects, ExportFilename);
|
||||||
|
|
||||||
FString XmlString;
|
FString XmlString;
|
||||||
tinyxml2::XMLPrinter Printer;
|
tinyxml2::XMLPrinter Printer;
|
||||||
@ -169,8 +164,6 @@ void AMujocoVolumeActor::InitializeMujocoScene_WithContactExclusion(const TMap<F
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// TODO Here we should check for mujoco dll if we are on windows and LOG an error if there is not + gently quit the game
|
|
||||||
|
|
||||||
std::array<char, 1024> ErrMsg{};
|
std::array<char, 1024> ErrMsg{};
|
||||||
MujocoModel = MakeMujocoModelPtr(mj_loadXML(TCHAR_TO_ANSI(*ExportFilename), nullptr, ErrMsg.data(), ErrMsg.size()));
|
MujocoModel = MakeMujocoModelPtr(mj_loadXML(TCHAR_TO_ANSI(*ExportFilename), nullptr, ErrMsg.data(), ErrMsg.size()));
|
||||||
if (!MujocoModel)
|
if (!MujocoModel)
|
||||||
@ -203,12 +196,6 @@ void AMujocoVolumeActor::InitializeMujocoScene_WithContactExclusion(const TMap<F
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
mjData_& AMujocoVolumeActor::GetMujocoData() const
|
|
||||||
{
|
|
||||||
check(MujocoData.IsValid());
|
|
||||||
return *MujocoData.Get();
|
|
||||||
}
|
|
||||||
|
|
||||||
void AMujocoVolumeActor::SetActuatorValue(const FString& ActuatorName, double Value)
|
void AMujocoVolumeActor::SetActuatorValue(const FString& ActuatorName, double Value)
|
||||||
{
|
{
|
||||||
if (MujocoModel)
|
if (MujocoModel)
|
||||||
@ -404,13 +391,11 @@ void AMujocoVolumeActor::Tick(float DeltaTime)
|
|||||||
{
|
{
|
||||||
if (MujocoData)
|
if (MujocoData)
|
||||||
{
|
{
|
||||||
// Default SimStepsPerGameFrame = 16 x 1ms for roughly 60FPS
|
mj_step(MujocoModel.Get(), MujocoData.Get());
|
||||||
// If ticks are strictly 16.666 ms then simulation will lag behind UE clock
|
|
||||||
// Anyway, we need a proper synchronisation between UE and Sim times - probably using TempoTime?
|
for (int32 Frame = 0; Frame < FrameSkip; ++Frame)
|
||||||
for (int32 SimStep = 0; SimStep < SimStepsPerGameFrame; ++SimStep)
|
|
||||||
{
|
{
|
||||||
mj_step(MujocoModel.Get(), MujocoData.Get());
|
mj_step(MujocoModel.Get(), MujocoData.Get());
|
||||||
PostPhysicStepDelegate.ExecuteIfBound(MujocoData->time);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
for (int32 i = 1; i < BodyComponents.Num(); ++i)
|
for (int32 i = 1; i < BodyComponents.Num(); ++i)
|
||||||
|
@ -1255,11 +1255,7 @@ bool FMujocoXmlGenerator::ParseActorAsset(AActor* Actor, tinyxml2::XMLElement* R
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
TUniquePtr<tinyxml2::XMLDocument> FMujocoXmlGenerator::GenerateMujocoXml(
|
TUniquePtr<tinyxml2::XMLDocument> FMujocoXmlGenerator::GenerateMujocoXml(const TObjectPtr<UMujocoExportOptions>& ExportOptions, const TArray<UObject*>& Objects, const FString& ExportFilename)
|
||||||
const TObjectPtr<UMujocoExportOptions>& ExportOptions,
|
|
||||||
const TArray<UObject*>& Objects,
|
|
||||||
const FString& ExportFilename,
|
|
||||||
TMap<FString, FString> ContactExclusion)
|
|
||||||
{
|
{
|
||||||
TUniquePtr<tinyxml2::XMLDocument> Doc = MakeUnique<tinyxml2::XMLDocument>();
|
TUniquePtr<tinyxml2::XMLDocument> Doc = MakeUnique<tinyxml2::XMLDocument>();
|
||||||
Doc->InsertFirstChild(Doc->NewDeclaration("xml version=\"1.0\" encoding=\"utf-8\""));
|
Doc->InsertFirstChild(Doc->NewDeclaration("xml version=\"1.0\" encoding=\"utf-8\""));
|
||||||
@ -1272,30 +1268,6 @@ TUniquePtr<tinyxml2::XMLDocument> FMujocoXmlGenerator::GenerateMujocoXml(
|
|||||||
Root->InsertEndChild(Doc->NewElement("equality"));
|
Root->InsertEndChild(Doc->NewElement("equality"));
|
||||||
Root->InsertEndChild(Doc->NewElement("tendon"));
|
Root->InsertEndChild(Doc->NewElement("tendon"));
|
||||||
Root->InsertEndChild(Doc->NewElement("actuator"));
|
Root->InsertEndChild(Doc->NewElement("actuator"));
|
||||||
|
|
||||||
// TODO Refacto using property from the MujocoActor aka the robot
|
|
||||||
// TODO Maybe using a ParentObject as parameter which holds that information?
|
|
||||||
// TODO Need actor refactoring anyway - Merge Pawn and Mujoco Actor?
|
|
||||||
if (!ContactExclusion.IsEmpty())
|
|
||||||
{
|
|
||||||
Root->InsertEndChild(Doc->NewElement("contact"));
|
|
||||||
|
|
||||||
for (auto& [Body1, Body2] : ContactExclusion)
|
|
||||||
{
|
|
||||||
// Don't add empty strings to the map please!
|
|
||||||
if (Body1.IsEmpty() || Body2.IsEmpty()) continue;
|
|
||||||
|
|
||||||
// Create the contact exclusion - formatted as (SO100 example)
|
|
||||||
// <exclude body1="Body_Base" body2="Body_Rotation_Pitch"/>
|
|
||||||
const auto Exclude = Doc->NewElement("exclude");
|
|
||||||
Exclude->SetAttribute("body1", TCHAR_TO_ANSI(*Body1));
|
|
||||||
Exclude->SetAttribute("body2", TCHAR_TO_ANSI(*Body2));
|
|
||||||
|
|
||||||
// Add exclusion to the contact tag
|
|
||||||
Root->FirstChildElement("contact")->InsertEndChild(Exclude);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (ExportOptions->bAddSkyBox)
|
if (ExportOptions->bAddSkyBox)
|
||||||
{
|
{
|
||||||
tinyxml2::XMLElement* TextureElement = AssetRoot->GetDocument()->NewElement("texture");
|
tinyxml2::XMLElement* TextureElement = AssetRoot->GetDocument()->NewElement("texture");
|
||||||
|
@ -21,44 +21,11 @@ DECLARE_DYNAMIC_MULTICAST_DELEGATE(FOnMujocoCompileBegin);
|
|||||||
DECLARE_DYNAMIC_MULTICAST_DELEGATE_OneParam(FOnMujocoCompileError, FString, Error);
|
DECLARE_DYNAMIC_MULTICAST_DELEGATE_OneParam(FOnMujocoCompileError, FString, Error);
|
||||||
DECLARE_DYNAMIC_MULTICAST_DELEGATE(FOnMujocoCompileSuccess);
|
DECLARE_DYNAMIC_MULTICAST_DELEGATE(FOnMujocoCompileSuccess);
|
||||||
|
|
||||||
// To be called after mj_step
|
|
||||||
DECLARE_DELEGATE_OneParam(FPostPhysicUpdate, float);
|
|
||||||
|
|
||||||
|
|
||||||
UCLASS(Blueprintable, BlueprintType)
|
UCLASS(Blueprintable, BlueprintType)
|
||||||
class LUCKYMUJOCO_API AMujocoVolumeActor : public AActor
|
class LUCKYMUJOCO_API AMujocoVolumeActor : public AActor
|
||||||
{
|
{
|
||||||
GENERATED_BODY()
|
GENERATED_BODY()
|
||||||
|
|
||||||
public:
|
|
||||||
AMujocoVolumeActor();
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Initialize the sim scene in headless mujoco
|
|
||||||
*/
|
|
||||||
UFUNCTION(BlueprintCallable, Category = "Mujoco")
|
|
||||||
void InitializeMujoco();
|
|
||||||
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Initialize the sim scene in headless mujoco with a list of contact exclusion
|
|
||||||
* @param ContactExclusion a list of pairs that should be patched in the xml file for contact exclusion (no friction, no collision)
|
|
||||||
* TODO Can't use a default empty map as parameter in blueprints? We shouldn't need to have 2 functions
|
|
||||||
* TODO ContactExclusion should be stored as a property of MujocoActor and not passed in the scene init
|
|
||||||
* TODO This require to cast the Actor in addition to the components list
|
|
||||||
*/
|
|
||||||
UFUNCTION(BlueprintCallable, Category = "Mujoco")
|
|
||||||
void InitializeMujocoScene_WithContactExclusion(const TMap<FString, FString>& ContactExclusion);
|
|
||||||
|
|
||||||
protected:
|
|
||||||
virtual void BeginPlay() override;
|
|
||||||
virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override;
|
|
||||||
virtual void PostRegisterAllComponents() override;
|
|
||||||
virtual void Tick(float DeltaTime) override;
|
|
||||||
virtual void PostInitializeComponents() override;
|
|
||||||
|
|
||||||
private:
|
|
||||||
TMujocoModelPtr MujocoModel;
|
TMujocoModelPtr MujocoModel;
|
||||||
TMujocoDataPtr MujocoData;
|
TMujocoDataPtr MujocoData;
|
||||||
|
|
||||||
@ -83,11 +50,16 @@ private:
|
|||||||
UPROPERTY(Transient, VisibleAnywhere, Category = "Mujoco | Debug")
|
UPROPERTY(Transient, VisibleAnywhere, Category = "Mujoco | Debug")
|
||||||
TArray<TSoftObjectPtr<UMujocoTendonComponent>> TendonComponents;
|
TArray<TSoftObjectPtr<UMujocoTendonComponent>> TendonComponents;
|
||||||
|
|
||||||
|
UFUNCTION(BlueprintCallable, Category = "Mujoco")
|
||||||
|
void InitializeMujoco();
|
||||||
|
|
||||||
template <typename ComponentType> void AssignComponentsToArray(UWorld* World, TArray<TSoftObjectPtr<ComponentType>>& ComponentArray);
|
template <typename ComponentType> void AssignComponentsToArray(UWorld* World, TArray<TSoftObjectPtr<ComponentType>>& ComponentArray);
|
||||||
|
|
||||||
public:
|
public:
|
||||||
UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mujoco | Simulation", meta = (Min = 1, Max = 100, ClampMin = 0, ClampMax = 100))
|
AMujocoVolumeActor();
|
||||||
int32 SimStepsPerGameFrame = 16;
|
|
||||||
|
UPROPERTY(EditAnywhere, BlueprintReadWrite, Category = "Mujoco | Simulation", meta = (Min = 0, Max = 100, ClampMin = 0, ClampMax = 100))
|
||||||
|
int32 FrameSkip = 0;
|
||||||
|
|
||||||
UPROPERTY(EditDefaultsOnly, BlueprintReadWrite, Category = "Mujoco")
|
UPROPERTY(EditDefaultsOnly, BlueprintReadWrite, Category = "Mujoco")
|
||||||
TObjectPtr<UBillboardComponent> SpriteComponent;
|
TObjectPtr<UBillboardComponent> SpriteComponent;
|
||||||
@ -104,33 +76,6 @@ public:
|
|||||||
UPROPERTY(BlueprintAssignable, Category = "Mujoco | Events")
|
UPROPERTY(BlueprintAssignable, Category = "Mujoco | Events")
|
||||||
FOnMujocoCompileSuccess OnMujocoCompileSuccess;
|
FOnMujocoCompileSuccess OnMujocoCompileSuccess;
|
||||||
|
|
||||||
/**
|
|
||||||
* Access MuJoCo scene options and data (e.g. Simulation time) - This is mutable, be careful
|
|
||||||
* @return mjData_ - Full access to mujoco scene options and data
|
|
||||||
*/
|
|
||||||
mjData_& GetMujocoData() const;
|
|
||||||
|
|
||||||
// ---------------------------
|
|
||||||
// ------- POST UPDATE -------
|
|
||||||
// ---------------------------
|
|
||||||
private:
|
|
||||||
FPostPhysicUpdate PostPhysicStepDelegate;
|
|
||||||
public:
|
|
||||||
/**
|
|
||||||
* Register a delegate to be executed after mj_step, useful to fine control actuators
|
|
||||||
* @param Object - The Class to call
|
|
||||||
* @param Func - The Function to call - takes a float as parameter which is the current simulation timestamp
|
|
||||||
*/
|
|
||||||
template<typename UserClass>
|
|
||||||
void BindPostPhysicStepDelegate(UserClass* Object, void (UserClass::*Func)(float))
|
|
||||||
{
|
|
||||||
PostPhysicStepDelegate.BindUObject(Object, Func);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
// -------------------------
|
|
||||||
// ------- ACTUATORS -------
|
|
||||||
// -------------------------
|
|
||||||
UFUNCTION(BlueprintCallable, Category = "Mujoco")
|
UFUNCTION(BlueprintCallable, Category = "Mujoco")
|
||||||
void SetActuatorValue(const FString& ActuatorName, double Value);
|
void SetActuatorValue(const FString& ActuatorName, double Value);
|
||||||
|
|
||||||
@ -149,9 +94,6 @@ public:
|
|||||||
UFUNCTION(BlueprintCallable, BlueprintPure, Category = "Mujoco")
|
UFUNCTION(BlueprintCallable, BlueprintPure, Category = "Mujoco")
|
||||||
FVector2D GetActuatorRangeByIndex(int32 ActuatorIndex) const;
|
FVector2D GetActuatorRangeByIndex(int32 ActuatorIndex) const;
|
||||||
|
|
||||||
// ----------------------
|
|
||||||
// ------- JOINTS -------
|
|
||||||
// ----------------------
|
|
||||||
UFUNCTION(BlueprintCallable, Category = "Mujoco")
|
UFUNCTION(BlueprintCallable, Category = "Mujoco")
|
||||||
void SetJointValue(const FString& JointName, double Value);
|
void SetJointValue(const FString& JointName, double Value);
|
||||||
|
|
||||||
@ -163,4 +105,16 @@ public:
|
|||||||
|
|
||||||
UFUNCTION(BlueprintCallable, BlueprintPure, Category = "Mujoco")
|
UFUNCTION(BlueprintCallable, BlueprintPure, Category = "Mujoco")
|
||||||
double GetJointValueByIndex(int32 JointIndex) const;
|
double GetJointValueByIndex(int32 JointIndex) const;
|
||||||
|
|
||||||
|
|
||||||
|
virtual void PostRegisterAllComponents() override;
|
||||||
|
|
||||||
|
virtual void Tick(float DeltaTime) override;
|
||||||
|
|
||||||
|
virtual void PostInitializeComponents() override;
|
||||||
|
|
||||||
|
protected:
|
||||||
|
|
||||||
|
virtual void BeginPlay() override;
|
||||||
|
virtual void EndPlay(const EEndPlayReason::Type EndPlayReason) override;
|
||||||
};
|
};
|
||||||
|
@ -307,13 +307,13 @@ struct LUCKYMUJOCO_API FMujocoOptions
|
|||||||
{
|
{
|
||||||
GENERATED_BODY()
|
GENERATED_BODY()
|
||||||
|
|
||||||
/** Override TimeStep setting. When enabled, the default value (0.001) is applied. */
|
/** Override TimeStep setting. When enabled, the default value (0.002) is applied. */
|
||||||
UPROPERTY(config, EditAnywhere, BlueprintReadWrite, Category = "Mujoco", meta = (InlineEditConditionToggle))
|
UPROPERTY(config, EditAnywhere, BlueprintReadWrite, Category = "Mujoco", meta = (InlineEditConditionToggle))
|
||||||
bool bOverrideTimeStep = false;
|
bool bOverrideTimeStep = false;
|
||||||
|
|
||||||
/** Simulation time step in seconds. */
|
/** Simulation time step in seconds. */
|
||||||
UPROPERTY(config, EditAnywhere, BlueprintReadWrite, Category = "Mujoco", meta = (Attribute = "timestep", EditCondition = "bOverrideTimeStep", ClampMin = 0.0001, ClampMax = 0.01, UIMin = 0.0001, UIMax = 0.01))
|
UPROPERTY(config, EditAnywhere, BlueprintReadWrite, Category = "Mujoco", meta = (Attribute = "timestep", EditCondition = "bOverrideTimeStep", ClampMin = 0.0001, ClampMax = 0.01, UIMin = 0.0001, UIMax = 0.01))
|
||||||
float TimeStep = 0.001f; // Default to 1ms
|
float TimeStep = 0.002f;
|
||||||
|
|
||||||
/** Override API Rate setting. */
|
/** Override API Rate setting. */
|
||||||
UPROPERTY(config, EditAnywhere, BlueprintReadWrite, Category = "Mujoco", meta = (InlineEditConditionToggle))
|
UPROPERTY(config, EditAnywhere, BlueprintReadWrite, Category = "Mujoco", meta = (InlineEditConditionToggle))
|
||||||
|
@ -35,19 +35,6 @@ class LUCKYMUJOCO_API FMujocoXmlGenerator
|
|||||||
|
|
||||||
TMap<FString, TSoftObjectPtr<UObject>> ObjectMap;
|
TMap<FString, TSoftObjectPtr<UObject>> ObjectMap;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
TUniquePtr<tinyxml2::XMLDocument> GenerateMujocoXml(const TObjectPtr<UMujocoExportOptions>& ExportOptions, const TArray<UObject*>& Objects, const FString& ExportFilename);
|
||||||
/**
|
|
||||||
* Generate the XML file used by the MuJoCo headless scene representing the physics simulation
|
|
||||||
* @param ExportOptions TODO - What they can be?
|
|
||||||
* @param Objects Actors and Components to be added to the scene
|
|
||||||
* @param ExportFilename pretty much that
|
|
||||||
* @param ContactExclusion a list of pairs that should be patched in the xml file for contact exclusion (no friction, no collision)
|
|
||||||
* TODO ContactExclusion should be stored as a property of MujocoActor and not passed in the scene init
|
|
||||||
*/
|
|
||||||
TUniquePtr<tinyxml2::XMLDocument> GenerateMujocoXml(
|
|
||||||
const TObjectPtr<UMujocoExportOptions>& ExportOptions,
|
|
||||||
const TArray<UObject*>& Objects,
|
|
||||||
const FString& ExportFilename,
|
|
||||||
TMap<FString, FString> ContactExclusion);
|
|
||||||
};
|
};
|
@ -141,8 +141,8 @@ public:
|
|||||||
CancelButton->SetEnabled(false);
|
CancelButton->SetEnabled(false);
|
||||||
RequestDestroyWindow();
|
RequestDestroyWindow();
|
||||||
|
|
||||||
const TUniquePtr<FMujocoXmlGenerator> Generator = MakeUnique<FMujocoXmlGenerator>();
|
TUniquePtr<FMujocoXmlGenerator> Generator = MakeUnique<FMujocoXmlGenerator>();
|
||||||
const TUniquePtr<tinyxml2::XMLDocument> Doc = Generator->GenerateMujocoXml(ExportOptions, Objects, ExportFilename, TMap<FString, FString>{});
|
TUniquePtr<tinyxml2::XMLDocument> Doc = Generator->GenerateMujocoXml(ExportOptions, Objects, ExportFilename);
|
||||||
|
|
||||||
FString XmlString;
|
FString XmlString;
|
||||||
tinyxml2::XMLPrinter Printer;
|
tinyxml2::XMLPrinter Printer;
|
||||||
|
@ -19,8 +19,7 @@ public class LuckyWorldV2 : ModuleRules
|
|||||||
"SocketIOClient",
|
"SocketIOClient",
|
||||||
"VaRest",
|
"VaRest",
|
||||||
"SIOJson",
|
"SIOJson",
|
||||||
"NavigationSystem",
|
"NavigationSystem"
|
||||||
"RenderCore"
|
|
||||||
});
|
});
|
||||||
|
|
||||||
PrivateDependencyModuleNames.AddRange(new string[] { });
|
PrivateDependencyModuleNames.AddRange(new string[] { });
|
||||||
|
@ -1,180 +0,0 @@
|
|||||||
// Fill out your copyright notice in the Description page of Project Settings.
|
|
||||||
|
|
||||||
#include "LRRenderUtilLibrary.h"
|
|
||||||
|
|
||||||
#include "Components/SceneCaptureComponent2D.h"
|
|
||||||
#include "Engine/TextureRenderTarget2D.h"
|
|
||||||
#include "Kismet/KismetRenderingLibrary.h"
|
|
||||||
#include "GameFramework/Actor.h"
|
|
||||||
#include "Engine/World.h"
|
|
||||||
|
|
||||||
void ULRRenderUtilLibrary::SetupSceneCaptureForMesh(
|
|
||||||
USceneCaptureComponent2D* SceneCapture,
|
|
||||||
UStaticMeshComponent* MeshComp,
|
|
||||||
TEnumAsByte<enum ESceneCaptureSource> CaptureSource)
|
|
||||||
{
|
|
||||||
if (!SceneCapture || !MeshComp)
|
|
||||||
{
|
|
||||||
UE_LOG(LogTemp, Warning, TEXT("SetupSceneCaptureForMesh: Invalid SceneCapture or MeshComp"));
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!MeshComp->IsValidLowLevel())
|
|
||||||
{
|
|
||||||
UE_LOG(LogTemp, Warning, TEXT("SetupSceneCaptureForMesh: MeshComp is not valid"));
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Set the scene capture to focus on the mesh
|
|
||||||
SceneCapture->ShowOnlyComponent(MeshComp);
|
|
||||||
|
|
||||||
SceneCapture->CaptureSource = CaptureSource;
|
|
||||||
SceneCapture->bCaptureEveryFrame = false;
|
|
||||||
SceneCapture->bCaptureOnMovement = false;
|
|
||||||
SceneCapture->FOVAngle = 90.f;
|
|
||||||
|
|
||||||
// Set a solid background color
|
|
||||||
SceneCapture->CompositeMode = ESceneCaptureCompositeMode::SCCM_Overwrite;
|
|
||||||
|
|
||||||
// Ensure we have a valid texture target
|
|
||||||
if (SceneCapture->TextureTarget)
|
|
||||||
{
|
|
||||||
SceneCapture->TextureTarget->ClearColor = FLinearColor::Transparent;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
UE_LOG(LogTemp, Warning, TEXT("SetupSceneCaptureForMesh: TextureTarget is null"));
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Adjust the transform to frame the mesh
|
|
||||||
FVector MeshBounds = MeshComp->Bounds.BoxExtent;
|
|
||||||
FVector MeshOrigin = MeshComp->Bounds.Origin;
|
|
||||||
|
|
||||||
// Calculate the camera distance based on mesh size
|
|
||||||
float MaxExtent = FMath::Max3(MeshBounds.X, MeshBounds.Y, MeshBounds.Z);
|
|
||||||
float CameraDistance = MaxExtent * 2.5f; // Adjusted to ensure mesh fits in view
|
|
||||||
|
|
||||||
// Calculate the camera location - position from front of mesh (+X axis)
|
|
||||||
FVector CameraLocation = MeshOrigin + FVector(CameraDistance, 0.f, 0.f);
|
|
||||||
|
|
||||||
// Calculate the camera rotation to look at mesh center
|
|
||||||
FRotator CameraRotation = (MeshOrigin - CameraLocation).Rotation();
|
|
||||||
|
|
||||||
SceneCapture->SetWorldLocationAndRotation(CameraLocation, CameraRotation);
|
|
||||||
|
|
||||||
// Register component to make sure it will render
|
|
||||||
if (!SceneCapture->IsRegistered())
|
|
||||||
{
|
|
||||||
SceneCapture->RegisterComponent();
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
UTextureRenderTarget2D* ULRRenderUtilLibrary::CaptureMeshToRenderTarget(
|
|
||||||
UStaticMeshComponent* MeshComp,
|
|
||||||
const FVector2D& ImageSize,
|
|
||||||
UObject* WorldContextObject,
|
|
||||||
TEnumAsByte<enum ESceneCaptureSource> CaptureSource)
|
|
||||||
{
|
|
||||||
if (!MeshComp || !WorldContextObject || !WorldContextObject->GetWorld())
|
|
||||||
{
|
|
||||||
UE_LOG(LogTemp, Warning, TEXT("CaptureMeshToRenderTarget: Invalid parameters"));
|
|
||||||
return nullptr;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Create a render target with proper size
|
|
||||||
UTextureRenderTarget2D* RenderTarget = UKismetRenderingLibrary::CreateRenderTarget2D(
|
|
||||||
WorldContextObject,
|
|
||||||
FMath::Max(32, static_cast<int32>(ImageSize.X)),
|
|
||||||
FMath::Max(32, static_cast<int32>(ImageSize.Y)),
|
|
||||||
ETextureRenderTargetFormat::RTF_RGBA8);
|
|
||||||
|
|
||||||
if (!RenderTarget)
|
|
||||||
{
|
|
||||||
UE_LOG(LogTemp, Warning, TEXT("CaptureMeshToRenderTarget: Failed to create render target"));
|
|
||||||
return nullptr;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Create a temporary actor to hold the scene capture component
|
|
||||||
AActor* TempActor = WorldContextObject->GetWorld()->SpawnActor<AActor>();
|
|
||||||
if (!TempActor)
|
|
||||||
{
|
|
||||||
UE_LOG(LogTemp, Warning, TEXT("CaptureMeshToRenderTarget: Failed to spawn temporary actor"));
|
|
||||||
return RenderTarget;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Create a root component if it doesn't exist
|
|
||||||
if (!TempActor->GetRootComponent())
|
|
||||||
{
|
|
||||||
USceneComponent* RootComponent = NewObject<USceneComponent>(TempActor, TEXT("RootComponent"));
|
|
||||||
TempActor->SetRootComponent(RootComponent);
|
|
||||||
RootComponent->RegisterComponent();
|
|
||||||
}
|
|
||||||
|
|
||||||
// Create and set up scene capture component
|
|
||||||
USceneCaptureComponent2D* SceneCapture = NewObject<USceneCaptureComponent2D>(TempActor);
|
|
||||||
if (SceneCapture)
|
|
||||||
{
|
|
||||||
SceneCapture->RegisterComponent();
|
|
||||||
SceneCapture->AttachToComponent(TempActor->GetRootComponent(), FAttachmentTransformRules::KeepRelativeTransform);
|
|
||||||
SceneCapture->TextureTarget = RenderTarget;
|
|
||||||
|
|
||||||
// Setup the scene capture
|
|
||||||
SetupSceneCaptureForMesh(SceneCapture, MeshComp, CaptureSource);
|
|
||||||
|
|
||||||
// Clear the render target
|
|
||||||
UKismetRenderingLibrary::ClearRenderTarget2D(WorldContextObject, RenderTarget, FLinearColor::Transparent);
|
|
||||||
|
|
||||||
// Disable post-processing effects
|
|
||||||
SceneCapture->PostProcessSettings.bOverride_AutoExposureMethod = true;
|
|
||||||
SceneCapture->PostProcessSettings.AutoExposureMethod = EAutoExposureMethod::AEM_Manual;
|
|
||||||
SceneCapture->PostProcessSettings.bOverride_AutoExposureBias = true;
|
|
||||||
SceneCapture->PostProcessSettings.AutoExposureBias = 1.0f;
|
|
||||||
SceneCapture->PostProcessSettings.bOverride_BloomIntensity = true;
|
|
||||||
SceneCapture->PostProcessSettings.BloomIntensity = 0.0f;
|
|
||||||
|
|
||||||
// Trigger a one-time capture
|
|
||||||
SceneCapture->CaptureScene();
|
|
||||||
|
|
||||||
// Force the GPU to complete rendering
|
|
||||||
FlushRenderingCommands();
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
UE_LOG(LogTemp, Warning, TEXT("CaptureMeshToRenderTarget: Failed to create scene capture component"));
|
|
||||||
}
|
|
||||||
|
|
||||||
// Clean up the temporary actor
|
|
||||||
TempActor->Destroy();
|
|
||||||
|
|
||||||
return RenderTarget;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool ULRRenderUtilLibrary::CaptureSceneNow(USceneCaptureComponent2D* SceneCapture)
|
|
||||||
{
|
|
||||||
if (!SceneCapture || !SceneCapture->IsValidLowLevel())
|
|
||||||
{
|
|
||||||
UE_LOG(LogTemp, Warning, TEXT("CaptureSceneNow: Invalid scene capture component"));
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!SceneCapture->TextureTarget)
|
|
||||||
{
|
|
||||||
UE_LOG(LogTemp, Warning, TEXT("CaptureSceneNow: Scene capture has no texture target"));
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
// Ensure component is registered
|
|
||||||
if (!SceneCapture->IsRegistered())
|
|
||||||
{
|
|
||||||
SceneCapture->RegisterComponent();
|
|
||||||
}
|
|
||||||
|
|
||||||
// Trigger the capture
|
|
||||||
SceneCapture->CaptureScene();
|
|
||||||
|
|
||||||
// Force the GPU to complete rendering
|
|
||||||
FlushRenderingCommands();
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
@ -1,57 +0,0 @@
|
|||||||
// Fill out your copyright notice in the Description page of Project Settings.
|
|
||||||
|
|
||||||
#pragma once
|
|
||||||
|
|
||||||
#include "CoreMinimal.h"
|
|
||||||
#include "Kismet/BlueprintFunctionLibrary.h"
|
|
||||||
#include "LRRenderUtilLibrary.generated.h"
|
|
||||||
|
|
||||||
class USceneCaptureComponent2D;
|
|
||||||
class UTextureRenderTarget2D;
|
|
||||||
class UStaticMeshComponent;
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Utility library for capturing and rendering objects in the Lucky Robots system
|
|
||||||
*/
|
|
||||||
UCLASS(BlueprintType, Blueprintable)
|
|
||||||
class LUCKYWORLDV2_API ULRRenderUtilLibrary : public UBlueprintFunctionLibrary
|
|
||||||
{
|
|
||||||
GENERATED_BODY()
|
|
||||||
|
|
||||||
public:
|
|
||||||
/**
|
|
||||||
* Captures a static mesh component to a render target texture
|
|
||||||
* @param MeshComp The static mesh component to capture
|
|
||||||
* @param ImageSize The size of the output image
|
|
||||||
* @param WorldContextObject The world context
|
|
||||||
* @param CaptureSource The type of data to capture (default is BaseColor)
|
|
||||||
* @return The rendered texture
|
|
||||||
*/
|
|
||||||
UFUNCTION(BlueprintCallable, Category = "Lucky Robots|Render Utilities")
|
|
||||||
static UTextureRenderTarget2D* CaptureMeshToRenderTarget(
|
|
||||||
UStaticMeshComponent* MeshComp,
|
|
||||||
const FVector2D& ImageSize,
|
|
||||||
|
|
||||||
UObject* WorldContextObject,
|
|
||||||
TEnumAsByte<enum ESceneCaptureSource> CaptureSource = ESceneCaptureSource::SCS_BaseColor);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Sets up a scene capture component to focus on a specific mesh
|
|
||||||
* @param SceneCapture The scene capture component to set up
|
|
||||||
* @param MeshComp The static mesh component to focus on
|
|
||||||
* @param CaptureSource The type of data to capture (default is BaseColor)
|
|
||||||
*/
|
|
||||||
UFUNCTION(BlueprintCallable, Category = "Lucky Robots|Render Utilities")
|
|
||||||
static void SetupSceneCaptureForMesh(
|
|
||||||
USceneCaptureComponent2D* SceneCapture,
|
|
||||||
UStaticMeshComponent* MeshComp,
|
|
||||||
TEnumAsByte<enum ESceneCaptureSource> CaptureSource = ESceneCaptureSource::SCS_BaseColor);
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Captures the current view of a scene capture component to its render target
|
|
||||||
* @param SceneCapture The scene capture component to trigger
|
|
||||||
* @return Success status
|
|
||||||
*/
|
|
||||||
UFUNCTION(BlueprintCallable, Category = "Lucky Robots|Render Utilities")
|
|
||||||
static bool CaptureSceneNow(USceneCaptureComponent2D* SceneCapture);
|
|
||||||
};
|
|
@ -6,38 +6,6 @@ set "UE_PATH=C:\Program Files\UE_5.5"
|
|||||||
set "PROJECT_PATH=%~dp0"
|
set "PROJECT_PATH=%~dp0"
|
||||||
set "UAT_PATH=%UE_PATH%\Engine\Build\BatchFiles\RunUAT.bat"
|
set "UAT_PATH=%UE_PATH%\Engine\Build\BatchFiles\RunUAT.bat"
|
||||||
|
|
||||||
|
|
||||||
:: Check if MuJoCo DLL exists in bin directory
|
|
||||||
if not exist "%MUJOCO_BIN_PATH%\mujoco.dll" (
|
|
||||||
echo Error: MuJoCo DLL not found at %MUJOCO_BIN_PATH%\mujoco.dll
|
|
||||||
echo Please ensure the MuJoCo DLL is properly built and placed in the correct location.
|
|
||||||
pause
|
|
||||||
exit /b 1
|
|
||||||
)
|
|
||||||
|
|
||||||
:: Copy MuJoCo DLL to the plugin binaries directory if it doesn't exist there
|
|
||||||
if not exist "%MUJOCO_DLL_PATH%\mujoco.dll" (
|
|
||||||
echo Copying MuJoCo DLL to plugin binaries directory...
|
|
||||||
copy "%MUJOCO_BIN_PATH%\mujoco.dll" "%MUJOCO_DLL_PATH%\"
|
|
||||||
if errorlevel 1 (
|
|
||||||
echo Failed to copy MuJoCo DLL
|
|
||||||
pause
|
|
||||||
exit /b 1
|
|
||||||
)
|
|
||||||
)
|
|
||||||
|
|
||||||
:: Add UE and MuJoCo paths to PATH environment variable
|
|
||||||
set "PATH=%UE_PATH%\Engine\Binaries\Win64;%MUJOCO_DLL_PATH%;%MUJOCO_BIN_PATH%;%PATH%"
|
|
||||||
|
|
||||||
:: Set the DLL search path for the current process
|
|
||||||
set "PATH=%PATH%;%MUJOCO_DLL_PATH%;%MUJOCO_BIN_PATH%"
|
|
||||||
|
|
||||||
:: Run the Unreal Editor
|
|
||||||
:: echo Starting Unreal Editor...
|
|
||||||
:: start "" "%UE_PATH%\Engine\Binaries\Win64\UnrealEditor.exe" "%PROJECT_PATH%LuckyWorldV2.uproject"
|
|
||||||
|
|
||||||
endlocal
|
|
||||||
|
|
||||||
:: Build and package command
|
:: Build and package command
|
||||||
"%UAT_PATH%" ^
|
"%UAT_PATH%" ^
|
||||||
-ScriptsForProject="%PROJECT_PATH%LuckyWorldV2.uproject" ^
|
-ScriptsForProject="%PROJECT_PATH%LuckyWorldV2.uproject" ^
|
||||||
|
Loading…
x
Reference in New Issue
Block a user