Process movement queue in one or several background threads

Before movement calculation, the main thread prepare a
vector of ActorFrameData, which contains all data necessary to perform
the simulation, and feed it to the solver. At the same time it fetches
the result from the previous background simulation, which in turn is
used by the game mechanics.
Other functions of the physics system (weapon hit for instance)
interrupt the background simulation, with some exceptions described
below.

The number of threads is controlled by the numeric setting

[Physics]
async num threads

In case 'async num threads' > 1 and Bullet doesn't support multiple threads,
1 async thread will be used. 0 means synchronous solver.
Additional settings (will be silently switched off if async num threads = 0)

[Physics]
defer aabb update

Update AABBs of actors and objects in the background thread(s). It is not an especially
costly operation, but it needs exclusive access to the collision world, which blocks
other operations. Since AABB needs to be updated for collision detection, one can queue
them to defer update before start of the movement solver. Extensive tests on as much
as one installation (mine) show no drawback having that switched on.

[Physics]
lineofsight keep inactive cache

Control for how long (how many frames) the line of sight (LOS) request will be kept updated.
When a request for LOS is made for the first time, the background threads are stopped to
service it. From now on, the LOS will be refreshed preemptively as part of the background
routine until it is not required for lineofsight keep inactive cache frames. This mean
that subsequent request will not interrupt the background computation.
pull/3013/head
fredzio 4 years ago
parent 91b3926a49
commit 3c2504b442

@ -73,7 +73,7 @@ add_openmw_dir (mwworld
add_openmw_dir (mwphysics
physicssystem trace collisiontype actor convert object heightfield closestnotmerayresultcallback
contacttestresultcallback deepestnotmecontacttestresultcallback stepper movementsolver
closestnotmeconvexresultcallback raycasting
closestnotmeconvexresultcallback raycasting mtphysics
)
add_openmw_dir (mwclass

@ -12,18 +12,19 @@
#include "../mwworld/class.hpp"
#include "collisiontype.hpp"
#include "mtphysics.hpp"
namespace MWPhysics
{
Actor::Actor(const MWWorld::Ptr& ptr, const Resource::BulletShape* shape, btCollisionWorld* world)
Actor::Actor(const MWWorld::Ptr& ptr, const Resource::BulletShape* shape, PhysicsTaskScheduler* scheduler)
: mCanWaterWalk(false), mWalkingOnWater(false)
, mCollisionObject(nullptr), mMeshTranslation(shape->mCollisionBoxTranslate), mHalfExtents(shape->mCollisionBoxHalfExtents)
, mForce(0.f, 0.f, 0.f), mOnGround(true), mOnSlope(false)
, mInternalCollisionMode(true)
, mExternalCollisionMode(true)
, mCollisionWorld(world)
, mTaskScheduler(scheduler)
{
mPtr = ptr;
@ -82,12 +83,12 @@ Actor::Actor(const MWWorld::Ptr& ptr, const Resource::BulletShape* shape, btColl
Actor::~Actor()
{
if (mCollisionObject)
mCollisionWorld->removeCollisionObject(mCollisionObject.get());
mTaskScheduler->removeCollisionObject(mCollisionObject.get());
}
void Actor::enableCollisionMode(bool collision)
{
mInternalCollisionMode = collision;
mInternalCollisionMode.store(collision, std::memory_order_release);
}
void Actor::enableCollisionBody(bool collision)
@ -101,12 +102,12 @@ void Actor::enableCollisionBody(bool collision)
void Actor::addCollisionMask(int collisionMask)
{
mCollisionWorld->addCollisionObject(mCollisionObject.get(), CollisionType_Actor, collisionMask);
mTaskScheduler->addCollisionObject(mCollisionObject.get(), CollisionType_Actor, collisionMask);
}
void Actor::updateCollisionMask()
{
mCollisionObject->getBroadphaseHandle()->m_collisionFilterMask = getCollisionMask();
mTaskScheduler->setCollisionFilterMask(mCollisionObject.get(), getCollisionMask());
}
int Actor::getCollisionMask() const
@ -121,6 +122,7 @@ int Actor::getCollisionMask() const
void Actor::updatePosition()
{
std::unique_lock<std::mutex> lock(mPositionMutex);
osg::Vec3f position = mPtr.getRefData().getPosition().asVec3();
mPosition = position;
@ -141,6 +143,7 @@ void Actor::updateCollisionObjectPosition()
void Actor::commitPositionChange()
{
std::unique_lock<std::mutex> lock(mPositionMutex);
if (mScaleUpdatePending)
{
mShape->setLocalScaling(Misc::Convert::toBullet(mScale));
@ -155,11 +158,13 @@ void Actor::commitPositionChange()
osg::Vec3f Actor::getCollisionObjectPosition() const
{
std::unique_lock<std::mutex> lock(mPositionMutex);
return Misc::Convert::toOsg(mLocalTransform.getOrigin());
}
void Actor::setPosition(const osg::Vec3f &position)
void Actor::setPosition(const osg::Vec3f &position, bool updateCollisionObject)
{
std::unique_lock<std::mutex> lock(mPositionMutex);
if (mTransformUpdatePending)
{
mCollisionObject->setWorldTransform(mLocalTransform);
@ -170,23 +175,29 @@ void Actor::setPosition(const osg::Vec3f &position)
mPreviousPosition = mPosition;
mPosition = position;
updateCollisionObjectPosition();
mCollisionObject->setWorldTransform(mLocalTransform);
if (updateCollisionObject)
{
updateCollisionObjectPosition();
mCollisionObject->setWorldTransform(mLocalTransform);
}
}
}
osg::Vec3f Actor::getPosition() const
{
std::unique_lock<std::mutex> lock(mPositionMutex);
return mPosition;
}
osg::Vec3f Actor::getPreviousPosition() const
{
std::unique_lock<std::mutex> lock(mPositionMutex);
return mPreviousPosition;
}
void Actor::updateRotation ()
{
std::unique_lock<std::mutex> lock(mPositionMutex);
if (mRotation == mPtr.getRefData().getBaseNode()->getAttitude())
return;
mRotation = mPtr.getRefData().getBaseNode()->getAttitude();
@ -202,6 +213,7 @@ bool Actor::isRotationallyInvariant() const
void Actor::updateScale()
{
std::unique_lock<std::mutex> lock(mPositionMutex);
float scale = mPtr.getCellRef().getScale();
osg::Vec3f scaleVec(scale,scale,scale);
@ -219,16 +231,19 @@ void Actor::updateScale()
osg::Vec3f Actor::getHalfExtents() const
{
std::unique_lock<std::mutex> lock(mPositionMutex);
return osg::componentMultiply(mHalfExtents, mScale);
}
osg::Vec3f Actor::getOriginalHalfExtents() const
{
std::unique_lock<std::mutex> lock(mPositionMutex);
return mHalfExtents;
}
osg::Vec3f Actor::getRenderingHalfExtents() const
{
std::unique_lock<std::mutex> lock(mPositionMutex);
return osg::componentMultiply(mHalfExtents, mRenderingScale);
}
@ -239,26 +254,27 @@ void Actor::setInertialForce(const osg::Vec3f &force)
void Actor::setOnGround(bool grounded)
{
mOnGround = grounded;
mOnGround.store(grounded, std::memory_order_release);
}
void Actor::setOnSlope(bool slope)
{
mOnSlope = slope;
mOnSlope.store(slope, std::memory_order_release);
}
bool Actor::isWalkingOnWater() const
{
return mWalkingOnWater;
return mWalkingOnWater.load(std::memory_order_acquire);
}
void Actor::setWalkingOnWater(bool walkingOnWater)
{
mWalkingOnWater = walkingOnWater;
mWalkingOnWater.store(walkingOnWater, std::memory_order_release);
}
void Actor::setCanWaterWalk(bool waterWalk)
{
std::unique_lock<std::mutex> lock(mPositionMutex);
if (waterWalk != mCanWaterWalk)
{
mCanWaterWalk = waterWalk;

@ -1,7 +1,9 @@
#ifndef OPENMW_MWPHYSICS_ACTOR_H
#define OPENMW_MWPHYSICS_ACTOR_H
#include <atomic>
#include <memory>
#include <mutex>
#include "ptrholder.hpp"
@ -10,7 +12,6 @@
#include <osg/Quat>
#include <osg/ref_ptr>
class btCollisionWorld;
class btCollisionShape;
class btCollisionObject;
class btConvexShape;
@ -27,7 +28,7 @@ namespace MWPhysics
class Actor final : public PtrHolder
{
public:
Actor(const MWWorld::Ptr& ptr, const Resource::BulletShape* shape, btCollisionWorld* world);
Actor(const MWWorld::Ptr& ptr, const Resource::BulletShape* shape, PhysicsTaskScheduler* scheduler);
~Actor() override;
/**
@ -37,7 +38,7 @@ namespace MWPhysics
bool getCollisionMode() const
{
return mInternalCollisionMode;
return mInternalCollisionMode.load(std::memory_order_acquire);
}
btConvexShape* getConvexShape() const { return mConvexShape; }
@ -82,8 +83,9 @@ namespace MWPhysics
/**
* Store the current position into mPreviousPosition, then move to this position.
* Optionally, inform the physics engine about the change of position.
*/
void setPosition(const osg::Vec3f& position);
void setPosition(const osg::Vec3f& position, bool updateCollisionObject=true);
osg::Vec3f getPosition() const;
@ -113,14 +115,14 @@ namespace MWPhysics
bool getOnGround() const
{
return mInternalCollisionMode && mOnGround;
return mInternalCollisionMode.load(std::memory_order_acquire) && mOnGround.load(std::memory_order_acquire);
}
void setOnSlope(bool slope);
bool getOnSlope() const
{
return mInternalCollisionMode && mOnSlope;
return mInternalCollisionMode.load(std::memory_order_acquire) && mOnSlope.load(std::memory_order_acquire);
}
btCollisionObject* getCollisionObject() const
@ -142,7 +144,7 @@ namespace MWPhysics
int getCollisionMask() const;
bool mCanWaterWalk;
bool mWalkingOnWater;
std::atomic<bool> mWalkingOnWater;
bool mRotationallyInvariant;
@ -162,14 +164,15 @@ namespace MWPhysics
btTransform mLocalTransform;
bool mScaleUpdatePending;
bool mTransformUpdatePending;
mutable std::mutex mPositionMutex;
osg::Vec3f mForce;
bool mOnGround;
bool mOnSlope;
bool mInternalCollisionMode;
std::atomic<bool> mOnGround;
std::atomic<bool> mOnSlope;
std::atomic<bool> mInternalCollisionMode;
bool mExternalCollisionMode;
btCollisionWorld* mCollisionWorld;
PhysicsTaskScheduler* mTaskScheduler;
Actor(const Actor&);
Actor& operator=(const Actor&);

@ -0,0 +1,607 @@
#include <BulletCollision/CollisionShapes/btCollisionShape.h>
#include <LinearMath/btThreads.h>
#include "components/debug/debuglog.hpp"
#include <components/misc/barrier.hpp>
#include "components/misc/convert.hpp"
#include "components/settings/settings.hpp"
#include "../mwmechanics/actorutil.hpp"
#include "../mwmechanics/movement.hpp"
#include "../mwworld/class.hpp"
#include "../mwworld/player.hpp"
#include "actor.hpp"
#include "movementsolver.hpp"
#include "mtphysics.hpp"
#include "object.hpp"
#include "physicssystem.hpp"
class btIParallelSumBody; // needed to compile with bullet < 2.88
namespace
{
/// @brief A scoped lock that is either shared or exclusive depending on configuration
template<class Mutex>
class MaybeSharedLock
{
public:
/// @param mutex a shared mutex
/// @param canBeSharedLock decide wether the lock will be shared or exclusive
MaybeSharedLock(Mutex& mutex, bool canBeSharedLock) : mMutex(mutex), mCanBeSharedLock(canBeSharedLock)
{
if (mCanBeSharedLock)
mMutex.lock_shared();
else
mMutex.lock();
}
~MaybeSharedLock()
{
if (mCanBeSharedLock)
mMutex.unlock_shared();
else
mMutex.unlock();
}
private:
Mutex& mMutex;
bool mCanBeSharedLock;
};
void handleFall(MWPhysics::ActorFrameData& actorData, bool simulationPerformed)
{
const float heightDiff = actorData.mPosition.z() - actorData.mOldHeight;
const bool isStillOnGround = (simulationPerformed && actorData.mWasOnGround && actorData.mActorRaw->getOnGround());
if (isStillOnGround || actorData.mFlying || actorData.mSwimming || actorData.mSlowFall < 1)
actorData.mNeedLand = true;
else if (heightDiff < 0)
actorData.mFallHeight += heightDiff;
}
void handleJump(const MWWorld::Ptr &ptr)
{
const bool isPlayer = (ptr == MWMechanics::getPlayer());
// Advance acrobatics and set flag for GetPCJumping
if (isPlayer)
{
ptr.getClass().skillUsageSucceeded(ptr, ESM::Skill::Acrobatics, 0);
MWBase::Environment::get().getWorld()->getPlayer().setJumping(true);
}
// Decrease fatigue
if (!isPlayer || !MWBase::Environment::get().getWorld()->getGodModeState())
{
const MWWorld::Store<ESM::GameSetting> &gmst = MWBase::Environment::get().getWorld()->getStore().get<ESM::GameSetting>();
const float fFatigueJumpBase = gmst.find("fFatigueJumpBase")->mValue.getFloat();
const float fFatigueJumpMult = gmst.find("fFatigueJumpMult")->mValue.getFloat();
const float normalizedEncumbrance = std::min(1.f, ptr.getClass().getNormalizedEncumbrance(ptr));
const float fatigueDecrease = fFatigueJumpBase + normalizedEncumbrance * fFatigueJumpMult;
MWMechanics::DynamicStat<float> fatigue = ptr.getClass().getCreatureStats(ptr).getFatigue();
fatigue.setCurrent(fatigue.getCurrent() - fatigueDecrease);
ptr.getClass().getCreatureStats(ptr).setFatigue(fatigue);
}
ptr.getClass().getMovementSettings(ptr).mPosition[2] = 0;
}
void updateStandingCollision(MWPhysics::ActorFrameData& actorData, MWPhysics::CollisionMap& standingCollisions)
{
if (!actorData.mStandingOn.isEmpty())
standingCollisions[actorData.mPtr] = actorData.mStandingOn;
else
standingCollisions.erase(actorData.mPtr);
}
void updateMechanics(MWPhysics::ActorFrameData& actorData)
{
if (actorData.mDidJump)
handleJump(actorData.mPtr);
MWMechanics::CreatureStats& stats = actorData.mPtr.getClass().getCreatureStats(actorData.mPtr);
if (actorData.mNeedLand)
stats.land(actorData.mPtr == MWMechanics::getPlayer() && (actorData.mFlying || actorData.mSwimming));
else if (actorData.mFallHeight < 0)
stats.addToFallHeight(-actorData.mFallHeight);
}
osg::Vec3f interpolateMovements(const MWPhysics::ActorFrameData& actorData, float timeAccum, float physicsDt)
{
const float interpolationFactor = timeAccum / physicsDt;
return actorData.mPosition * interpolationFactor + actorData.mActorRaw->getPreviousPosition() * (1.f - interpolationFactor);
}
struct WorldFrameData
{
WorldFrameData() : mIsInStorm(MWBase::Environment::get().getWorld()->isInStorm())
, mStormDirection(MWBase::Environment::get().getWorld()->getStormDirection())
{}
bool mIsInStorm;
osg::Vec3f mStormDirection;
};
namespace Config
{
/* The purpose of these 2 classes is to make OpenMW works with Bullet compiled with either single or multithread support.
At runtime, Bullet resolve the call to btParallelFor() to:
- btITaskScheduler::parallelFor() if bullet is multithreaded
- btIParallelForBody::forLoop() if bullet is singlethreaded.
NOTE: From Bullet 2.88, there is a btDefaultTaskScheduler(), that returns NULL if multithreading is not supported.
It might be worth considering to simplify the API once OpenMW stops supporting 2.87.
*/
template<class ...>
using void_t = void;
/// @brief for Bullet <= 2.87
template <class T, class = void>
class MultiThreadedBulletImpl : public T
{
public:
MultiThreadedBulletImpl(): T("") {};
~MultiThreadedBulletImpl() override = default;
int getMaxNumThreads() const override { return 1; };
int getNumThreads() const override { return 1; };
void setNumThreads(int numThreads) override {};
/// @brief will be called by Bullet if threading is supported
void parallelFor(int iBegin, int iEnd, int batchsize, const btIParallelForBody& body) override {};
};
/// @brief for Bullet >= 2.88
template <class T>
class MultiThreadedBulletImpl<T, void_t<decltype(&T::parallelSum)>> : public T
{
public:
MultiThreadedBulletImpl(): T("") {};
~MultiThreadedBulletImpl() override = default;
int getMaxNumThreads() const override { return 1; };
int getNumThreads() const override { return 1; };
void setNumThreads(int numThreads) override {};
/// @brief will be called by Bullet if threading is supported
void parallelFor(int iBegin, int iEnd, int batchsize, const btIParallelForBody& body) override {};
btScalar parallelSum(int iBegin, int iEnd, int grainSize, const btIParallelSumBody& body) override { return {}; };
};
using MultiThreadedBullet = MultiThreadedBulletImpl<btITaskScheduler>;
class SingleThreadedBullet : public btIParallelForBody
{
public:
explicit SingleThreadedBullet(bool &threadingSupported): mThreadingSupported(threadingSupported) {};
/// @brief will be called by Bullet if threading is NOT supported
void forLoop(int iBegin, int iEnd) const override
{
mThreadingSupported = false;
}
private:
bool &mThreadingSupported;
};
/// @return either the number of thread as configured by the user, or 1 if Bullet doesn't support multithreading
int computeNumThreads(bool& threadSafeBullet)
{
int wantedThread = Settings::Manager::getInt("async num threads", "Physics");
auto bulletScheduler = std::make_unique<MultiThreadedBullet>();
btSetTaskScheduler(bulletScheduler.get());
bool threadingSupported = true;
btParallelFor(0, 0, 0, SingleThreadedBullet(threadingSupported));
threadSafeBullet = threadingSupported;
if (!threadingSupported && wantedThread > 1)
{
Log(Debug::Warning) << "Bullet was not compiled with multithreading support, 1 async thread will be used";
return 1;
}
return std::max(0, wantedThread);
}
}
}
namespace MWPhysics
{
PhysicsTaskScheduler::PhysicsTaskScheduler(float physicsDt, std::shared_ptr<btCollisionWorld> collisionWorld)
: mPhysicsDt(physicsDt)
, mCollisionWorld(std::move(collisionWorld))
, mNumJobs(0)
, mRemainingSteps(0)
, mLOSCacheExpiry(Settings::Manager::getInt("lineofsight keep inactive cache", "Physics"))
, mDeferAabbUpdate(Settings::Manager::getBool("defer aabb update", "Physics"))
, mNewFrame(false)
, mAdvanceSimulation(false)
, mQuit(false)
, mNextJob(0)
, mNextLOS(0)
{
mNumThreads = Config::computeNumThreads(mThreadSafeBullet);
if (mNumThreads >= 1)
{
for (int i = 0; i < mNumThreads; ++i)
mThreads.emplace_back([&] { worker(); } );
}
else
{
mLOSCacheExpiry = -1;
mDeferAabbUpdate = false;
}
mPreStepBarrier = std::make_unique<Misc::Barrier>(mNumThreads, [&]()
{
updateAabbs();
});
mPostStepBarrier = std::make_unique<Misc::Barrier>(mNumThreads, [&]()
{
if (mRemainingSteps)
--mRemainingSteps;
mNextJob.store(0, std::memory_order_release);
updateActorsPositions();
});
mPostSimBarrier = std::make_unique<Misc::Barrier>(mNumThreads, [&]()
{
udpateActorsAabbs();
mNewFrame = false;
if (mLOSCacheExpiry >= 0)
{
std::unique_lock<std::shared_timed_mutex> lock(mLOSCacheMutex);
mLOSCache.erase(
std::remove_if(mLOSCache.begin(), mLOSCache.end(),
[](const LOSRequest& req) { return req.mStale; }),
mLOSCache.end());
}
});
}
PhysicsTaskScheduler::~PhysicsTaskScheduler()
{
std::unique_lock<std::shared_timed_mutex> lock(mSimulationMutex);
mQuit = true;
mNumJobs = 0;
mRemainingSteps = 0;
lock.unlock();
mHasJob.notify_all();
for (auto& thread : mThreads)
thread.join();
}
const PtrPositionList& PhysicsTaskScheduler::moveActors(int numSteps, float timeAccum, std::vector<ActorFrameData>&& actorsData, CollisionMap& standingCollisions, bool skipSimulation)
{
// This function run in the main thread.
// While the mSimulationMutex is held, background physics threads can't run.
std::unique_lock<std::shared_timed_mutex> lock(mSimulationMutex);
// start by finishing previous background computation
if (mNumThreads != 0)
{
if (mAdvanceSimulation)
standingCollisions.clear();
for (auto& data : mActorsFrameData)
{
// Ignore actors that were deleted while the background thread was running
if (!data.mActor.lock())
continue;
updateMechanics(data);
if (mAdvanceSimulation)
updateStandingCollision(data, standingCollisions);
}
}
// init
mRemainingSteps = numSteps;
mTimeAccum = timeAccum;
mActorsFrameData = std::move(actorsData);
mAdvanceSimulation = (mRemainingSteps != 0);
mNewFrame = true;
mNumJobs = mActorsFrameData.size();
mNextLOS.store(0, std::memory_order_relaxed);
mNextJob.store(0, std::memory_order_release);
if (mAdvanceSimulation)
mWorldFrameData = std::make_unique<WorldFrameData>();
// update each actor position based on latest data
for (auto& data : mActorsFrameData)
data.updatePosition();
// we are asked to skip the simulation (load a savegame for instance)
// just return the actors' reference position without applying the movements
if (skipSimulation)
{
standingCollisions.clear();
mMovementResults.clear();
for (const auto& m : mActorsFrameData)
mMovementResults[m.mPtr] = m.mPosition;
return mMovementResults;
}
if (mNumThreads == 0)
{
mMovementResults.clear();
syncComputation();
if (mAdvanceSimulation)
{
standingCollisions.clear();
for (auto& data : mActorsFrameData)
updateStandingCollision(data, standingCollisions);
}
return mMovementResults;
}
// Remove actors that were deleted while the background thread was running
for (auto& data : mActorsFrameData)
{
if (!data.mActor.lock())
mMovementResults.erase(data.mPtr);
}
std::swap(mMovementResults, mPreviousMovementResults);
// mMovementResults is shared between all workers instance
// pre-allocate all nodes so that we don't need synchronization
mMovementResults.clear();
for (const auto& m : mActorsFrameData)
mMovementResults[m.mPtr] = m.mPosition;
lock.unlock();
mHasJob.notify_all();
return mPreviousMovementResults;
}
void PhysicsTaskScheduler::rayTest(const btVector3& rayFromWorld, const btVector3& rayToWorld, btCollisionWorld::RayResultCallback& resultCallback) const
{
MaybeSharedLock<std::shared_timed_mutex> lock(mCollisionWorldMutex, mThreadSafeBullet);
mCollisionWorld->rayTest(rayFromWorld, rayToWorld, resultCallback);
}
void PhysicsTaskScheduler::convexSweepTest(const btConvexShape* castShape, const btTransform& from, const btTransform& to, btCollisionWorld::ConvexResultCallback& resultCallback) const
{
MaybeSharedLock<std::shared_timed_mutex> lock(mCollisionWorldMutex, mThreadSafeBullet);
mCollisionWorld->convexSweepTest(castShape, from, to, resultCallback);
}
void PhysicsTaskScheduler::contactTest(btCollisionObject* colObj, btCollisionWorld::ContactResultCallback& resultCallback)
{
std::shared_lock<std::shared_timed_mutex> lock(mCollisionWorldMutex);
mCollisionWorld->contactTest(colObj, resultCallback);
}
boost::optional<btVector3> PhysicsTaskScheduler::getHitPoint(const btTransform& from, btCollisionObject* target)
{
MaybeSharedLock<std::shared_timed_mutex> lock(mCollisionWorldMutex, mThreadSafeBullet);
// target the collision object's world origin, this should be the center of the collision object
btTransform rayTo;
rayTo.setIdentity();
rayTo.setOrigin(target->getWorldTransform().getOrigin());
btCollisionWorld::ClosestRayResultCallback cb(from.getOrigin(), rayTo.getOrigin());
mCollisionWorld->rayTestSingle(from, rayTo, target, target->getCollisionShape(), target->getWorldTransform(), cb);
if (!cb.hasHit())
// didn't hit the target. this could happen if point is already inside the collision box
return boost::none;
return {cb.m_hitPointWorld};
}
void PhysicsTaskScheduler::aabbTest(const btVector3& aabbMin, const btVector3& aabbMax, btBroadphaseAabbCallback& callback)
{
std::shared_lock<std::shared_timed_mutex> lock(mCollisionWorldMutex);
mCollisionWorld->getBroadphase()->aabbTest(aabbMin, aabbMax, callback);
}
void PhysicsTaskScheduler::getAabb(const btCollisionObject* obj, btVector3& min, btVector3& max)
{
std::shared_lock<std::shared_timed_mutex> lock(mCollisionWorldMutex);
obj->getCollisionShape()->getAabb(obj->getWorldTransform(), min, max);
}
void PhysicsTaskScheduler::setCollisionFilterMask(btCollisionObject* collisionObject, int collisionFilterMask)
{
std::unique_lock<std::shared_timed_mutex> lock(mCollisionWorldMutex);
collisionObject->getBroadphaseHandle()->m_collisionFilterMask = collisionFilterMask;
}
void PhysicsTaskScheduler::addCollisionObject(btCollisionObject* collisionObject, int collisionFilterGroup, int collisionFilterMask)
{
std::unique_lock<std::shared_timed_mutex> lock(mCollisionWorldMutex);
mCollisionWorld->addCollisionObject(collisionObject, collisionFilterGroup, collisionFilterMask);
}
void PhysicsTaskScheduler::removeCollisionObject(btCollisionObject* collisionObject)
{
std::unique_lock<std::shared_timed_mutex> lock(mCollisionWorldMutex);
mCollisionWorld->removeCollisionObject(collisionObject);
}
void PhysicsTaskScheduler::updateSingleAabb(std::weak_ptr<PtrHolder> ptr)
{
if (mDeferAabbUpdate)
{
std::unique_lock<std::mutex> lock(mUpdateAabbMutex);
mUpdateAabb.insert(std::move(ptr));
}
else
{
std::unique_lock<std::shared_timed_mutex> lock(mCollisionWorldMutex);
updatePtrAabb(ptr);
}
}
bool PhysicsTaskScheduler::getLineOfSight(const std::weak_ptr<Actor>& actor1, const std::weak_ptr<Actor>& actor2)
{
std::unique_lock<std::shared_timed_mutex> lock(mLOSCacheMutex);
auto actorPtr1 = actor1.lock();
auto actorPtr2 = actor2.lock();
if (!actorPtr1 || !actorPtr2)
return false;
auto req = LOSRequest(actor1, actor2);
auto result = std::find(mLOSCache.begin(), mLOSCache.end(), req);
if (result == mLOSCache.end())
{
req.mResult = hasLineOfSight(actorPtr1.get(), actorPtr2.get());
if (mLOSCacheExpiry >= 0)
mLOSCache.push_back(req);
return req.mResult;
}
result->mAge = 0;
return result->mResult;
}
void PhysicsTaskScheduler::refreshLOSCache()
{
std::shared_lock<std::shared_timed_mutex> lock(mLOSCacheMutex);
int job = 0;
int numLOS = mLOSCache.size();
while ((job = mNextLOS.fetch_add(1, std::memory_order_relaxed)) < numLOS)
{
auto& req = mLOSCache[job];
auto actorPtr1 = req.mActors[0].lock();
auto actorPtr2 = req.mActors[1].lock();
if (req.mAge++ > mLOSCacheExpiry || !actorPtr1 || !actorPtr2)
req.mStale = true;
else
req.mResult = hasLineOfSight(actorPtr1.get(), actorPtr2.get());
}
}
void PhysicsTaskScheduler::updateAabbs()
{
std::unique_lock<std::shared_timed_mutex> lock1(mCollisionWorldMutex, std::defer_lock);
std::unique_lock<std::mutex> lock2(mUpdateAabbMutex, std::defer_lock);
std::lock(lock1, lock2);
std::for_each(mUpdateAabb.begin(), mUpdateAabb.end(),
[this](const std::weak_ptr<PtrHolder>& ptr) { updatePtrAabb(ptr); });
mUpdateAabb.clear();
}
void PhysicsTaskScheduler::updatePtrAabb(const std::weak_ptr<PtrHolder>& ptr)
{
if (const auto p = ptr.lock())
{
if (const auto actor = std::dynamic_pointer_cast<Actor>(p))
{
actor->commitPositionChange();
mCollisionWorld->updateSingleAabb(actor->getCollisionObject());
}
else if (const auto object = std::dynamic_pointer_cast<Object>(p))
{
object->commitPositionChange();
mCollisionWorld->updateSingleAabb(object->getCollisionObject());
}
};
}
void PhysicsTaskScheduler::worker()
{
std::shared_lock<std::shared_timed_mutex> lock(mSimulationMutex);
while (!mQuit)
{
if (!mNewFrame)
mHasJob.wait(lock, [&]() { return mQuit || mNewFrame; });
if (mDeferAabbUpdate)
mPreStepBarrier->wait();
int job = 0;
while ((job = mNextJob.fetch_add(1, std::memory_order_relaxed)) < mNumJobs)
{
MaybeSharedLock<std::shared_timed_mutex> lockColWorld(mCollisionWorldMutex, mThreadSafeBullet);
if(const auto actor = mActorsFrameData[job].mActor.lock())
{
if (mRemainingSteps)
MovementSolver::move(mActorsFrameData[job], mPhysicsDt, mCollisionWorld.get(), *mWorldFrameData);
else
{
auto& actorData = mActorsFrameData[job];
handleFall(actorData, mAdvanceSimulation);
mMovementResults[actorData.mPtr] = interpolateMovements(actorData, mTimeAccum, mPhysicsDt);
}
}
}
mPostStepBarrier->wait();
if (!mRemainingSteps)
{
if (mLOSCacheExpiry >= 0)
refreshLOSCache();
mPostSimBarrier->wait();
}
}
}
void PhysicsTaskScheduler::updateActorsPositions()
{
std::unique_lock<std::shared_timed_mutex> lock(mCollisionWorldMutex);
for (auto& actorData : mActorsFrameData)
{
if(const auto actor = actorData.mActor.lock())
{
if (actorData.mPosition == actor->getPosition())
actor->setPosition(actorData.mPosition, false); // update previous position to make sure interpolation is correct
else
{
actorData.mPositionChanged = true;
actor->setPosition(actorData.mPosition);
}
}
}
}
void PhysicsTaskScheduler::udpateActorsAabbs()
{
std::unique_lock<std::shared_timed_mutex> lock(mCollisionWorldMutex);
for (const auto& actorData : mActorsFrameData)
if (actorData.mPositionChanged)
{
if(const auto actor = actorData.mActor.lock())
mCollisionWorld->updateSingleAabb(actor->getCollisionObject());
}
}
bool PhysicsTaskScheduler::hasLineOfSight(const Actor* actor1, const Actor* actor2)
{
btVector3 pos1 = Misc::Convert::toBullet(actor1->getCollisionObjectPosition() + osg::Vec3f(0,0,actor1->getHalfExtents().z() * 0.9)); // eye level
btVector3 pos2 = Misc::Convert::toBullet(actor2->getCollisionObjectPosition() + osg::Vec3f(0,0,actor2->getHalfExtents().z() * 0.9));
btCollisionWorld::ClosestRayResultCallback resultCallback(pos1, pos2);
resultCallback.m_collisionFilterGroup = 0xFF;
resultCallback.m_collisionFilterMask = CollisionType_World|CollisionType_HeightMap|CollisionType_Door;
MaybeSharedLock<std::shared_timed_mutex> lockColWorld(mCollisionWorldMutex, mThreadSafeBullet);
mCollisionWorld->rayTest(pos1, pos2, resultCallback);
return !resultCallback.hasHit();
}
void PhysicsTaskScheduler::syncComputation()
{
while (mRemainingSteps--)
{
for (auto& actorData : mActorsFrameData)
MovementSolver::move(actorData, mPhysicsDt, mCollisionWorld.get(), *mWorldFrameData);
updateActorsPositions();
}
for (auto& actorData : mActorsFrameData)
{
handleFall(actorData, mAdvanceSimulation);
mMovementResults[actorData.mPtr] = interpolateMovements(actorData, mTimeAccum, mPhysicsDt);
updateMechanics(actorData);
}
udpateActorsAabbs();
}
}

@ -0,0 +1,94 @@
#ifndef OPENMW_MWPHYSICS_MTPHYSICS_H
#define OPENMW_MWPHYSICS_MTPHYSICS_H
#include <atomic>
#include <condition_variable>
#include <thread>
#include <shared_mutex>
#include <boost/optional/optional.hpp>
#include <BulletCollision/CollisionDispatch/btCollisionWorld.h>
#include "physicssystem.hpp"
#include "ptrholder.hpp"
namespace Misc
{
class Barrier;
}
namespace MWPhysics
{
class PhysicsTaskScheduler
{
public:
PhysicsTaskScheduler(float physicsDt, std::shared_ptr<btCollisionWorld> collisionWorld);
~PhysicsTaskScheduler();
/// @brief move actors taking into account desired movements and collisions
/// @param numSteps how much simulation step to run
/// @param timeAccum accumulated time from previous run to interpolate movements
/// @param actorsData per actor data needed to compute new positions
/// @return new position of each actor
const PtrPositionList& moveActors(int numSteps, float timeAccum, std::vector<ActorFrameData>&& actorsData, CollisionMap& standingCollisions, bool skip);
// Thread safe wrappers
void rayTest(const btVector3& rayFromWorld, const btVector3& rayToWorld, btCollisionWorld::RayResultCallback& resultCallback) const;
void convexSweepTest(const btConvexShape* castShape, const btTransform& from, const btTransform& to, btCollisionWorld::ConvexResultCallback& resultCallback) const;
void contactTest(btCollisionObject* colObj, btCollisionWorld::ContactResultCallback& resultCallback);
boost::optional<btVector3> getHitPoint(const btTransform& from, btCollisionObject* target);
void aabbTest(const btVector3& aabbMin, const btVector3& aabbMax, btBroadphaseAabbCallback& callback);
void getAabb(const btCollisionObject* obj, btVector3& min, btVector3& max);
void setCollisionFilterMask(btCollisionObject* collisionObject, int collisionFilterMask);
void addCollisionObject(btCollisionObject* collisionObject, int collisionFilterGroup, int collisionFilterMask);
void removeCollisionObject(btCollisionObject* collisionObject);
void updateSingleAabb(std::weak_ptr<PtrHolder> ptr);
bool getLineOfSight(const std::weak_ptr<Actor>& actor1, const std::weak_ptr<Actor>& actor2);
private:
void syncComputation();
void worker();
void updateActorsPositions();
void udpateActorsAabbs();
bool hasLineOfSight(const Actor* actor1, const Actor* actor2);
void refreshLOSCache();
void updateAabbs();
void updatePtrAabb(const std::weak_ptr<PtrHolder>& ptr);
std::unique_ptr<WorldFrameData> mWorldFrameData;
std::vector<ActorFrameData> mActorsFrameData;
PtrPositionList mMovementResults;
PtrPositionList mPreviousMovementResults;
const float mPhysicsDt;
float mTimeAccum;
std::shared_ptr<btCollisionWorld> mCollisionWorld;
std::vector<LOSRequest> mLOSCache;
std::set<std::weak_ptr<PtrHolder>, std::owner_less<std::weak_ptr<PtrHolder>>> mUpdateAabb;
// TODO: use std::experimental::flex_barrier or std::barrier once it becomes a thing
std::unique_ptr<Misc::Barrier> mPreStepBarrier;
std::unique_ptr<Misc::Barrier> mPostStepBarrier;
std::unique_ptr<Misc::Barrier> mPostSimBarrier;
int mNumThreads;
int mNumJobs;
int mRemainingSteps;
int mLOSCacheExpiry;
bool mDeferAabbUpdate;
bool mNewFrame;
bool mAdvanceSimulation;
bool mThreadSafeBullet;
bool mQuit;
std::atomic<int> mNextJob;
std::atomic<int> mNextLOS;
std::vector<std::thread> mThreads;
mutable std::shared_timed_mutex mSimulationMutex;
mutable std::shared_timed_mutex mCollisionWorldMutex;
mutable std::shared_timed_mutex mLOSCacheMutex;
mutable std::mutex mUpdateAabbMutex;
std::condition_variable_any mHasJob;
};
}
#endif

@ -1,4 +1,5 @@
#include "object.hpp"
#include "mtphysics.hpp"
#include <components/debug/debuglog.hpp>
#include <components/nifosg/particle.hpp>
@ -8,16 +9,15 @@
#include <BulletCollision/CollisionShapes/btCompoundShape.h>
#include <BulletCollision/CollisionDispatch/btCollisionObject.h>
#include <BulletCollision/CollisionDispatch/btCollisionWorld.h>
#include <LinearMath/btTransform.h>
namespace MWPhysics
{
Object::Object(const MWWorld::Ptr& ptr, osg::ref_ptr<Resource::BulletShapeInstance> shapeInstance, btCollisionWorld* world)
Object::Object(const MWWorld::Ptr& ptr, osg::ref_ptr<Resource::BulletShapeInstance> shapeInstance, PhysicsTaskScheduler* scheduler)
: mShapeInstance(shapeInstance)
, mSolid(true)
, mCollisionWorld(world)
, mTaskScheduler(scheduler)
{
mPtr = ptr;
@ -36,7 +36,7 @@ namespace MWPhysics
Object::~Object()
{
if (mCollisionObject)
mCollisionWorld->removeCollisionObject(mCollisionObject.get());
mTaskScheduler->removeCollisionObject(mCollisionObject.get());
}
const Resource::BulletShapeInstance* Object::getShapeInstance() const
@ -46,24 +46,28 @@ namespace MWPhysics
void Object::setScale(float scale)
{
std::unique_lock<std::mutex> lock(mPositionMutex);
mScale = { scale,scale,scale };
mScaleUpdatePending = true;
}
void Object::setRotation(const btQuaternion& quat)
{
std::unique_lock<std::mutex> lock(mPositionMutex);
mLocalTransform.setRotation(quat);
mTransformUpdatePending = true;
}
void Object::setOrigin(const btVector3& vec)
{
std::unique_lock<std::mutex> lock(mPositionMutex);
mLocalTransform.setOrigin(vec);
mTransformUpdatePending = true;
}
void Object::commitPositionChange()
{
std::unique_lock<std::mutex> lock(mPositionMutex);
if (mScaleUpdatePending)
{
mShapeInstance->setLocalScaling(mScale);
@ -88,6 +92,7 @@ namespace MWPhysics
btTransform Object::getTransform() const
{
std::unique_lock<std::mutex> lock(mPositionMutex);
return mLocalTransform;
}

@ -8,6 +8,7 @@
#include <map>
#include <memory>
#include <mutex>
namespace Resource
{
@ -15,16 +16,17 @@ namespace Resource
}
class btCollisionObject;
class btCollisionWorld;
class btQuaternion;
class btVector3;
namespace MWPhysics
{
class PhysicsTaskScheduler;
class Object final : public PtrHolder
{
public:
Object(const MWWorld::Ptr& ptr, osg::ref_ptr<Resource::BulletShapeInstance> shapeInstance, btCollisionWorld* world);
Object(const MWWorld::Ptr& ptr, osg::ref_ptr<Resource::BulletShapeInstance> shapeInstance, PhysicsTaskScheduler* scheduler);
~Object() override;
const Resource::BulletShapeInstance* getShapeInstance() const;
@ -48,11 +50,12 @@ namespace MWPhysics
osg::ref_ptr<Resource::BulletShapeInstance> mShapeInstance;
std::map<int, osg::NodePath> mRecIndexToNodePath;
bool mSolid;
btCollisionWorld* mCollisionWorld;
btVector3 mScale;
btTransform mLocalTransform;
bool mScaleUpdatePending;
bool mTransformUpdatePending;
mutable std::mutex mPositionMutex;
PhysicsTaskScheduler* mTaskScheduler;
};
}

@ -35,7 +35,6 @@
#include "../mwworld/esmstore.hpp"
#include "../mwworld/cellstore.hpp"
#include "../mwworld/player.hpp"
#include "../mwrender/bulletdebugdraw.hpp"
@ -52,6 +51,7 @@
#include "contacttestresultcallback.hpp"
#include "constants.hpp"
#include "movementsolver.hpp"
#include "mtphysics.hpp"
namespace MWPhysics
{
@ -88,6 +88,8 @@ namespace MWPhysics
Log(Debug::Warning) << "Warning: using custom physics framerate (" << physFramerate << " FPS).";
}
}
mTaskScheduler = std::make_unique<PhysicsTaskScheduler>(mPhysicsDt, mCollisionWorld);
}
PhysicsSystem::~PhysicsSystem()
@ -95,11 +97,11 @@ namespace MWPhysics
mResourceSystem->removeResourceManager(mShapeManager.get());
if (mWaterCollisionObject)
mCollisionWorld->removeCollisionObject(mWaterCollisionObject.get());
mTaskScheduler->removeCollisionObject(mWaterCollisionObject.get());
for (auto& heightField : mHeightFields)
{
mCollisionWorld->removeCollisionObject(heightField.second->getCollisionObject());
mTaskScheduler->removeCollisionObject(heightField.second->getCollisionObject());
delete heightField.second;
}
@ -211,7 +213,7 @@ namespace MWPhysics
DeepestNotMeContactTestResultCallback resultCallback(me, targetCollisionObjects, Misc::Convert::toBullet(origin));
resultCallback.m_collisionFilterGroup = CollisionType_Actor;
resultCallback.m_collisionFilterMask = CollisionType_World | CollisionType_Door | CollisionType_HeightMap | CollisionType_Actor;
mCollisionWorld->contactTest(&object, resultCallback);
mTaskScheduler->contactTest(&object, resultCallback);
if (resultCallback.mObject)
{
@ -235,21 +237,12 @@ namespace MWPhysics
rayFrom.setIdentity();
rayFrom.setOrigin(Misc::Convert::toBullet(point));
// target the collision object's world origin, this should be the center of the collision object
btTransform rayTo;
rayTo.setIdentity();
rayTo.setOrigin(targetCollisionObj->getWorldTransform().getOrigin());
btCollisionWorld::ClosestRayResultCallback cb(rayFrom.getOrigin(), rayTo.getOrigin());
auto hitpoint = mTaskScheduler->getHitPoint(rayFrom, targetCollisionObj);
if (hitpoint)
return (point - Misc::Convert::toOsg(hitpoint.get())).length();
btCollisionWorld::rayTestSingle(rayFrom, rayTo, targetCollisionObj, targetCollisionObj->getCollisionShape(), targetCollisionObj->getWorldTransform(), cb);
if (!cb.hasHit())
{
// didn't hit the target. this could happen if point is already inside the collision box
return 0.f;
}
else
return (point - Misc::Convert::toOsg(cb.m_hitPointWorld)).length();
// didn't hit the target. this could happen if point is already inside the collision box
return 0.f;
}
RayCastingResult PhysicsSystem::castRay(const osg::Vec3f &from, const osg::Vec3f &to, const MWWorld::ConstPtr& ignore, std::vector<MWWorld::Ptr> targets, int mask, int group) const
@ -293,7 +286,7 @@ namespace MWPhysics
resultCallback.m_collisionFilterGroup = group;
resultCallback.m_collisionFilterMask = mask;
mCollisionWorld->rayTest(btFrom, btTo, resultCallback);
mTaskScheduler->rayTest(btFrom, btTo, resultCallback);
RayCastingResult result;
result.mHit = resultCallback.hasHit();
@ -319,7 +312,7 @@ namespace MWPhysics
btTransform from_ (btrot, Misc::Convert::toBullet(from));
btTransform to_ (btrot, Misc::Convert::toBullet(to));
mCollisionWorld->convexSweepTest(&shape, from_, to_, callback);
mTaskScheduler->convexSweepTest(&shape, from_, to_, callback);
RayCastingResult result;
result.mHit = callback.hasHit();
@ -333,18 +326,15 @@ namespace MWPhysics
bool PhysicsSystem::getLineOfSight(const MWWorld::ConstPtr &actor1, const MWWorld::ConstPtr &actor2) const
{
const Actor* physactor1 = getActor(actor1);
const Actor* physactor2 = getActor(actor2);
if (!physactor1 || !physactor2)
return false;
osg::Vec3f pos1 (physactor1->getCollisionObjectPosition() + osg::Vec3f(0,0,physactor1->getHalfExtents().z() * 0.9)); // eye level
osg::Vec3f pos2 (physactor2->getCollisionObjectPosition() + osg::Vec3f(0,0,physactor2->getHalfExtents().z() * 0.9));
RayCastingResult result = castRay(pos1, pos2, MWWorld::ConstPtr(), std::vector<MWWorld::Ptr>(), CollisionType_World|CollisionType_HeightMap|CollisionType_Door);
const auto getWeakPtr = [&](const MWWorld::ConstPtr &ptr) -> std::weak_ptr<Actor>
{
const auto found = mActors.find(ptr);
if (found != mActors.end())
return { found->second };
return {};
};
return !result.mHit;
return mTaskScheduler->getLineOfSight(getWeakPtr(actor1), getWeakPtr(actor2));
}
bool PhysicsSystem::isOnGround(const MWWorld::Ptr &actor)
@ -398,7 +388,7 @@ namespace MWPhysics
const Object * physobject = getObject(object);
if (!physobject) return osg::BoundingBox();
btVector3 min, max;
physobject->getCollisionObject()->getCollisionShape()->getAabb(physobject->getCollisionObject()->getWorldTransform(), min, max);
mTaskScheduler->getAabb(physobject->getCollisionObject(), min, max);
return osg::BoundingBox(Misc::Convert::toOsg(min), Misc::Convert::toOsg(max));
}
@ -424,7 +414,7 @@ namespace MWPhysics
ContactTestResultCallback resultCallback (me);
resultCallback.m_collisionFilterGroup = collisionGroup;
resultCallback.m_collisionFilterMask = collisionMask;
mCollisionWorld->contactTest(me, resultCallback);
mTaskScheduler->contactTest(me, resultCallback);
return resultCallback.mResult;
}
@ -442,7 +432,7 @@ namespace MWPhysics
HeightField *heightfield = new HeightField(heights, x, y, triSize, sqrtVerts, minH, maxH, holdObject);
mHeightFields[std::make_pair(x,y)] = heightfield;
mCollisionWorld->addCollisionObject(heightfield->getCollisionObject(), CollisionType_HeightMap,
mTaskScheduler->addCollisionObject(heightfield->getCollisionObject(), CollisionType_HeightMap,
CollisionType_Actor|CollisionType_Projectile);
}
@ -451,7 +441,7 @@ namespace MWPhysics
HeightFieldMap::iterator heightfield = mHeightFields.find(std::make_pair(x,y));
if(heightfield != mHeightFields.end())
{
mCollisionWorld->removeCollisionObject(heightfield->second->getCollisionObject());
mTaskScheduler->removeCollisionObject(heightfield->second->getCollisionObject());
delete heightfield->second;
mHeightFields.erase(heightfield);
}
@ -471,13 +461,13 @@ namespace MWPhysics
if (!shapeInstance || !shapeInstance->getCollisionShape())
return;
auto obj = std::make_shared<Object>(ptr, shapeInstance, mCollisionWorld.get());
auto obj = std::make_shared<Object>(ptr, shapeInstance, mTaskScheduler.get());
mObjects.emplace(ptr, obj);
if (obj->isAnimated())
mAnimatedObjects.insert(obj.get());
mCollisionWorld->addCollisionObject(obj->getCollisionObject(), collisionType,
mTaskScheduler->addCollisionObject(obj->getCollisionObject(), collisionType,
CollisionType_Actor|CollisionType_HeightMap|CollisionType_Projectile);
}
@ -571,14 +561,14 @@ namespace MWPhysics
{
float scale = ptr.getCellRef().getScale();
found->second->setScale(scale);
mCollisionWorld->updateSingleAabb(found->second->getCollisionObject());
mTaskScheduler->updateSingleAabb(found->second);
return;
}
ActorMap::iterator foundActor = mActors.find(ptr);
if (foundActor != mActors.end())
{
foundActor->second->updateScale();
mCollisionWorld->updateSingleAabb(foundActor->second->getCollisionObject());
mTaskScheduler->updateSingleAabb(foundActor->second);
return;
}
}
@ -589,7 +579,7 @@ namespace MWPhysics
if (found != mObjects.end())
{
found->second->setRotation(Misc::Convert::toBullet(ptr.getRefData().getBaseNode()->getAttitude()));
mCollisionWorld->updateSingleAabb(found->second->getCollisionObject());
mTaskScheduler->updateSingleAabb(found->second);
return;
}
ActorMap::iterator foundActor = mActors.find(ptr);
@ -598,7 +588,7 @@ namespace MWPhysics
if (!foundActor->second->isRotationallyInvariant())
{
foundActor->second->updateRotation();
mCollisionWorld->updateSingleAabb(foundActor->second->getCollisionObject());
mTaskScheduler->updateSingleAabb(foundActor->second);
}
return;
}
@ -610,14 +600,14 @@ namespace MWPhysics
if (found != mObjects.end())
{
found->second->setOrigin(Misc::Convert::toBullet(ptr.getRefData().getPosition().asVec3()));
mCollisionWorld->updateSingleAabb(found->second->getCollisionObject());
mTaskScheduler->updateSingleAabb(found->second);
return;
}
ActorMap::iterator foundActor = mActors.find(ptr);
if (foundActor != mActors.end())
{
foundActor->second->updatePosition();
mCollisionWorld->updateSingleAabb(foundActor->second->getCollisionObject());
mTaskScheduler->updateSingleAabb(foundActor->second);
return;
}
}
@ -639,7 +629,7 @@ namespace MWPhysics
if (!shape)
return;
auto actor = std::make_shared<Actor>(ptr, shape, mCollisionWorld.get());
auto actor = std::make_shared<Actor>(ptr, shape, mTaskScheduler.get());
mActors.emplace(ptr, std::move(actor));
}
@ -678,10 +668,8 @@ namespace MWPhysics
mStandingCollisions.clear();
}
const PtrPositionList& PhysicsSystem::applyQueuedMovement(float dt)
const PtrPositionList& PhysicsSystem::applyQueuedMovement(float dt, bool skipSimulation)
{
mMovementResults.clear();
mTimeAccum += dt;
const int maxAllowedSteps = 20;
@ -689,100 +677,8 @@ namespace MWPhysics
numSteps = std::min(numSteps, maxAllowedSteps);
mTimeAccum -= numSteps * mPhysicsDt;
mActorsFrameData = prepareFrameData();
bool advanceSimulation = (numSteps != 0);
if (advanceSimulation)
mWorldFrameData = std::make_unique<WorldFrameData>();
// update each actor position based on latest data
for (auto& data : mActorsFrameData)
data.updatePosition();
mMovementResults.clear();
while (numSteps--)
{
for (auto& actorData : mActorsFrameData)
MovementSolver::move(actorData, mPhysicsDt, mCollisionWorld.get(), *mWorldFrameData);
// update actors position
for (auto& actorData : mActorsFrameData)
{
if(const auto actor = actorData.mActor.lock())
{
if (actorData.mPosition != actorData.mActorRaw->getPosition())
actorData.mPositionChanged = true;
actorData.mActorRaw->setPosition(actorData.mPosition);
}
}
}
for (auto& actorData : mActorsFrameData)
{
// handle fall of actor
const float heightDiff = actorData.mPosition.z() - actorData.mOldHeight;
const bool isStillOnGround = (advanceSimulation && actorData.mWasOnGround && actorData.mActorRaw->getOnGround());
if (isStillOnGround || actorData.mFlying || actorData.mSwimming || actorData.mSlowFall < 1)
actorData.mNeedLand = true;
else if (heightDiff < 0)
actorData.mFallHeight += heightDiff;
// interpolate position
const float interpolationFactor = mTimeAccum / mPhysicsDt;
mMovementResults[actorData.mPtr] = actorData.mPosition * interpolationFactor + actorData.mActorRaw->getPreviousPosition() * (1.f - interpolationFactor);
// update mechanics if actor jumped
if (actorData.mDidJump)
{
const bool isPlayer = (actorData.mPtr == MWMechanics::getPlayer());
// Advance acrobatics and set flag for GetPCJumping
if (isPlayer)
{
actorData.mPtr.getClass().skillUsageSucceeded(actorData.mPtr, ESM::Skill::Acrobatics, 0);
MWBase::Environment::get().getWorld()->getPlayer().setJumping(true);
}
// Decrease fatigue
if (!isPlayer || !MWBase::Environment::get().getWorld()->getGodModeState())
{
const MWWorld::Store<ESM::GameSetting> &gmst = MWBase::Environment::get().getWorld()->getStore().get<ESM::GameSetting>();
const float fFatigueJumpBase = gmst.find("fFatigueJumpBase")->mValue.getFloat();
const float fFatigueJumpMult = gmst.find("fFatigueJumpMult")->mValue.getFloat();
const float normalizedEncumbrance = std::min(1.f, actorData.mPtr.getClass().getNormalizedEncumbrance(actorData.mPtr));
const float fatigueDecrease = fFatigueJumpBase + normalizedEncumbrance * fFatigueJumpMult;
MWMechanics::DynamicStat<float> fatigue = actorData.mPtr.getClass().getCreatureStats(actorData.mPtr).getFatigue();
fatigue.setCurrent(fatigue.getCurrent() - fatigueDecrease);
actorData.mPtr.getClass().getCreatureStats(actorData.mPtr).setFatigue(fatigue);
}
actorData.mPtr.getClass().getMovementSettings(actorData.mPtr).mPosition[2] = 0;
}
MWMechanics::CreatureStats& stats = actorData.mPtr.getClass().getCreatureStats(actorData.mPtr);
if (actorData.mNeedLand)
stats.land(actorData.mPtr == MWMechanics::getPlayer() && (actorData.mFlying || actorData.mSwimming));
else if (actorData.mFallHeight < 0)
stats.addToFallHeight(-actorData.mFallHeight);
}
// update actors aabb
for (const auto& actorData : mActorsFrameData)
if (actorData.mPositionChanged)
mCollisionWorld->updateSingleAabb(actorData.mActorRaw->getCollisionObject());
// update standing collisions map
if (advanceSimulation)
{
mStandingCollisions.clear();
for (auto& actorData : mActorsFrameData)
{
if (!actorData.mStandingOn.isEmpty())
mStandingCollisions[actorData.mPtr] = actorData.mStandingOn;
else
mStandingCollisions.erase(actorData.mPtr);
}
}
return mMovementResults;
return mTaskScheduler->moveActors(numSteps, mTimeAccum, prepareFrameData(), mStandingCollisions, skipSimulation);
}
std::vector<ActorFrameData> PhysicsSystem::prepareFrameData()
@ -840,7 +736,7 @@ namespace MWPhysics
{
auto obj = mObjects.find(animatedObject->getPtr());
assert(obj != mObjects.end());
mCollisionWorld->updateSingleAabb(obj->second->getCollisionObject());
mTaskScheduler->updateSingleAabb(obj->second);
}
#ifndef BT_NO_PROFILE
@ -854,7 +750,7 @@ namespace MWPhysics
ObjectMap::iterator found = mObjects.find(object);
if (found != mObjects.end())
if (found->second->animateCollisionShapes())
mCollisionWorld->updateSingleAabb(found->second->getCollisionObject());
mTaskScheduler->updateSingleAabb(found->second);
}
void PhysicsSystem::debugDraw()
@ -926,7 +822,7 @@ namespace MWPhysics
{
if (mWaterCollisionObject)
{
mCollisionWorld->removeCollisionObject(mWaterCollisionObject.get());
mTaskScheduler->removeCollisionObject(mWaterCollisionObject.get());
}
if (!mWaterEnabled)
@ -938,7 +834,7 @@ namespace MWPhysics
mWaterCollisionObject.reset(new btCollisionObject());
mWaterCollisionShape.reset(new btStaticPlaneShape(btVector3(0,0,1), mWaterHeight));
mWaterCollisionObject->setCollisionShape(mWaterCollisionShape.get());
mCollisionWorld->addCollisionObject(mWaterCollisionObject.get(), CollisionType_Water,
mTaskScheduler->addCollisionObject(mWaterCollisionObject.get(), CollisionType_Water,
CollisionType_Actor);
}
@ -954,7 +850,7 @@ namespace MWPhysics
const int mask = MWPhysics::CollisionType_Actor;
const int group = 0xff;
HasSphereCollisionCallback callback(bulletPosition, radius, object, mask, group);
mCollisionWorld->getBroadphase()->aabbTest(aabbMin, aabbMax, callback);
mTaskScheduler->aabbTest(aabbMin, aabbMax, callback);
return callback.getResult();
}

@ -193,7 +193,7 @@ namespace MWPhysics
void queueObjectMovement(const MWWorld::Ptr &ptr, const osg::Vec3f &velocity);
/// Apply all queued movements, then clear the list.
const PtrPositionList& applyQueuedMovement(float dt);
const PtrPositionList& applyQueuedMovement(float dt, bool skipSimulation);
/// Clear the queued movements list without applying.
void clearQueuedMovement();
@ -245,6 +245,7 @@ namespace MWPhysics
std::unique_ptr<btDefaultCollisionConfiguration> mCollisionConfiguration;
std::unique_ptr<btCollisionDispatcher> mDispatcher;
std::shared_ptr<btCollisionWorld> mCollisionWorld;
std::unique_ptr<PhysicsTaskScheduler> mTaskScheduler;
std::unique_ptr<Resource::BulletShapeManager> mShapeManager;
Resource::ResourceSystem* mResourceSystem;
@ -271,9 +272,6 @@ namespace MWPhysics
using PtrVelocityList = std::vector<std::pair<MWWorld::Ptr, osg::Vec3f>>;
PtrVelocityList mMovementQueue;
PtrPositionList mMovementResults;
std::unique_ptr<WorldFrameData> mWorldFrameData;
std::vector<ActorFrameData> mActorsFrameData;
float mTimeAccum;

@ -144,7 +144,7 @@ namespace MWWorld
const std::string& resourcePath, const std::string& userDataPath)
: mResourceSystem(resourceSystem), mLocalScripts (mStore),
mCells (mStore, mEsm), mSky (true),
mGodMode(false), mScriptsEnabled(true), mContentFiles (contentFiles),
mGodMode(false), mScriptsEnabled(true), mDiscardMovements(true), mContentFiles (contentFiles),
mUserDataPath(userDataPath), mShouldUpdateNavigator(false),
mActivationDistanceOverride (activationDistanceOverride),
mStartCell(startCell), mDistanceToFacedObject(-1.f), mTeleportEnabled(true),
@ -932,6 +932,7 @@ namespace MWWorld
void World::changeToInteriorCell (const std::string& cellName, const ESM::Position& position, bool adjustPlayerPos, bool changeEvent)
{
mPhysics->clearQueuedMovement();
mDiscardMovements = true;
if (changeEvent && mCurrentWorldSpace != cellName)
{
@ -951,6 +952,7 @@ namespace MWWorld
void World::changeToExteriorCell (const ESM::Position& position, bool adjustPlayerPos, bool changeEvent)
{
mPhysics->clearQueuedMovement();
mDiscardMovements = true;
if (changeEvent && mCurrentWorldSpace != ESM::CellId::sDefaultWorldspace)
{
@ -1499,7 +1501,8 @@ namespace MWWorld
mProjectileManager->update(duration);
const auto results = mPhysics->applyQueuedMovement(duration);
const auto results = mPhysics->applyQueuedMovement(duration, mDiscardMovements);
mDiscardMovements = false;
for(const auto& result : results)
{

@ -102,6 +102,7 @@ namespace MWWorld
bool mSky;
bool mGodMode;
bool mScriptsEnabled;
bool mDiscardMovements;
std::vector<std::string> mContentFiles;
std::string mUserDataPath;

@ -0,0 +1,51 @@
#ifndef OPENMW_BARRIER_H
#define OPENMW_BARRIER_H
#include <condition_variable>
#include <functional>
#include <mutex>
namespace Misc
{
/// @brief Synchronize several threads
class Barrier
{
public:
using BarrierCallback = std::function<void(void)>;
/// @param count number of threads to wait on
/// @param func callable to be executed once after all threads have met
Barrier(int count, BarrierCallback&& func) : mThreadCount(count), mRendezvousCount(0), mGeneration(0)
, mFunc(std::forward<BarrierCallback>(func))
{}
/// @brief stop execution of threads until count distinct threads reach this point
void wait()
{
std::unique_lock<std::mutex> lock(mMutex);
++mRendezvousCount;
const int currentGeneration = mGeneration;
if (mRendezvousCount == mThreadCount)
{
++mGeneration;
mRendezvousCount = 0;
mFunc();
mRendezvous.notify_all();
}
else
{
mRendezvous.wait(lock, [&]() { return mGeneration != currentGeneration; });
}
}
private:
int mThreadCount;
int mRendezvousCount;
int mGeneration;
mutable std::mutex mMutex;
std::condition_variable mRendezvous;
BarrierCallback mFunc;
};
}
#endif

@ -916,3 +916,15 @@ object shadows = false
# Allow shadows indoors. Due to limitations with Morrowind's data, only actors can cast shadows indoors, which some might feel is distracting.
enable indoor shadows = true
[Physics]
# how much background thread to use in the physics solver. 0 to disable (i.e solver run in the main thread)
async num threads = 0
# maintain a cache of lineofsight request in the bacground physics thread
# determines for how much frames an inactive lineofsight request should be kept updated in the cache
# -1 to disable (i.e the LOS will be calculated only on request)
lineofsight keep inactive cache = 0
# wether to defer aabb update till before collision detection
defer aabb update = true

Loading…
Cancel
Save