diff --git a/Config/DefaultEngine.ini b/Config/DefaultEngine.ini index 40d5e6d..4a2dac9 100644 --- a/Config/DefaultEngine.ini +++ b/Config/DefaultEngine.ini @@ -23,4 +23,5 @@ r.DefaultFeature.AutoExposure=False [CoreRedirects] +ClassRedirects=(OldName="/Script/PBDRobotics.Joint",NewName="/Script/PBDRobotics.Joint") +PropertyRedirects=(OldName="/Script/PBDRobotics.Joint.PrevLink",NewName="/Script/PBDRobotics.Joint.FirstLink") -+PropertyRedirects=(OldName="/Script/PBDRobotics.Joint.NextLink",NewName="/Script/PBDRobotics.Joint.SecondLink") \ No newline at end of file ++PropertyRedirects=(OldName="/Script/PBDRobotics.Joint.NextLink",NewName="/Script/PBDRobotics.Joint.SecondLink") ++PropertyRedirects=(OldName="/Script/PBDRobotics.Robot.Parts",NewName="/Script/PBDRobotics.Robot.Links") \ No newline at end of file diff --git a/Content/Blueprints/BP_Puma.uasset b/Content/Blueprints/BP_Puma.uasset index f764713..d35a0a9 100644 Binary files a/Content/Blueprints/BP_Puma.uasset and b/Content/Blueprints/BP_Puma.uasset differ diff --git a/Content/Blueprints/BP_Robot.uasset b/Content/Blueprints/BP_Robot.uasset index 87117cc..7dd3c98 100644 Binary files a/Content/Blueprints/BP_Robot.uasset and b/Content/Blueprints/BP_Robot.uasset differ diff --git a/Content/Blueprints/BP_TestBot.uasset b/Content/Blueprints/BP_TestBot.uasset deleted file mode 100644 index 4e0f8da..0000000 Binary files a/Content/Blueprints/BP_TestBot.uasset and /dev/null differ diff --git a/Content/Blueprints/BP_TestCube.uasset b/Content/Blueprints/BP_TestCube.uasset deleted file mode 100644 index 815eba9..0000000 Binary files a/Content/Blueprints/BP_TestCube.uasset and /dev/null differ diff --git a/Content/Levels/Main.umap b/Content/Levels/Main.umap index b6dd1d4..7adfc03 100644 Binary files a/Content/Levels/Main.umap and b/Content/Levels/Main.umap differ diff --git a/Source/PBDRobotics/Joint.cpp b/Source/PBDRobotics/Joint.cpp index 2598100..e37b182 100644 --- a/Source/PBDRobotics/Joint.cpp +++ b/Source/PBDRobotics/Joint.cpp @@ -72,7 +72,7 @@ void UJoint::SolvePosition(const double H) const{ Vector3d Q; if (L2->IsEffector){ const Quaterniond Tq = L1->Orientation * L2->Orientation.inverse(); - Q = 2 * Tq.vec(); + Q = -2 * Tq.vec(); } else{ const Vector3d A1 = GetFirstWorldAxis(); const Vector3d A2 = GetSecondWorldAxis(); diff --git a/Source/PBDRobotics/Link.cpp b/Source/PBDRobotics/Link.cpp index 7564757..3c21d02 100644 --- a/Source/PBDRobotics/Link.cpp +++ b/Source/PBDRobotics/Link.cpp @@ -45,8 +45,6 @@ void ULink::SetupProperties(){ Mass = 1e50; Inertia_Tensor_Local = Vector3d::Ones().asDiagonal() * 1e50; } - - Log(GetInertia()); } void ULink::SetupJoints() const { diff --git a/Source/PBDRobotics/Robot.cpp b/Source/PBDRobotics/Robot.cpp index 6980fb7..d77fff4 100644 --- a/Source/PBDRobotics/Robot.cpp +++ b/Source/PBDRobotics/Robot.cpp @@ -3,42 +3,57 @@ #include "Robot.h" -#include "util.h" - - ARobot::ARobot(){ PrimaryActorTick.bCanEverTick = true; } void ARobot::BeginPlay(){ Super::BeginPlay(); - - GetComponents(Parts); - for (auto* Link : Parts){ + + for (auto* Link : Links) Link->Setup(); - if (Link->PrevJoint) - Joints.Add(Link->PrevJoint); + ResetPositionAndOrientation(); +} + +void ARobot::ResetPositionAndOrientation(){ + for (const auto* Joint : Joints){ + const ULink* L1 = Joint->FirstLink; + ULink* L2 = Joint->SecondLink; + + Vector3d ConnectPosL1 = L1->Position + Joint->GetFirstWorldDirection(); + const Vector3d Correction = ConnectPosL1 - Joint->GetSecondWorldDirection(); + L2->Position = Correction; } +} - // Example: 3 Parts are connected with 2 Joints - assert(Parts.Num() == Joints.Num() + 1); + +void ARobot::Connect(ULink* L1, ULink* L2){ + Links.AddUnique(L1); + Links.Add(L2); + UJoint* Joint = NewObject(this); + Joint->FirstLink = L1; + Joint->SecondLink = L2; + L1->NextJoint = Joint; + L2->PrevJoint = Joint; + Joints.Add(Joint); } + void ARobot::Tick(const float DeltaTime){ Super::Tick(DeltaTime); - constexpr int SubSteps = 30; + constexpr int SubSteps = 50; const double h = DeltaTime / SubSteps; for (int i = 0; i < SubSteps; i++){ - for (auto* Link : Parts) + for (auto* Link : Links) Link->Update(h); for (const auto* Joint : Joints) Joint->SolvePosition(h); - for (auto* Link : Parts) + for (auto* Link : Links) Link->Integrate(h); for (const auto* Joint : Joints) Joint->SolveVelocity(h); } - for (auto* Link : Parts) + for (auto* Link : Links) Link->UpdateInternalTransform(); } diff --git a/Source/PBDRobotics/Robot.h b/Source/PBDRobotics/Robot.h index 6f1c32e..90bf5e1 100644 --- a/Source/PBDRobotics/Robot.h +++ b/Source/PBDRobotics/Robot.h @@ -12,21 +12,22 @@ class PBDROBOTICS_API ARobot : public AActor { GENERATED_BODY() public: - // Sets default values for this actor's properties ARobot(); protected: - // Called when the game starts or when spawned virtual void BeginPlay() override; -public: - // Called every frame - virtual void Tick(float DeltaTime) override; + UPROPERTY(BlueprintReadWrite) + TArray Links = TArray(); -private: - UPROPERTY() - TArray Parts; - - UPROPERTY() + UPROPERTY(BlueprintReadWrite) TArray Joints = TArray(); + + UFUNCTION(BlueprintCallable) + void Connect(ULink* L1, ULink* L2); + +private: + void ResetPositionAndOrientation(); +public: + virtual void Tick(float DeltaTime) override; };