Merge pull request #350 from erwincoumans/master

maintain backward compatibility using BT_ENABLE_GYROPSCOPIC_FORCE = BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_BODY
This commit is contained in:
erwincoumans
2015-04-15 10:58:54 -07:00
14 changed files with 631 additions and 128 deletions

View File

@@ -0,0 +1,503 @@
#include "ForkLiftPhysicsSetup.h"
#include "BulletDynamics/MLCPSolvers/btDantzigSolver.h"
#include "BulletDynamics/MLCPSolvers/btSolveProjectedGaussSeidel.h"
#include "BulletDynamics/MLCPSolvers/btMLCPSolver.h"
#include "OpenGLWindow/CommonRenderInterface.h"
btScalar maxMotorImpulse = 1400.f;
btScalar loadMass = 350.f;//
#ifdef FORCE_ZAXIS_UP
int rightIndex = 0;
int upIndex = 2;
int forwardIndex = 1;
btVector3 wheelDirectionCS0(0,0,-1);
btVector3 wheelAxleCS(1,0,0);
#else
int rightIndex = 0;
int upIndex = 1;
int forwardIndex = 2;
btVector3 wheelDirectionCS0(0,-1,0);
btVector3 wheelAxleCS(-1,0,0);
#endif
float defaultBreakingForce = 10.f;
float gBreakingForce = 100.f;
float gEngineForce = 0.f;
float gVehicleSteering = 0.f;
float steeringIncrement = 0.04f;
float steeringClamp = 0.3f;
float wheelRadius = 0.5f;
float wheelWidth = 0.4f;
btScalar suspensionRestLength(0.6);
#define CUBE_HALF_EXTENTS 1
float suspensionStiffness = 20.f;
float suspensionDamping = 2.3f;
float suspensionCompression = 4.4f;
float rollInfluence = 0.1f;//1.0f;
float wheelFriction = 1000;//BT_LARGE_FLOAT;
struct ForkLiftInternalData
{
btRigidBody* m_carChassis;
//----------------------------
btRigidBody* m_liftBody;
btVector3 m_liftStartPos;
btHingeConstraint* m_liftHinge;
btRigidBody* m_forkBody;
btVector3 m_forkStartPos;
btSliderConstraint* m_forkSlider;
btRigidBody* m_loadBody;
btVector3 m_loadStartPos;
bool m_useDefaultCamera;
class btTriangleIndexVertexArray* m_indexVertexArrays;
btVector3* m_vertices;
btRaycastVehicle::btVehicleTuning m_tuning;
btVehicleRaycaster* m_vehicleRayCaster;
btRaycastVehicle* m_vehicle;
btCollisionShape* m_wheelShape;
float m_cameraHeight;
float m_minCameraDistance;
float m_maxCameraDistance;
btAlignedObjectArray<btCollisionShape*> m_collisionShapes;
class btBroadphaseInterface* m_overlappingPairCache;
class btCollisionDispatcher* m_dispatcher;
class btConstraintSolver* m_constraintSolver;
class btDefaultCollisionConfiguration* m_collisionConfiguration;
class btDiscreteDynamicsWorld* m_dynamicsWorld;
int m_wheelInstances[4];
bool useMCLPSolver;
ForkLiftInternalData()
:m_carChassis(0),
m_liftBody(0),
m_forkBody(0),
m_loadBody(0),
m_indexVertexArrays(0),
m_vertices(0),
m_cameraHeight(4.f),
m_minCameraDistance(3.f),
m_maxCameraDistance(10.f),
m_overlappingPairCache(0),
m_dispatcher(0),
m_constraintSolver(0),
m_collisionConfiguration(0),
m_dynamicsWorld(0),
useMCLPSolver(false)
{
m_vehicle = 0;
m_wheelShape = 0;
m_useDefaultCamera = false;
}
};
ForkLiftPhysicsSetup::ForkLiftPhysicsSetup()
{
m_data = new ForkLiftInternalData;
}
ForkLiftPhysicsSetup::~ForkLiftPhysicsSetup()
{
delete m_data;
}
void ForkLiftPhysicsSetup::initPhysics(GraphicsPhysicsBridge& gfxBridge)
{
#ifdef FORCE_ZAXIS_UP
m_cameraUp = btVector3(0,0,1);
m_forwardAxis = 1;
#endif
btCollisionShape* groundShape = new btBoxShape(btVector3(50,3,50));
m_data->m_collisionShapes.push_back(groundShape);
m_data->m_collisionConfiguration = new btDefaultCollisionConfiguration();
m_data->m_dispatcher = new btCollisionDispatcher(m_data->m_collisionConfiguration);
btVector3 worldMin(-1000,-1000,-1000);
btVector3 worldMax(1000,1000,1000);
m_data->m_overlappingPairCache = new btAxisSweep3(worldMin,worldMax);
if (m_data->useMCLPSolver)
{
btDantzigSolver* mlcp = new btDantzigSolver();
//btSolveProjectedGaussSeidel* mlcp = new btSolveProjectedGaussSeidel;
btMLCPSolver* sol = new btMLCPSolver(mlcp);
m_data->m_constraintSolver = sol;
} else
{
m_data->m_constraintSolver = new btSequentialImpulseConstraintSolver();
}
m_data->m_dynamicsWorld = new btDiscreteDynamicsWorld(m_data->m_dispatcher,m_data->m_overlappingPairCache,m_data->m_constraintSolver,m_data->m_collisionConfiguration);
if (m_data->useMCLPSolver)
{
m_data->m_dynamicsWorld ->getSolverInfo().m_minimumSolverBatchSize = 1;//for direct solver it is better to have a small A matrix
} else
{
m_data->m_dynamicsWorld ->getSolverInfo().m_minimumSolverBatchSize = 128;//for direct solver, it is better to solve multiple objects together, small batches have high overhead
}
#ifdef FORCE_ZAXIS_UP
m_dynamicsWorld->setGravity(btVector3(0,0,-10));
#endif
//m_dynamicsWorld->setGravity(btVector3(0,0,0));
btTransform tr;
tr.setIdentity();
tr.setOrigin(btVector3(0,-3,0));
//either use heightfield or triangle mesh
//create ground object
localCreateRigidBody(0,tr,groundShape);
#ifdef FORCE_ZAXIS_UP
// indexRightAxis = 0;
// indexUpAxis = 2;
// indexForwardAxis = 1;
btCollisionShape* chassisShape = new btBoxShape(btVector3(1.f,2.f, 0.5f));
btCompoundShape* compound = new btCompoundShape();
btTransform localTrans;
localTrans.setIdentity();
//localTrans effectively shifts the center of mass with respect to the chassis
localTrans.setOrigin(btVector3(0,0,1));
#else
btCollisionShape* chassisShape = new btBoxShape(btVector3(1.f,0.5f,2.f));
m_data->m_collisionShapes.push_back(chassisShape);
btCompoundShape* compound = new btCompoundShape();
m_data->m_collisionShapes.push_back(compound);
btTransform localTrans;
localTrans.setIdentity();
//localTrans effectively shifts the center of mass with respect to the chassis
localTrans.setOrigin(btVector3(0,1,0));
#endif
compound->addChildShape(localTrans,chassisShape);
{
btCollisionShape* suppShape = new btBoxShape(btVector3(0.5f,0.1f,0.5f));
btTransform suppLocalTrans;
suppLocalTrans.setIdentity();
//localTrans effectively shifts the center of mass with respect to the chassis
suppLocalTrans.setOrigin(btVector3(0,1.0,2.5));
compound->addChildShape(suppLocalTrans, suppShape);
}
tr.setOrigin(btVector3(0,0.f,0));
m_data->m_carChassis = localCreateRigidBody(800,tr,compound);//chassisShape);
//m_carChassis->setDamping(0.2,0.2);
m_data->m_wheelShape = new btCylinderShapeX(btVector3(wheelWidth,wheelRadius,wheelRadius));
gfxBridge.createCollisionShapeGraphicsObject(m_data->m_wheelShape);
int wheelGraphicsIndex = m_data->m_wheelShape->getUserIndex();
const float position[4]={0,10,10,0};
const float quaternion[4]={0,0,0,1};
const float color[4]={0,1,0,1};
const float scaling[4] = {1,1,1,1};
for (int i=0;i<4;i++)
{
m_data->m_wheelInstances[i] = gfxBridge.registerGraphicsInstance(wheelGraphicsIndex, position, quaternion, color, scaling);
}
{
btCollisionShape* liftShape = new btBoxShape(btVector3(0.5f,2.0f,0.05f));
m_data->m_collisionShapes.push_back(liftShape);
btTransform liftTrans;
m_data->m_liftStartPos = btVector3(0.0f, 2.5f, 3.05f);
liftTrans.setIdentity();
liftTrans.setOrigin(m_data->m_liftStartPos);
m_data->m_liftBody = localCreateRigidBody(10,liftTrans, liftShape);
btTransform localA, localB;
localA.setIdentity();
localB.setIdentity();
localA.getBasis().setEulerZYX(0, SIMD_HALF_PI, 0);
localA.setOrigin(btVector3(0.0, 1.0, 3.05));
localB.getBasis().setEulerZYX(0, SIMD_HALF_PI, 0);
localB.setOrigin(btVector3(0.0, -1.5, -0.05));
m_data->m_liftHinge = new btHingeConstraint(*m_data->m_carChassis,*m_data->m_liftBody, localA, localB);
// m_liftHinge->setLimit(-LIFT_EPS, LIFT_EPS);
m_data->m_liftHinge->setLimit(0.0f, 0.0f);
m_data->m_dynamicsWorld->addConstraint(m_data->m_liftHinge, true);
btCollisionShape* forkShapeA = new btBoxShape(btVector3(1.0f,0.1f,0.1f));
m_data->m_collisionShapes.push_back(forkShapeA);
btCompoundShape* forkCompound = new btCompoundShape();
m_data->m_collisionShapes.push_back(forkCompound);
btTransform forkLocalTrans;
forkLocalTrans.setIdentity();
forkCompound->addChildShape(forkLocalTrans, forkShapeA);
btCollisionShape* forkShapeB = new btBoxShape(btVector3(0.1f,0.02f,0.6f));
m_data->m_collisionShapes.push_back(forkShapeB);
forkLocalTrans.setIdentity();
forkLocalTrans.setOrigin(btVector3(-0.9f, -0.08f, 0.7f));
forkCompound->addChildShape(forkLocalTrans, forkShapeB);
btCollisionShape* forkShapeC = new btBoxShape(btVector3(0.1f,0.02f,0.6f));
m_data->m_collisionShapes.push_back(forkShapeC);
forkLocalTrans.setIdentity();
forkLocalTrans.setOrigin(btVector3(0.9f, -0.08f, 0.7f));
forkCompound->addChildShape(forkLocalTrans, forkShapeC);
btTransform forkTrans;
m_data->m_forkStartPos = btVector3(0.0f, 0.6f, 3.2f);
forkTrans.setIdentity();
forkTrans.setOrigin(m_data->m_forkStartPos);
m_data->m_forkBody = localCreateRigidBody(5, forkTrans, forkCompound);
localA.setIdentity();
localB.setIdentity();
localA.getBasis().setEulerZYX(0, 0, SIMD_HALF_PI);
localA.setOrigin(btVector3(0.0f, -1.9f, 0.05f));
localB.getBasis().setEulerZYX(0, 0, SIMD_HALF_PI);
localB.setOrigin(btVector3(0.0, 0.0, -0.1));
m_data->m_forkSlider = new btSliderConstraint(*m_data->m_liftBody, *m_data->m_forkBody, localA, localB, true);
m_data->m_forkSlider->setLowerLinLimit(0.1f);
m_data->m_forkSlider->setUpperLinLimit(0.1f);
// m_forkSlider->setLowerAngLimit(-LIFT_EPS);
// m_forkSlider->setUpperAngLimit(LIFT_EPS);
m_data->m_forkSlider->setLowerAngLimit(0.0f);
m_data->m_forkSlider->setUpperAngLimit(0.0f);
m_data->m_dynamicsWorld->addConstraint(m_data->m_forkSlider, true);
btCompoundShape* loadCompound = new btCompoundShape();
m_data->m_collisionShapes.push_back(loadCompound);
btCollisionShape* loadShapeA = new btBoxShape(btVector3(2.0f,0.5f,0.5f));
m_data->m_collisionShapes.push_back(loadShapeA);
btTransform loadTrans;
loadTrans.setIdentity();
loadCompound->addChildShape(loadTrans, loadShapeA);
btCollisionShape* loadShapeB = new btBoxShape(btVector3(0.1f,1.0f,1.0f));
m_data->m_collisionShapes.push_back(loadShapeB);
loadTrans.setIdentity();
loadTrans.setOrigin(btVector3(2.1f, 0.0f, 0.0f));
loadCompound->addChildShape(loadTrans, loadShapeB);
btCollisionShape* loadShapeC = new btBoxShape(btVector3(0.1f,1.0f,1.0f));
m_data->m_collisionShapes.push_back(loadShapeC);
loadTrans.setIdentity();
loadTrans.setOrigin(btVector3(-2.1f, 0.0f, 0.0f));
loadCompound->addChildShape(loadTrans, loadShapeC);
loadTrans.setIdentity();
m_data->m_loadStartPos = btVector3(0.0f, 3.5f, 7.0f);
loadTrans.setOrigin(m_data->m_loadStartPos);
m_data->m_loadBody = localCreateRigidBody(loadMass, loadTrans, loadCompound);
}
/// create vehicle
{
m_data->m_vehicleRayCaster = new btDefaultVehicleRaycaster(m_data->m_dynamicsWorld);
m_data->m_vehicle = new btRaycastVehicle(m_data->m_tuning,m_data->m_carChassis,m_data->m_vehicleRayCaster);
///never deactivate the vehicle
m_data->m_carChassis->setActivationState(DISABLE_DEACTIVATION);
m_data->m_dynamicsWorld->addVehicle(m_data->m_vehicle);
float connectionHeight = 1.2f;
bool isFrontWheel=true;
//choose coordinate system
m_data->m_vehicle->setCoordinateSystem(rightIndex,upIndex,forwardIndex);
#ifdef FORCE_ZAXIS_UP
btVector3 connectionPointCS0(CUBE_HALF_EXTENTS-(0.3*wheelWidth),2*CUBE_HALF_EXTENTS-wheelRadius, connectionHeight);
#else
btVector3 connectionPointCS0(CUBE_HALF_EXTENTS-(0.3*wheelWidth),connectionHeight,2*CUBE_HALF_EXTENTS-wheelRadius);
#endif
m_data->m_vehicle->addWheel(connectionPointCS0,wheelDirectionCS0,wheelAxleCS,suspensionRestLength,wheelRadius,m_data->m_tuning,isFrontWheel);
#ifdef FORCE_ZAXIS_UP
connectionPointCS0 = btVector3(-CUBE_HALF_EXTENTS+(0.3*wheelWidth),2*CUBE_HALF_EXTENTS-wheelRadius, connectionHeight);
#else
connectionPointCS0 = btVector3(-CUBE_HALF_EXTENTS+(0.3*wheelWidth),connectionHeight,2*CUBE_HALF_EXTENTS-wheelRadius);
#endif
m_data->m_vehicle->addWheel(connectionPointCS0,wheelDirectionCS0,wheelAxleCS,suspensionRestLength,wheelRadius,m_data->m_tuning,isFrontWheel);
#ifdef FORCE_ZAXIS_UP
connectionPointCS0 = btVector3(-CUBE_HALF_EXTENTS+(0.3*wheelWidth),-2*CUBE_HALF_EXTENTS+wheelRadius, connectionHeight);
#else
connectionPointCS0 = btVector3(-CUBE_HALF_EXTENTS+(0.3*wheelWidth),connectionHeight,-2*CUBE_HALF_EXTENTS+wheelRadius);
#endif //FORCE_ZAXIS_UP
isFrontWheel = false;
m_data->m_vehicle->addWheel(connectionPointCS0,wheelDirectionCS0,wheelAxleCS,suspensionRestLength,wheelRadius,m_data->m_tuning,isFrontWheel);
#ifdef FORCE_ZAXIS_UP
connectionPointCS0 = btVector3(CUBE_HALF_EXTENTS-(0.3*wheelWidth),-2*CUBE_HALF_EXTENTS+wheelRadius, connectionHeight);
#else
connectionPointCS0 = btVector3(CUBE_HALF_EXTENTS-(0.3*wheelWidth),connectionHeight,-2*CUBE_HALF_EXTENTS+wheelRadius);
#endif
m_data->m_vehicle->addWheel(connectionPointCS0,wheelDirectionCS0,wheelAxleCS,suspensionRestLength,wheelRadius,m_data->m_tuning,isFrontWheel);
for (int i=0;i<m_data->m_vehicle->getNumWheels();i++)
{
btWheelInfo& wheel = m_data->m_vehicle->getWheelInfo(i);
wheel.m_suspensionStiffness = suspensionStiffness;
wheel.m_wheelsDampingRelaxation = suspensionDamping;
wheel.m_wheelsDampingCompression = suspensionCompression;
wheel.m_frictionSlip = wheelFriction;
wheel.m_rollInfluence = rollInfluence;
}
}
resetForklift();
gfxBridge.autogenerateGraphicsObjects(m_data->m_dynamicsWorld);
// setCameraDistance(26.f);
}
void ForkLiftPhysicsSetup::resetForklift()
{
gVehicleSteering = 0.f;
gBreakingForce = defaultBreakingForce;
gEngineForce = 0.f;
m_data->m_carChassis->setCenterOfMassTransform(btTransform::getIdentity());
m_data->m_carChassis->setLinearVelocity(btVector3(0,0,0));
m_data->m_carChassis->setAngularVelocity(btVector3(0,0,0));
m_data->m_dynamicsWorld->getBroadphase()->getOverlappingPairCache()->cleanProxyFromPairs(m_data->m_carChassis->getBroadphaseHandle(),m_data->m_dynamicsWorld->getDispatcher());
if (m_data->m_vehicle)
{
m_data->m_vehicle->resetSuspension();
for (int i=0;i<m_data->m_vehicle->getNumWheels();i++)
{
//synchronize the wheels with the (interpolated) chassis worldtransform
m_data->m_vehicle->updateWheelTransform(i,true);
}
}
btTransform liftTrans;
liftTrans.setIdentity();
liftTrans.setOrigin(m_data->m_liftStartPos);
m_data->m_liftBody->activate();
m_data->m_liftBody->setCenterOfMassTransform(liftTrans);
m_data->m_liftBody->setLinearVelocity(btVector3(0,0,0));
m_data->m_liftBody->setAngularVelocity(btVector3(0,0,0));
btTransform forkTrans;
forkTrans.setIdentity();
forkTrans.setOrigin(m_data->m_forkStartPos);
m_data->m_forkBody->activate();
m_data->m_forkBody->setCenterOfMassTransform(forkTrans);
m_data->m_forkBody->setLinearVelocity(btVector3(0,0,0));
m_data->m_forkBody->setAngularVelocity(btVector3(0,0,0));
// m_liftHinge->setLimit(-LIFT_EPS, LIFT_EPS);
m_data->m_liftHinge->setLimit(0.0f, 0.0f);
m_data->m_liftHinge->enableAngularMotor(false, 0, 0);
m_data->m_forkSlider->setLowerLinLimit(0.1f);
m_data->m_forkSlider->setUpperLinLimit(0.1f);
m_data->m_forkSlider->setPoweredLinMotor(false);
btTransform loadTrans;
loadTrans.setIdentity();
loadTrans.setOrigin(m_data->m_loadStartPos);
m_data->m_loadBody->activate();
m_data->m_loadBody->setCenterOfMassTransform(loadTrans);
m_data->m_loadBody->setLinearVelocity(btVector3(0,0,0));
m_data->m_loadBody->setAngularVelocity(btVector3(0,0,0));
}
btRigidBody* ForkLiftPhysicsSetup::localCreateRigidBody(btScalar mass, const btTransform& startTransform, btCollisionShape* shape)
{
btAssert((!shape || shape->getShapeType() != INVALID_SHAPE_PROXYTYPE));
//rigidbody is dynamic if and only if mass is non zero, otherwise static
bool isDynamic = (mass != 0.f);
btVector3 localInertia(0,0,0);
if (isDynamic)
shape->calculateLocalInertia(mass,localInertia);
//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
//#define USE_MOTIONSTATE 1
#ifdef USE_MOTIONSTATE
btDefaultMotionState* myMotionState = new btDefaultMotionState(startTransform);
btRigidBody::btRigidBodyConstructionInfo cInfo(mass,myMotionState,shape,localInertia);
btRigidBody* body = new btRigidBody(cInfo);
body->setContactProcessingThreshold(BT_LARGE_FLOAT);//m_defaultContactProcessingThreshold);
#else
btRigidBody* body = new btRigidBody(mass,0,shape,localInertia);
body->setWorldTransform(startTransform);
#endif//
m_data->m_dynamicsWorld->addRigidBody(body);
return body;
}
void ForkLiftPhysicsSetup::exitPhysics()
{
}
void ForkLiftPhysicsSetup::stepSimulation(float deltaTime)
{
m_data->m_dynamicsWorld->stepSimulation(deltaTime);
}
void ForkLiftPhysicsSetup::debugDraw(int debugDrawFlags)
{
}
bool ForkLiftPhysicsSetup::pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld)
{
return false;
}
bool ForkLiftPhysicsSetup::movePickedBody(const btVector3& rayFromWorld, const btVector3& rayToWorld)
{
return false;
}
void ForkLiftPhysicsSetup::removePickingConstraint()
{
}
void ForkLiftPhysicsSetup::syncPhysicsToGraphics(GraphicsPhysicsBridge& gfxBridge)
{
gfxBridge.syncPhysicsToGraphics(m_data->m_dynamicsWorld);
//sync wheels
for (int i=0;i<m_data->m_vehicle->getNumWheels();i++)
{
//synchronize the wheels with the (interpolated) chassis worldtransform
m_data->m_vehicle->updateWheelTransform(i,true);
CommonRenderInterface* renderer = gfxBridge.getRenderInterface();
if (renderer)
{
btTransform tr = m_data->m_vehicle->getWheelInfo(i).m_worldTransform;
btVector3 pos=tr.getOrigin();
btQuaternion orn = tr.getRotation();
renderer->writeSingleInstanceTransformToCPU(pos,orn,m_data->m_wheelInstances[i]);
}
}
}
void ForkLiftPhysicsSetup::renderScene(GraphicsPhysicsBridge& gfxBridge)
{
gfxBridge.drawText3D("hi!",0,10,10,2);
}
void ForkLiftPhysicsSetup::lockLiftHinge()
{
}
void ForkLiftPhysicsSetup::lockForkSlider()
{
}

View File

@@ -0,0 +1,50 @@
#ifndef FORK_LIFT_PHYSICS_SETUP_H
#define FORK_LIFT_PHYSICS_SETUP_H
class btRigidBody;
class btCollisionShape;
class btBroadphaseInterface;
class btConstraintSolver;
class btCollisionDispatcher;
class btDefaultCollisionConfiguration;
class btDiscreteDynamicsWorld;
class btTransform;
class btVector3;
class btBoxShape;
#include "LinearMath/btVector3.h"
#include "LinearMath/btAlignedObjectArray.h"
#include "Bullet3AppSupport/CommonRigidBodySetup.h"
class ForkLiftPhysicsSetup : public CommonPhysicsSetup
{
protected:
struct ForkLiftInternalData* m_data;
public:
ForkLiftPhysicsSetup();
virtual ~ForkLiftPhysicsSetup();
virtual void initPhysics(GraphicsPhysicsBridge& gfxBridge);
virtual void exitPhysics();
virtual void stepSimulation(float deltaTime);
virtual void debugDraw(int debugDrawFlags);
virtual bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld);
virtual bool movePickedBody(const btVector3& rayFromWorld, const btVector3& rayToWorld);
virtual void removePickingConstraint();
virtual void syncPhysicsToGraphics(GraphicsPhysicsBridge& gfxBridge);
virtual void renderScene(GraphicsPhysicsBridge& gfxBridge);
void resetForklift();
void lockLiftHinge();
void lockForkSlider();
class btRigidBody* localCreateRigidBody(btScalar mass, const btTransform& startTrans, btCollisionShape* shape);
};
#endif //FORK_LIFT_PHYSICS_SETUP_H

View File

@@ -107,7 +107,7 @@ void GyroscopicDemo::initPhysics()
m_dynamicsWorld->addRigidBody(body);
if (gyro[i])
{
body->setFlags(BT_ENABLE_GYROPSCOPIC_FORCE);
body->setFlags(BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_BODY);
} else
{
body->setFlags(0);

View File

@@ -1,19 +1,17 @@
#include "GyroscopicSetup.h"
static int gyroflags[5] = {
static int gyroflags[4] = {
0,//none, no gyroscopic term
BT_ENABLE_GYROSCOPIC_FORCE_EXPLICIT,
BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_EWERT,
BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_CATTO,
BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_COOPER,
BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_WORLD,
BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_BODY
};
static const char* gyroNames[5] = {
static const char* gyroNames[4] = {
"No Coriolis",
"Explicit",
"Ewert",
"Catto",
"Cooper",
"Implicit (World)",
"Implicit (Body)"
};
@@ -25,16 +23,15 @@ void GyroscopicSetup::initPhysics(GraphicsPhysicsBridge& gfxBridge)
gfxBridge.createPhysicsDebugDrawer(m_dynamicsWorld);
btVector3 positions[5] = {
btVector3 positions[4] = {
btVector3( -10, 8,4),
btVector3( -5, 8,4),
btVector3( 0, 8,4),
btVector3( 5, 8,4),
btVector3( 10, 8,4),
};
for (int i = 0; i<5; i++)
for (int i = 0; i<4; i++)
{
btCylinderShapeZ* pin = new btCylinderShapeZ(btVector3(0.1,0.1, 0.2));
btBoxShape* box = new btBoxShape(btVector3(1,0.1,0.1));

View File

@@ -16,6 +16,7 @@
#include "../bullet2/RagdollDemo/RagdollDemo.h"
#include "../bullet2/LuaDemo/LuaPhysicsSetup.h"
#include "../bullet2/ChainDemo/ChainDemo.h"
#include "../../Demos/ForkLiftDemo/ForkLiftPhysicsSetup.h"
#include "../../Demos/CcdPhysicsDemo/CcdPhysicsSetup.h"
#include "../../Demos/GyroscopicDemo/GyroscopicSetup.h"
#include "../bullet2/ConstraintDemo/ConstraintPhysicsSetup.h"
@@ -57,6 +58,7 @@ MYCREATEFUNC2(LuaDemoCreateFunc,LuaPhysicsSetup);
MYCREATEFUNC(Serialize);
MYCREATEFUNC(CcdPhysics);
MYCREATEFUNC(Gyroscopic);
MYCREATEFUNC(ForkLiftPhysics);
MYCREATEFUNC(KinematicObject);
MYCREATEFUNC(ConstraintPhysics);
MYCREATEFUNC(Dof6Spring2);
@@ -96,6 +98,7 @@ static BulletDemoEntry allDemos[]=
{0,"API Demos", 0},
{1,"Raytracer",RaytracerPhysicsCreateFunc},
{1,"BasicDemo",BasicDemo::MyCreateFunc},
{1,"ForkLift",ForkLiftPhysicsCreateFunc},
{ 1, "CcdDemo", CcdPhysicsCreateFunc },
{ 1, "Gyroscopic", GyroscopicCreateFunc },
{ 1, "Kinematic", KinematicObjectCreateFunc },

View File

@@ -18,6 +18,8 @@ SET(App_AllBullet2Demos_SRCS
../../Demos/Raytracer/RaytracerSetup.h
../../Demos/GyroscopicDemo/GyroscopicSetup.cpp
../../Demos/GyroscopicDemo/GyroscopicSetup.h
../../Demos/ForkLiftDemo/ForkLiftPhysicsSetup.cpp
../../Demos/ForkLiftDemo/ForkLiftPhysicsSetup.h
../../Demos/SerializeDemo/SerializeSetup.cpp
../../Extras/Serialize/BulletFileLoader/bChunk.cpp
../../Extras/Serialize/BulletFileLoader/bDNA.cpp

View File

@@ -53,6 +53,8 @@
"../FiniteElementMethod/FiniteElementDemo.cpp",
"../../Demos/BasicDemo/BasicDemoPhysicsSetup.cpp",
"../../Demos/BasicDemo/BasicDemoPhysicsSetup.h",
"../../Demos/ForkLiftDemo/ForkLiftPhysicsSetup.cpp",
"../../Demos/ForkLiftDemo/ForkLiftPhysicsSetup.h",
"../../Demos/CcdPhysicsDemo/CcdPhysicsSetup.cpp",
"../../Demos/CcdPhysicsDemo/CcdPhysicsSetup.h",
"../../Demos/Raytracer/RaytracerSetup.cpp",

View File

@@ -30,6 +30,12 @@ struct MyGraphicsPhysicsBridge : public GraphicsPhysicsBridge
:m_glApp(glApp), m_debugDraw(0), m_curColor(0)
{
}
virtual struct CommonRenderInterface* getRenderInterface()
{
return m_glApp->m_renderer;
}
virtual void createRigidBodyGraphicsObject(btRigidBody* body, const btVector3& color)
{
createCollisionObjectGraphicsObject(body,color);
@@ -319,9 +325,10 @@ void Bullet2RigidBodyDemo::renderScene()
MyGraphicsPhysicsBridge glBridge(m_glApp);
m_physicsSetup->syncPhysicsToGraphics(glBridge);
m_glApp->m_renderer->renderScene();
m_physicsSetup->renderScene(glBridge);
}
void Bullet2RigidBodyDemo::physicsDebugDraw(int debugDrawFlags)

View File

@@ -48,6 +48,10 @@ struct GraphicsPhysicsBridge
return 0;
}
virtual struct CommonRenderInterface* getRenderInterface()
{
return 0;
}
virtual void setUpAxis(int axis)
{
}
@@ -77,6 +81,7 @@ public:
virtual void debugDraw(int debugDrawFlags)=0;
virtual void renderScene(GraphicsPhysicsBridge& gfxBridge){};
virtual bool pickBody(const btVector3& rayFromWorld, const btVector3& rayToWorld) = 0;
virtual bool movePickedBody(const btVector3& rayFromWorld, const btVector3& rayToWorld)=0;

View File

@@ -255,7 +255,7 @@ void SimpleOpenGL3App::drawText3D( const char* txt, float worldPosX, float world
//float extraSpacing = 0.;
float startX = posX;
float startY = posY-g_DefaultLargeFont->m_CharHeight;
float startY = posY-g_DefaultLargeFont->m_CharHeight*size1;
while (txt[pos])
@@ -263,7 +263,7 @@ void SimpleOpenGL3App::drawText3D( const char* txt, float worldPosX, float world
int c = txt[pos];
//r.h = g_DefaultNormalFont->m_CharHeight;
//r.w = g_DefaultNormalFont->m_CharWidth[c]+extraSpacing;
float endX = startX+g_DefaultLargeFont->m_CharWidth[c];
float endX = startX+g_DefaultLargeFont->m_CharWidth[c]*size1;
float endY = posY;

View File

@@ -1271,22 +1271,17 @@ btScalar btSequentialImpulseConstraintSolver::solveGroupCacheFriendlySetup(btCol
btVector3 gyroForce (0,0,0);
if (body->getFlags()&BT_ENABLE_GYROSCOPIC_FORCE_EXPLICIT)
{
gyroForce = body->computeGyroscopicForce(infoGlobal.m_maxGyroscopicForce);
gyroForce = body->computeGyroscopicForceExplicit(infoGlobal.m_maxGyroscopicForce);
solverBody.m_externalTorqueImpulse -= gyroForce*body->getInvInertiaTensorWorld()*infoGlobal.m_timeStep;
}
if (body->getFlags()&BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_EWERT)
if (body->getFlags()&BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_WORLD)
{
gyroForce = body->computeGyroscopicImpulseImplicit_Ewert(infoGlobal.m_timeStep);
gyroForce = body->computeGyroscopicImpulseImplicit_World(infoGlobal.m_timeStep);
solverBody.m_externalTorqueImpulse += gyroForce;
}
if (body->getFlags()&BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_COOPER)
if (body->getFlags()&BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_BODY)
{
gyroForce = body->computeGyroscopicImpulseImplicit_Cooper(infoGlobal.m_timeStep);
solverBody.m_externalTorqueImpulse += gyroForce;
}
if (body->getFlags()&BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_CATTO)
{
gyroForce = body->computeGyroscopicImpulseImplicit_Catto(infoGlobal.m_timeStep);
gyroForce = body->computeGyroscopicImpulseImplicit_Body(infoGlobal.m_timeStep);
solverBody.m_externalTorqueImpulse += gyroForce;
}

View File

@@ -87,7 +87,7 @@ void btRigidBody::setupRigidBody(const btRigidBody::btRigidBodyConstructionInfo&
setMassProps(constructionInfo.m_mass, constructionInfo.m_localInertia);
updateInertiaTensor();
m_rigidbodyFlags = BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_EWERT;
m_rigidbodyFlags = BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_BODY;
m_deltaLinearVelocity.setZero();
@@ -289,7 +289,7 @@ inline btMatrix3x3 evalEulerEqnDeriv(const btVector3& w1, const btVector3& w0, c
return dfw1;
}
btVector3 btRigidBody::computeGyroscopicForce(btScalar maxGyroscopicForce) const
btVector3 btRigidBody::computeGyroscopicForceExplicit(btScalar maxGyroscopicForce) const
{
btVector3 inertiaLocal = getLocalInertia();
btMatrix3x3 inertiaTensorWorld = getWorldTransform().getBasis().scaled(inertiaLocal) * getWorldTransform().getBasis().transpose();
@@ -311,7 +311,7 @@ void btSetCrossMatrixMinus(btMatrix3x3& res, const btVector3& a)
+a_1, -a_0, 0);
}
btVector3 btRigidBody::computeGyroscopicImpulseImplicit_Catto(btScalar step) const
btVector3 btRigidBody::computeGyroscopicImpulseImplicit_Body(btScalar step) const
{
btVector3 idl = getLocalInertia();
btVector3 omega1 = getAngularVelocity();
@@ -338,8 +338,9 @@ btVector3 btRigidBody::computeGyroscopicImpulseImplicit_Catto(btScalar step) con
// Jacobian
btMatrix3x3 J = Ib + (skew0*Ib - skew1)*step;
btMatrix3x3 Jinv = J.inverse();
btVector3 omega_div = Jinv*f;
// btMatrix3x3 Jinv = J.inverse();
// btVector3 omega_div = Jinv*f;
btVector3 omega_div = J.solve33(f);
// Single Newton-Raphson update
omegab = omegab - omega_div;//Solve33(J, f);
@@ -351,94 +352,7 @@ btVector3 btRigidBody::computeGyroscopicImpulseImplicit_Catto(btScalar step) con
btVector3 btRigidBody::computeGyroscopicImpulseImplicit_Cooper(btScalar step) const
{
#if 0
dReal h = callContext->m_stepperCallContext->m_stepSize; // Step size
dVector3 L; // Compute angular momentum
dMultiply0_331(L, I, b->avel);
#endif
btVector3 inertiaLocal = getLocalInertia();
btMatrix3x3 inertiaTensorWorld = getWorldTransform().getBasis().scaled(inertiaLocal) * getWorldTransform().getBasis().transpose();
btVector3 L = inertiaTensorWorld*getAngularVelocity();
btMatrix3x3 Itild(0, 0, 0, 0, 0, 0, 0, 0, 0);
#if 0
for (int ii = 0; ii<12; ++ii) {
Itild[ii] = Itild[ii] * h + I[ii];
}
#endif
btSetCrossMatrixMinus(Itild, L*step);
Itild += inertiaTensorWorld;
#if 0
// Compute a new effective 'inertia tensor'
// for the implicit step: the cross-product
// matrix of the angular momentum plus the
// old tensor scaled by the timestep.
// Itild may not be symmetric pos-definite,
// but we can still use it to compute implicit
// gyroscopic torques.
dMatrix3 Itild = { 0 };
dSetCrossMatrixMinus(Itild, L, 4);
for (int ii = 0; ii<12; ++ii) {
Itild[ii] = Itild[ii] * h + I[ii];
}
#endif
L *= step;
//Itild may not be symmetric pos-definite
btMatrix3x3 itInv = Itild.inverse();
Itild = inertiaTensorWorld * itInv;
btMatrix3x3 ident(1,0,0,0,1,0,0,0,1);
Itild -= ident;
#if 0
// Scale momentum by inverse time to get
// a sort of "torque"
dScaleVector3(L, dRecip(h));
// Invert the pseudo-tensor
dMatrix3 itInv;
// This is a closed-form inversion.
// It's probably not numerically stable
// when dealing with small masses with
// a large asymmetry.
// An LU decomposition might be better.
if (dInvertMatrix3(itInv, Itild) != 0) {
// "Divide" the original tensor
// by the pseudo-tensor (on the right)
dMultiply0_333(Itild, I, itInv);
// Subtract an identity matrix
Itild[0] -= 1; Itild[5] -= 1; Itild[10] -= 1;
// This new inertia matrix rotates the
// momentum to get a new set of torques
// that will work correctly when applied
// to the old inertia matrix as explicit
// torques with a semi-implicit update
// step.
dVector3 tau0;
dMultiply0_331(tau0, Itild, L);
// Add the gyro torques to the torque
// accumulator
for (int ii = 0; ii<3; ++ii) {
b->tacc[ii] += tau0[ii];
}
#endif
btVector3 tau0 = Itild * L;
// printf("tau0 = %f,%f,%f\n",tau0.x(),tau0.y(),tau0.z());
return tau0;
}
btVector3 btRigidBody::computeGyroscopicImpulseImplicit_Ewert(btScalar step) const
btVector3 btRigidBody::computeGyroscopicImpulseImplicit_World(btScalar step) const
{
// use full newton-euler equations. common practice to drop the wxIw term. want it for better tumbling behavior.
// calculate using implicit euler step so it's stable.
@@ -462,10 +376,10 @@ btVector3 btRigidBody::computeGyroscopicImpulseImplicit_Ewert(btScalar step) con
const btVector3 fw = evalEulerEqn(w1, w0, btVector3(0, 0, 0), step, I);
const btMatrix3x3 dfw = evalEulerEqnDeriv(w1, w0, step, I);
const btMatrix3x3 dfw_inv = dfw.inverse();
btVector3 dw;
dw = dfw_inv*fw;
dw = dfw.solve33(fw);
//const btMatrix3x3 dfw_inv = dfw.inverse();
//dw = dfw_inv*fw;
w1 -= dw;
}

View File

@@ -42,11 +42,12 @@ enum btRigidBodyFlags
{
BT_DISABLE_WORLD_GRAVITY = 1,
///BT_ENABLE_GYROPSCOPIC_FORCE flags is enabled by default in Bullet 2.83 and onwards.
///and it BT_ENABLE_GYROPSCOPIC_FORCE becomes equivalent to BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_BODY
///See Demos/GyroscopicDemo and computeGyroscopicImpulseImplicit
BT_ENABLE_GYROSCOPIC_FORCE_EXPLICIT = 2,
BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_COOPER=4,
BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_EWERT=8,
BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_CATTO=16,
BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_WORLD=4,
BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_BODY=8,
BT_ENABLE_GYROPSCOPIC_FORCE = BT_ENABLE_GYROSCOPIC_FORCE_IMPLICIT_BODY,
};
@@ -534,11 +535,14 @@ public:
btVector3 computeGyroscopicImpulseImplicit_Ewert(btScalar dt) const;
btVector3 computeGyroscopicImpulseImplicit_Cooper(btScalar step) const;
btVector3 computeGyroscopicImpulseImplicit_Catto(btScalar step) const;
///perform implicit force computation in world space
btVector3 computeGyroscopicImpulseImplicit_World(btScalar dt) const;
btVector3 computeGyroscopicForce(btScalar maxGyroscopicForce) const;//explicit version is best avoided, it gains energy
///perform implicit force computation in body space (inertial frame)
btVector3 computeGyroscopicImpulseImplicit_Body(btScalar step) const;
///explicit version is best avoided, it gains energy
btVector3 computeGyroscopicForceExplicit(btScalar maxGyroscopicForce) const;
btVector3 getLocalInertia() const;
///////////////////////////////////////////////

View File

@@ -610,6 +610,27 @@ public:
/**@brief Return the inverse of the matrix */
btMatrix3x3 inverse() const;
/// Solve A * x = b, where b is a column vector. This is more efficient
/// than computing the inverse in one-shot cases.
///Solve33 is from Box2d, thanks to Erin Catto,
btVector3 solve33(const btVector3& b) const
{
btVector3 col1 = getColumn(0);
btVector3 col2 = getColumn(1);
btVector3 col3 = getColumn(2);
btScalar det = btDot(col1, btCross(col2, col3));
if (btFabs(det)>SIMD_EPSILON)
{
det = 1.0f / det;
}
btVector3 x;
x[0] = det * btDot(b, btCross(col2, col3));
x[1] = det * btDot(col1, btCross(b, col3));
x[2] = det * btDot(col1, btCross(col2, b));
return x;
}
btMatrix3x3 transposeTimes(const btMatrix3x3& m) const;
btMatrix3x3 timesTranspose(const btMatrix3x3& m) const;