pull andrew's measure-acceleration branch

This commit is contained in:
Seth Alves 2015-04-17 11:35:12 -07:00
commit 292ba20cf3
7 changed files with 138 additions and 88 deletions

View file

@ -2231,6 +2231,7 @@ void Application::update(float deltaTime) {
PerformanceTimer perfTimer("physics");
_myAvatar->relayDriveKeysToCharacterController();
_physicsEngine.stepSimulation();
_physicsEngine.dumpStatsIfNecessary();
}
if (!_aboutToQuit) {

View file

@ -62,6 +62,9 @@ void EntityMotionState::stepKinematicSimulation(quint64 now) {
// which is different from physical kinematic motion (inside getWorldTransform())
// which steps in physics simulation time.
_entity->simulate(now);
// TODO: we can't use ObjectMotionState::measureAcceleration() here because the entity
// has no RigidBody and the timestep is a little bit out of sync with the physics simulation anyway.
// Hence we must manually measure kinematic velocity and acceleration.
}
bool EntityMotionState::isMoving() const {
@ -71,7 +74,7 @@ bool EntityMotionState::isMoving() const {
// This callback is invoked by the physics simulation in two cases:
// (1) when the RigidBody is first added to the world
// (irregardless of MotionType: STATIC, DYNAMIC, or KINEMATIC)
// (2) at the beginning of each simulation frame for KINEMATIC RigidBody's --
// (2) at the beginning of each simulation step for KINEMATIC RigidBody's --
// it is an opportunity for outside code to update the object's simulation position
void EntityMotionState::getWorldTransform(btTransform& worldTrans) const {
if (_isKinematic) {
@ -89,9 +92,10 @@ void EntityMotionState::getWorldTransform(btTransform& worldTrans) const {
worldTrans.setRotation(glmToBullet(_entity->getRotation()));
}
// This callback is invoked by the physics simulation at the end of each simulation frame...
// This callback is invoked by the physics simulation at the end of each simulation step...
// iff the corresponding RigidBody is DYNAMIC and has moved.
void EntityMotionState::setWorldTransform(const btTransform& worldTrans) {
measureAcceleration();
_entity->setPosition(bulletToGLM(worldTrans.getOrigin()) + ObjectMotionState::getWorldOffset());
_entity->setRotation(bulletToGLM(worldTrans.getRotation()));
@ -116,7 +120,7 @@ void EntityMotionState::setWorldTransform(const btTransform& worldTrans) {
#endif
}
void EntityMotionState::updateObjectEasy(uint32_t flags, uint32_t frame) {
void EntityMotionState::updateObjectEasy(uint32_t flags, uint32_t step) {
if (flags & (EntityItem::DIRTY_POSITION | EntityItem::DIRTY_VELOCITY)) {
if (flags & EntityItem::DIRTY_POSITION) {
_sentPosition = _entity->getPosition() - ObjectMotionState::getWorldOffset();
@ -131,7 +135,7 @@ void EntityMotionState::updateObjectEasy(uint32_t flags, uint32_t frame) {
if (flags & EntityItem::DIRTY_VELOCITY) {
updateObjectVelocities();
}
_sentFrame = frame;
_sentStep = step;
}
// TODO: entity support for friction and restitution
@ -179,7 +183,6 @@ float EntityMotionState::computeMass(const ShapeInfo& shapeInfo) const {
return _entity->computeMass();
}
bool EntityMotionState::shouldSendUpdate(uint32_t simulationFrame) {
bool baseResult = this->ObjectMotionState::shouldSendUpdate(simulationFrame);
@ -199,8 +202,8 @@ bool EntityMotionState::shouldSendUpdate(uint32_t simulationFrame) {
return true;
}
void EntityMotionState::sendUpdate(OctreeEditPacketSender* packetSender, uint32_t step) {
void EntityMotionState::sendUpdate(OctreeEditPacketSender* packetSender, uint32_t frame) {
if (!_entity->isKnownID()) {
return; // never update entities that are unknown
}
@ -305,7 +308,7 @@ void EntityMotionState::sendUpdate(OctreeEditPacketSender* packetSender, uint32_
// The outgoing flags only itemized WHAT to send, not WHETHER to send, hence we always set them
// to the full set. These flags may be momentarily cleared by incoming external changes.
_outgoingPacketFlags = DIRTY_PHYSICS_FLAGS;
_sentFrame = frame;
_sentStep = step;
}
}

View file

@ -50,14 +50,14 @@ public:
virtual void setWorldTransform(const btTransform& worldTrans);
// these relay incoming values to the RigidBody
virtual void updateObjectEasy(uint32_t flags, uint32_t frame);
virtual void updateObjectEasy(uint32_t flags, uint32_t step);
virtual void updateObjectVelocities();
virtual void computeShapeInfo(ShapeInfo& shapeInfo);
virtual float computeMass(const ShapeInfo& shapeInfo) const;
virtual bool shouldSendUpdate(uint32_t simulationFrame);
virtual void sendUpdate(OctreeEditPacketSender* packetSender, uint32_t frame);
virtual void sendUpdate(OctreeEditPacketSender* packetSender, uint32_t step);
virtual uint32_t getIncomingDirtyFlags() const;
virtual void clearIncomingDirtyFlags(uint32_t flags) { _entity->clearDirtyFlags(flags); }

View file

@ -22,7 +22,7 @@ const float MAX_FRICTION = 10.0f;
const float DEFAULT_RESTITUTION = 0.5f;
// origin of physics simulation in world frame
// origin of physics simulation in world-frame
glm::vec3 _worldOffset(0.0f);
// static
@ -35,6 +35,12 @@ const glm::vec3& ObjectMotionState::getWorldOffset() {
return _worldOffset;
}
// static
uint32_t _simulationStep = 0;
void ObjectMotionState::setSimulationStep(uint32_t step) {
assert(step > _simulationStep);
_simulationStep = step;
}
ObjectMotionState::ObjectMotionState() :
_friction(DEFAULT_FRICTION),
@ -46,12 +52,15 @@ ObjectMotionState::ObjectMotionState() :
_sentMoving(false),
_numNonMovingUpdates(0),
_outgoingPacketFlags(DIRTY_PHYSICS_FLAGS),
_sentFrame(0),
_sentStep(0),
_sentPosition(0.0f),
_sentRotation(),
_sentVelocity(0.0f),
_sentAngularVelocity(0.0f),
_sentAcceleration(0.0f) {
_sentAcceleration(0.0f),
_lastSimulationStep(0),
_lastVelocity(0.0f),
_measuredAcceleration(0.0f) {
}
ObjectMotionState::~ObjectMotionState() {
@ -59,6 +68,27 @@ ObjectMotionState::~ObjectMotionState() {
assert(_body == NULL);
}
void ObjectMotionState::measureAcceleration() {
// try to manually measure the true acceleration of the object
uint32_t numSubsteps = _simulationStep - _lastSimulationStep;
if (numSubsteps > 0) {
float dt = ((float)numSubsteps * PHYSICS_ENGINE_FIXED_SUBSTEP);
float invDt = 1.0f / dt;
_lastSimulationStep = _simulationStep;
// Note: the integration equation for velocity uses damping: v1 = (v0 + a * dt) * (1 - D)^dt
// hence the equation for acceleration is: a = (v1 / (1 - D)^dt - v0) / dt
glm::vec3 velocity = bulletToGLM(_body->getLinearVelocity());
_measuredAcceleration = (velocity / powf(1.0f - _linearDamping, dt) - _lastVelocity) * invDt;
_lastVelocity = velocity;
}
}
void ObjectMotionState::resetMeasuredAcceleration() {
_lastSimulationStep = _simulationStep;
_lastVelocity = bulletToGLM(_body->getLinearVelocity());
}
void ObjectMotionState::setFriction(float friction) {
_friction = btMax(btMin(fabsf(friction), MAX_FRICTION), 0.0f);
}
@ -103,15 +133,16 @@ bool ObjectMotionState::doesNotNeedToSendUpdate() const {
return !_body->isActive() && _numNonMovingUpdates > MAX_NUM_NON_MOVING_UPDATES;
}
bool ObjectMotionState::shouldSendUpdate(uint32_t simulationFrame) {
bool ObjectMotionState::shouldSendUpdate(uint32_t simulationStep) {
assert(_body);
// if we've never checked before, our _sentFrame will be 0, and we need to initialize our state
if (_sentFrame == 0) {
_sentPosition = bulletToGLM(_body->getWorldTransform().getOrigin());
// if we've never checked before, our _sentStep will be 0, and we need to initialize our state
if (_sentStep == 0) {
btTransform xform = _body->getWorldTransform();
_sentPosition = bulletToGLM(xform.getOrigin());
_sentRotation = bulletToGLM(xform.getRotation());
_sentVelocity = bulletToGLM(_body->getLinearVelocity());
_sentRotation = bulletToGLM(_body->getWorldTransform().getRotation());
_sentAngularVelocity = bulletToGLM(_body->getAngularVelocity());
_sentFrame = simulationFrame;
_sentStep = simulationStep;
return false;
}
@ -121,9 +152,9 @@ bool ObjectMotionState::shouldSendUpdate(uint32_t simulationFrame) {
glm::vec3 wasAngularVelocity = _sentAngularVelocity;
#endif
int numFrames = simulationFrame - _sentFrame;
float dt = (float)(numFrames) * PHYSICS_ENGINE_FIXED_SUBSTEP;
_sentFrame = simulationFrame;
int numSteps = simulationStep - _sentStep;
float dt = (float)(numSteps) * PHYSICS_ENGINE_FIXED_SUBSTEP;
_sentStep = simulationStep;
bool isActive = _body->isActive();
if (!isActive) {
@ -179,7 +210,7 @@ bool ObjectMotionState::shouldSendUpdate(uint32_t simulationFrame) {
// Bullet caps the effective rotation velocity inside its rotation integration step, therefore
// we must integrate with the same algorithm and timestep in order achieve similar results.
for (int i = 0; i < numFrames; ++i) {
for (int i = 0; i < numSteps; ++i) {
_sentRotation = glm::normalize(computeBulletRotationStep(_sentAngularVelocity, PHYSICS_ENGINE_FIXED_SUBSTEP) * _sentRotation);
}
}

View file

@ -59,9 +59,14 @@ public:
static void setWorldOffset(const glm::vec3& offset);
static const glm::vec3& getWorldOffset();
static void setSimulationStep(uint32_t step);
ObjectMotionState();
~ObjectMotionState();
void measureAcceleration();
void resetMeasuredAcceleration();
// An EASY update does not require the object to be removed and then reinserted into the PhysicsEngine
virtual void updateObjectEasy(uint32_t flags, uint32_t frame) = 0;
virtual void updateObjectVelocities() = 0;
@ -89,7 +94,7 @@ public:
void clearOutgoingPacketFlags(uint32_t flags) { _outgoingPacketFlags &= ~flags; }
bool doesNotNeedToSendUpdate() const;
virtual bool shouldSendUpdate(uint32_t simulationFrame);
virtual bool shouldSendUpdate(uint32_t simulationStep);
virtual void sendUpdate(OctreeEditPacketSender* packetSender, uint32_t frame) = 0;
virtual MotionType computeMotionType() const = 0;
@ -128,12 +133,16 @@ protected:
int _numNonMovingUpdates; // RELIABLE_SEND_HACK for "not so reliable" resends of packets for non-moving objects
uint32_t _outgoingPacketFlags;
uint32_t _sentFrame;
uint32_t _sentStep;
glm::vec3 _sentPosition; // in simulation-frame (not world-frame)
glm::quat _sentRotation;;
glm::vec3 _sentVelocity;
glm::vec3 _sentAngularVelocity; // radians per second
glm::vec3 _sentAcceleration;
uint32_t _lastSimulationStep;
glm::vec3 _lastVelocity;
glm::vec3 _measuredAcceleration;
};
#endif // hifi_ObjectMotionState_h

View file

@ -193,6 +193,9 @@ void PhysicsEngine::relayIncomingChangesToSimulation() {
// hence the MotionState has all the knowledge and authority to perform the update.
motionState->updateObjectEasy(flags, _numSubsteps);
}
if (flags & (EntityItem::DIRTY_POSITION | EntityItem::DIRTY_VELOCITY)) {
motionState->resetMeasuredAcceleration();
}
} else {
// the only way we should ever get here (motionState exists but no body) is when the object
// is undergoing non-physical kinematic motion.
@ -288,77 +291,73 @@ void PhysicsEngine::init(EntityEditPacketSender* packetSender) {
}
void PhysicsEngine::stepSimulation() {
{
lock();
CProfileManager::Reset();
BT_PROFILE("stepSimulation");
// NOTE: the grand order of operations is:
// (1) pull incoming changes
// (2) step simulation
// (3) synchronize outgoing motion states
// (4) send outgoing packets
lock();
CProfileManager::Reset();
BT_PROFILE("stepSimulation");
// NOTE: the grand order of operations is:
// (1) pull incoming changes
// (2) step simulation
// (3) synchronize outgoing motion states
// (4) send outgoing packets
// This is step (1) pull incoming changes
relayIncomingChangesToSimulation();
const int MAX_NUM_SUBSTEPS = 4;
const float MAX_TIMESTEP = (float)MAX_NUM_SUBSTEPS * PHYSICS_ENGINE_FIXED_SUBSTEP;
float dt = 1.0e-6f * (float)(_clock.getTimeMicroseconds());
_clock.reset();
float timeStep = btMin(dt, MAX_TIMESTEP);
// TODO: move character->preSimulation() into relayIncomingChanges
if (_characterController) {
if (_characterController->needsRemoval()) {
_characterController->setDynamicsWorld(NULL);
}
_characterController->updateShapeIfNecessary();
if (_characterController->needsAddition()) {
_characterController->setDynamicsWorld(_dynamicsWorld);
}
_characterController->preSimulation(timeStep);
// This is step (1) pull incoming changes
relayIncomingChangesToSimulation();
const int MAX_NUM_SUBSTEPS = 4;
const float MAX_TIMESTEP = (float)MAX_NUM_SUBSTEPS * PHYSICS_ENGINE_FIXED_SUBSTEP;
float dt = 1.0e-6f * (float)(_clock.getTimeMicroseconds());
_clock.reset();
float timeStep = btMin(dt, MAX_TIMESTEP);
// TODO: move character->preSimulation() into relayIncomingChanges
if (_characterController) {
if (_characterController->needsRemoval()) {
_characterController->setDynamicsWorld(NULL);
}
// This is step (2) step simulation
int numSubsteps = _dynamicsWorld->stepSimulation(timeStep, MAX_NUM_SUBSTEPS, PHYSICS_ENGINE_FIXED_SUBSTEP);
_numSubsteps += (uint32_t)numSubsteps;
stepNonPhysicalKinematics(usecTimestampNow());
unlock();
// TODO: make all of this harvest stuff into one function: relayOutgoingChanges()
if (numSubsteps > 0) {
BT_PROFILE("postSimulation");
// This is step (3) which is done outside of stepSimulation() so we can lock _entityTree.
//
// Unfortunately we have to unlock the simulation (above) before we try to lock the _entityTree
// to avoid deadlock -- the _entityTree may try to lock its EntitySimulation (from which this
// PhysicsEngine derives) when updating/adding/deleting entities so we need to wait for our own
// lock on the tree before we re-lock ourselves.
//
// TODO: untangle these lock sequences.
_entityTree->lockForWrite();
lock();
_dynamicsWorld->synchronizeMotionStates();
if (_characterController) {
_characterController->postSimulation();
}
unlock();
_entityTree->unlock();
computeCollisionEvents();
_characterController->updateShapeIfNecessary();
if (_characterController->needsAddition()) {
_characterController->setDynamicsWorld(_dynamicsWorld);
}
_characterController->preSimulation(timeStep);
}
if (_dumpNextStats) {
_dumpNextStats = false;
CProfileManager::dumpAll();
// This is step (2) step simulation
int numSubsteps = _dynamicsWorld->stepSimulation(timeStep, MAX_NUM_SUBSTEPS, PHYSICS_ENGINE_FIXED_SUBSTEP);
_numSubsteps += (uint32_t)numSubsteps;
stepNonPhysicalKinematics(usecTimestampNow());
unlock();
// TODO: make all of this harvest stuff into one function: relayOutgoingChanges()
if (numSubsteps > 0) {
BT_PROFILE("postSimulation");
// This is step (3) which is done outside of stepSimulation() so we can lock _entityTree.
//
// Unfortunately we have to unlock the simulation (above) before we try to lock the _entityTree
// to avoid deadlock -- the _entityTree may try to lock its EntitySimulation (from which this
// PhysicsEngine derives) when updating/adding/deleting entities so we need to wait for our own
// lock on the tree before we re-lock ourselves.
//
// TODO: untangle these lock sequences.
ObjectMotionState::setSimulationStep(_numSubsteps);
_entityTree->lockForWrite();
lock();
_dynamicsWorld->synchronizeMotionStates();
if (_characterController) {
_characterController->postSimulation();
}
unlock();
_entityTree->unlock();
computeCollisionEvents();
}
}
void PhysicsEngine::stepNonPhysicalKinematics(const quint64& now) {
BT_PROFILE("nonPhysicalKinematics");
QSet<ObjectMotionState*>::iterator stateItr = _nonPhysicalKinematicObjects.begin();
// TODO?: need to occasionally scan for stopped non-physical kinematics objects
while (stateItr != _nonPhysicalKinematicObjects.end()) {
ObjectMotionState* motionState = *stateItr;
motionState->stepKinematicSimulation(now);
@ -366,8 +365,6 @@ void PhysicsEngine::stepNonPhysicalKinematics(const quint64& now) {
}
}
// TODO?: need to occasionally scan for stopped non-physical kinematics objects
void PhysicsEngine::computeCollisionEvents() {
BT_PROFILE("computeCollisionEvents");
// update all contacts every frame
@ -445,6 +442,13 @@ void PhysicsEngine::computeCollisionEvents() {
}
}
void PhysicsEngine::dumpStatsIfNecessary() {
if (_dumpNextStats) {
_dumpNextStats = false;
CProfileManager::dumpAll();
}
}
// Bullet collision flags are as follows:
// CF_STATIC_OBJECT= 1,
// CF_KINEMATIC_OBJECT= 2,
@ -507,6 +511,7 @@ void PhysicsEngine::addObject(const ShapeInfo& shapeInfo, btCollisionShape* shap
body->setFriction(motionState->_friction);
body->setDamping(motionState->_linearDamping, motionState->_angularDamping);
_dynamicsWorld->addRigidBody(body);
motionState->resetMeasuredAcceleration();
}
void PhysicsEngine::removeObjectFromBullet(ObjectMotionState* motionState) {

View file

@ -68,9 +68,10 @@ public:
void stepSimulation();
void stepNonPhysicalKinematics(const quint64& now);
void computeCollisionEvents();
void dumpStatsIfNecessary();
/// \param offset position of simulation origin in domain-frame
void setOriginOffset(const glm::vec3& offset) { _originOffset = offset; }