Skip to content

Commit

Permalink
More fixes, gravity and basic shapes work
Browse files Browse the repository at this point in the history
  • Loading branch information
Lamakaio committed Jun 6, 2024
1 parent 638be0b commit f6ba0e0
Show file tree
Hide file tree
Showing 4 changed files with 92 additions and 14 deletions.
24 changes: 23 additions & 1 deletion src/ospjolt/activescene/joltinteg.h
Original file line number Diff line number Diff line change
Expand Up @@ -44,6 +44,7 @@
#include <Jolt/Core/TempAllocator.h>
#include <Jolt/Physics/Collision/Shape/CompoundShape.h>
#include <Jolt/Physics/Collision/Shape/MutableCompoundShape.h>
#include <Jolt/Physics/PhysicsStepListener.h>
#include <Jolt/Core/JobSystemSingleThreaded.h>

#include <longeron/id_management/registry_stl.hpp>
Expand Down Expand Up @@ -196,6 +197,20 @@ class ObjectVsBroadPhaseLayerFilterImpl : public ObjectVsBroadPhaseLayerFilter
}
}
};

//Forward declaration
struct ACtxJoltWorld;

class PhysicsStepListenerImpl : public PhysicsStepListener
{
public:
PhysicsStepListenerImpl(ACtxJoltWorld* pContext) : m_context(pContext) {};
virtual void OnStep(float inDeltaTime, PhysicsSystem& inPhysicsSystem) override;

private:
ACtxJoltWorld* m_context;
};

using TransformedShapePtr_t = std::unique_ptr<TransformedShape>;
using ShapeStorage_t = osp::Storage_t<osp::active::ActiveEnt, TransformedShapePtr_t>;

Expand All @@ -216,7 +231,7 @@ struct ACtxJoltWorld
// The default values are the one suggested in the Jolt hello world exemple for a "real" project.
// It might be overkill here.
//TODO temp allocator
ACtxJoltWorld(
ACtxJoltWorld( int threadCount = 2,
uint maxBodies = 65536,
uint numBodyMutexes = 0,
uint maxBodyPairs = 65536,
Expand All @@ -231,6 +246,9 @@ struct ACtxJoltWorld
m_bPLInterface,
m_objectVsBPLFilter,
m_objectLayerFilter);
m_world->SetGravity(Vec3Arg::sZero());
m_listener = std::make_unique<PhysicsStepListenerImpl>(this);
m_world->AddStepListener(m_listener.get());
}

static void initJoltGlobal()
Expand Down Expand Up @@ -262,6 +280,8 @@ struct ACtxJoltWorld

std::unique_ptr<PhysicsSystem> m_world;

std::unique_ptr<PhysicsStepListenerImpl> m_listener;

lgrn::IdRegistryStl<OspBodyId> m_bodyIds;
//std::vector<JoltBodyPtr_t> m_bodyPtrs;
std::vector<ForceFactors_t> m_bodyFactors;
Expand All @@ -274,8 +294,10 @@ struct ACtxJoltWorld
std::vector<ForceFactorFunc> m_factors;
ShapeStorage_t m_shapes;


osp::active::ACompTransformStorage_t *m_pTransform;
};



}
61 changes: 56 additions & 5 deletions src/ospjolt/activescene/joltinteg_fn.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,16 +67,16 @@ void SysJolt::update_translate(ACtxPhysics& rCtxPhys, ACtxJoltWorld& rCtxWorld)
BodyIDVector allBodiesIds;
pJoltWorld->GetBodies(allBodiesIds);

BodyInterface &body_interface = pJoltWorld->GetBodyInterface();
BodyInterface &bodyInterface = pJoltWorld->GetBodyInterface();

// Translate every jolt body
for (JoltBodyId bodyId : allBodiesIds)
{
RVec3 position = body_interface.GetPosition(bodyId);
RVec3 position = bodyInterface.GetPosition(bodyId);
Matrix4 matrix;
position += RVec3(translate.x(), translate.y(), translate.z());
//As we are translating the whole world, we don't need to wake up asleep bodies.
body_interface.SetPosition(bodyId, position, EActivation::DontActivate);
bodyInterface.SetPosition(bodyId, position, EActivation::DontActivate);
}
}
}
Expand All @@ -91,15 +91,15 @@ void SysJolt::update_world(
ACompTransformStorage_t& rTf) noexcept
{
PhysicsSystem *pJoltWorld = rCtxWorld.m_world.get();
BodyInterface &body_interface = pJoltWorld->GetBodyInterface();
BodyInterface &bodyInterface = pJoltWorld->GetBodyInterface();

// Apply changed velocities
for (auto const& [ent, vel] : std::exchange(rCtxPhys.m_setVelocity, {}))
{
OspBodyId const ospBodyId = rCtxWorld.m_entToBody.at(ent);
JoltBodyId const bodyId = rCtxWorld.m_ospToJoltBodyId[ospBodyId];

body_interface.SetLinearVelocity(bodyId, Vec3(vel.x(), vel.y(), vel.z()));
bodyInterface.SetLinearVelocity(bodyId, Vec3(vel.x(), vel.y(), vel.z()));
}

rCtxWorld.m_pTransform = std::addressof(rTf);
Expand All @@ -115,6 +115,7 @@ void SysJolt::remove_components(ACtxJoltWorld& rCtxWorld, ActiveEnt ent) noexcep
if (itBodyId != rCtxWorld.m_entToBody.end())
{
OspBodyId const bodyId = itBodyId->second;
rCtxWorld.m_bodyIds.remove(bodyId);
rCtxWorld.m_bodyToEnt[bodyId] = lgrn::id_null<ActiveEnt>();
rCtxWorld.m_entToBody.erase(itBodyId);
}
Expand Down Expand Up @@ -152,6 +153,21 @@ void SysJolt::orient_shape(TransformedShapePtr_t& pJoltShape, osp::EShape ospSha

}

float SysJolt::get_inverse_mass_no_lock(PhysicsSystem &physicsSystem, JoltBodyId joltBodyId)
{
const BodyLockInterfaceNoLock& lockInterface = physicsSystem.GetBodyLockInterfaceNoLock();
// Scoped lock
{
JPH::BodyLockRead lock(lockInterface, joltBodyId);
if (lock.Succeeded()) // body_id may no longer be valid
{
const JPH::Body &body = lock.GetBody();

return body.GetMotionProperties()->GetInverseMass();
}
}
return 0.0f;
}

void SysJolt::find_shapes_recurse(
ACtxPhysics const& rCtxPhys,
Expand Down Expand Up @@ -201,4 +217,39 @@ void SysJolt::find_shapes_recurse(

}

}

//TODO this is locking and single threaded (for the physics simulation). Is it bad ?
void PhysicsStepListenerImpl::OnStep(float inDeltaTime, PhysicsSystem &rJoltWorld)
{
//no lock as all bodies are already locked
BodyInterface &bodyInterface = rJoltWorld.GetBodyInterfaceNoLock();
for (OspBodyId ospBody : m_context->m_bodyIds)
{
JoltBodyId joltBody = m_context->m_ospToJoltBodyId[ospBody];
if (bodyInterface.GetMotionType(joltBody) != EMotionType::Dynamic)
{
continue;
}

//Transform jolt -> osp

ActiveEnt const ent = m_context->m_bodyToEnt[ospBody];
Mat44 worldTranform = bodyInterface.GetWorldTransform(joltBody);
worldTranform.StoreFloat4x4((Float4*)m_context->m_pTransform->get(ent).m_transform.data());

//Force and torque osp -> jolt
Vector3 force{0.0f};
Vector3 torque{0.0f};

auto factorBits = lgrn::bit_view(m_context->m_bodyFactors[ospBody]);
for (std::size_t const factorIdx : factorBits.ones())
{
ACtxJoltWorld::ForceFactorFunc const& factor = m_context->m_factors[factorIdx];
factor.m_func(joltBody, ospBody, *m_context, factor.m_userData, force, torque);
}
Vec3 vel = bodyInterface.GetLinearVelocity(joltBody);

bodyInterface.AddForceAndTorque(joltBody, Vec3Arg (force.x(), force.y(), force.z()), Vec3Arg(torque.x(), torque.y(), torque.z()));
}
}
5 changes: 3 additions & 2 deletions src/ospjolt/activescene/joltinteg_fn.h
Original file line number Diff line number Diff line change
Expand Up @@ -122,6 +122,8 @@ class SysJolt
{
return bodyInterface.SetUserData(joltBody, reinterpret_cast<uint64_t>(std::uintptr_t(ospBody)));
}

static float get_inverse_mass_no_lock(PhysicsSystem& physicsSystem, JoltBodyId joltBodyId);
private:

/**
Expand All @@ -147,5 +149,4 @@ class SysJolt

};

}

}
16 changes: 10 additions & 6 deletions src/testapp/sessions/jolt.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -150,12 +150,11 @@ osp::Session setup_jolt_force_accel(
.m_func = [] (JoltBodyId const joltBodyId, OspBodyId const ospBodyID, ACtxJoltWorld const& rJolt, UserData_t data, Vector3& rForce, Vector3& rTorque) noexcept
{
PhysicsSystem *pJoltWorld = rJolt.m_world.get();
BodyInterface &bodyInterface = pJoltWorld->GetBodyInterface();

float mass = bodyInterface.GetShape(joltBodyId)->GetMassProperties().mMass;
float inv_mass = SysJolt::get_inverse_mass_no_lock(*pJoltWorld, joltBodyId);

auto const& force = *reinterpret_cast<Vector3 const*>(data[0]);
rForce += force * mass;
rForce += force / inv_mass;
},
.m_userData = {&rAccel}
};
Expand Down Expand Up @@ -227,9 +226,13 @@ Session setup_phys_shapes_jolt(
bodyCreation.mMassPropertiesOverride = massProp;
bodyCreation.mOverrideMassProperties = EOverrideMassProperties::CalculateInertia;
}
else
{
bodyCreation.mMotionType = EMotionType::Static;
bodyCreation.mObjectLayer = Layers::NON_MOVING;
}
PhysicsSystem *pJoltWorld = rJolt.m_world.get();
BodyInterface &bodyInterface = pJoltWorld->GetBodyInterface();

JoltBodyId joltBodyId = bodyInterface.CreateAndAddBody(bodyCreation, EActivation::Activate);

rJolt.m_ospToJoltBodyId[bodyId] = joltBodyId;
Expand Down Expand Up @@ -627,7 +630,8 @@ static void rocket_thrust_force(JoltBodyId const joltBody, OspBodyId const ospBo
auto &rBodyRockets = rRocketsJolt.m_bodyRockets[ospBody];

PhysicsSystem *pJoltWorld = rJolt.m_world.get();
BodyInterface &bodyInterface = pJoltWorld->GetBodyInterface();
//no lock as all bodies are locked in callbacks
BodyInterface &bodyInterface = pJoltWorld->GetBodyInterfaceNoLock();

if (rBodyRockets.empty())
{
Expand All @@ -637,7 +641,7 @@ static void rocket_thrust_force(JoltBodyId const joltBody, OspBodyId const ospBo
Quat joltQuat = bodyInterface.GetRotation(joltBody);
Quaternion const rot{{joltQuat.GetX(), joltQuat.GetY(), joltQuat.GetZ()}, joltQuat.GetW()};

RVec3 joltCom = bodyInterface.GetCenterOfMassPosition(joltBody);
RVec3 joltCom = bodyInterface.GetCenterOfMassPosition(joltBody) - bodyInterface.GetPosition(joltBody);
Vector3 com(joltCom.GetX(), joltCom.GetY(), joltCom.GetZ());

for (BodyRocket const& bodyRocket : rBodyRockets)
Expand Down

0 comments on commit f6ba0e0

Please sign in to comment.