Compare commits
3 Commits
a5bbfa56ea
...
e63695a453
Author | SHA1 | Date | |
---|---|---|---|
|
e63695a453 | ||
|
947556661a | ||
|
bf89adc9b9 |
Binary file not shown.
Binary file not shown.
Binary file not shown.
@ -115,7 +115,13 @@ void AMujocoVolumeActor::BindPostPhysicDelegate(UserClass* Object, void(UserClas
|
||||
PostPhysicUpdateDelegate.BindUObject(Object, Func);
|
||||
}
|
||||
|
||||
void AMujocoVolumeActor::InitializeMujoco(TMap<FString, FString> ContactExclusion)
|
||||
|
||||
void AMujocoVolumeActor::InitializeMujoco()
|
||||
{
|
||||
InitializeMujocoScene_WithContactExclusion(TMap<FString, FString>{});
|
||||
}
|
||||
|
||||
void AMujocoVolumeActor::InitializeMujocoScene_WithContactExclusion(const TMap<FString, FString>& ContactExclusion)
|
||||
{
|
||||
if (!Options)
|
||||
{
|
||||
@ -170,6 +176,8 @@ void AMujocoVolumeActor::InitializeMujoco(TMap<FString, FString> ContactExclusio
|
||||
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{};
|
||||
MujocoModel = MakeMujocoModelPtr(mj_loadXML(TCHAR_TO_ANSI(*ExportFilename), nullptr, ErrMsg.data(), ErrMsg.size()));
|
||||
if (!MujocoModel)
|
||||
|
@ -33,15 +33,23 @@ class LUCKYMUJOCO_API AMujocoVolumeActor : public AActor
|
||||
public:
|
||||
AMujocoVolumeActor();
|
||||
|
||||
UFUNCTION(BlueprintCallable, Category = "Mujoco")
|
||||
|
||||
/**
|
||||
* 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
|
||||
*/
|
||||
void InitializeMujoco(TMap<FString, FString> ContactExclusion);
|
||||
UFUNCTION(BlueprintCallable, Category = "Mujoco")
|
||||
void InitializeMujocoScene_WithContactExclusion(const TMap<FString, FString>& ContactExclusion);
|
||||
|
||||
protected:
|
||||
virtual void BeginPlay() override;
|
||||
|
@ -307,7 +307,7 @@ struct LUCKYMUJOCO_API FMujocoOptions
|
||||
{
|
||||
GENERATED_BODY()
|
||||
|
||||
/** Override TimeStep setting. When enabled, the default value (0.002) is applied. */
|
||||
/** Override TimeStep setting. When enabled, the default value (0.001) is applied. */
|
||||
UPROPERTY(config, EditAnywhere, BlueprintReadWrite, Category = "Mujoco", meta = (InlineEditConditionToggle))
|
||||
bool bOverrideTimeStep = false;
|
||||
|
||||
|
Loading…
x
Reference in New Issue
Block a user