diff --git a/examples/BasicDemo/BasicExample.cpp b/examples/BasicDemo/BasicExample.cpp index 031a5e40f..1273371db 100644 --- a/examples/BasicDemo/BasicExample.cpp +++ b/examples/BasicDemo/BasicExample.cpp @@ -1,3 +1,17 @@ +/* +Bullet Continuous Collision Detection and Physics Library +Copyright (c) 2015 Google Inc. http://bulletphysics.org + +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +*/ diff --git a/examples/BasicDemo/BasicExample.h b/examples/BasicDemo/BasicExample.h index 87635d909..c2c02b10c 100644 --- a/examples/BasicDemo/BasicExample.h +++ b/examples/BasicDemo/BasicExample.h @@ -1,3 +1,18 @@ +/* +Bullet Continuous Collision Detection and Physics Library +Copyright (c) 2015 Google Inc. http://bulletphysics.org + +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +*/ + #ifndef BASIC_EXAMPLE_H #define BASIC_EXAMPLE_H diff --git a/examples/Constraints/ConstraintDemo.cpp b/examples/Constraints/ConstraintDemo.cpp new file mode 100644 index 000000000..19a6e76ed --- /dev/null +++ b/examples/Constraints/ConstraintDemo.cpp @@ -0,0 +1,876 @@ +/* +Bullet Continuous Collision Detection and Physics Library +Copyright (c) 2003-2015 Erwin Coumans http://continuousphysics.com/Bullet/ + +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +*/ + + + +#include "ConstraintDemo.h" + +#include "btBulletDynamicsCommon.h" +#include "LinearMath/btIDebugDraw.h" + +#include //printf debugging + + +#include "../CommonInterfaces/CommonRigidBodyBase.h" + + + + + +///AllConstraintDemo shows how to create a constraint, like Hinge or btGenericD6constraint +class AllConstraintDemo : public CommonRigidBodyBase +{ + //keep track of variables to delete memory at the end + + void setupEmptyDynamicsWorld(); + + + public: + + AllConstraintDemo(struct GUIHelperInterface* helper); + + virtual ~AllConstraintDemo(); + + void initPhysics(); + + void exitPhysics(); + + + + virtual void keyboardCallback(unsigned char key, int x, int y); + + // for cone-twist motor driving + float m_Time; + class btConeTwistConstraint* m_ctc; + +}; + + + +const int numObjects = 3; + +#define ENABLE_ALL_DEMOS 1 + +#define CUBE_HALF_EXTENTS 1.f + +#define SIMD_PI_2 ((SIMD_PI)*0.5f) +#define SIMD_PI_4 ((SIMD_PI)*0.25f) + + + + +btTransform sliderTransform; +btVector3 lowerSliderLimit = btVector3(-10,0,0); +btVector3 hiSliderLimit = btVector3(10,0,0); + +btRigidBody* d6body0 =0; + +btHingeConstraint* spDoorHinge = NULL; +btHingeConstraint* spHingeDynAB = NULL; +btGeneric6DofConstraint* spSlider6Dof = NULL; + +static bool s_bTestConeTwistMotor = false; + + + + + +void AllConstraintDemo::setupEmptyDynamicsWorld() +{ + m_collisionConfiguration = new btDefaultCollisionConfiguration(); + m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration); + m_broadphase = new btDbvtBroadphase(); + m_solver = new btSequentialImpulseConstraintSolver(); + m_dynamicsWorld = new btDiscreteDynamicsWorld(m_dispatcher,m_broadphase,m_solver,m_collisionConfiguration); + +} + + +void AllConstraintDemo::initPhysics() +{ + m_Time = 0; + + setupEmptyDynamicsWorld(); + + m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); + + //btCollisionShape* groundShape = new btBoxShape(btVector3(btScalar(50.),btScalar(40.),btScalar(50.))); + btCollisionShape* groundShape = new btStaticPlaneShape(btVector3(0,1,0),40); + + m_collisionShapes.push_back(groundShape); + btTransform groundTransform; + groundTransform.setIdentity(); + groundTransform.setOrigin(btVector3(0,-56,0)); + btRigidBody* groundBody; + groundBody= createRigidBody(0, groundTransform, groundShape); + + + + btCollisionShape* shape = new btBoxShape(btVector3(CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS)); + m_collisionShapes.push_back(shape); + btTransform trans; + trans.setIdentity(); + trans.setOrigin(btVector3(0,20,0)); + + float mass = 1.f; + +#if ENABLE_ALL_DEMOS +///gear constraint demo + +#define THETA SIMD_PI/4.f +#define L_1 (2 - tan(THETA)) +#define L_2 (1 / cos(THETA)) +#define RATIO L_2 / L_1 + + btRigidBody* bodyA=0; + btRigidBody* bodyB=0; + + { + btCollisionShape* cylA = new btCylinderShape(btVector3(0.2,0.25,0.2)); + btCollisionShape* cylB = new btCylinderShape(btVector3(L_1,0.025,L_1)); + btCompoundShape* cyl0 = new btCompoundShape(); + cyl0->addChildShape(btTransform::getIdentity(),cylA); + cyl0->addChildShape(btTransform::getIdentity(),cylB); + + btScalar mass = 6.28; + btVector3 localInertia; + cyl0->calculateLocalInertia(mass,localInertia); + btRigidBody::btRigidBodyConstructionInfo ci(mass,0,cyl0,localInertia); + ci.m_startWorldTransform.setOrigin(btVector3(-8,1,-8)); + + btRigidBody* body = new btRigidBody(ci);//1,0,cyl0,localInertia); + m_dynamicsWorld->addRigidBody(body); + body->setLinearFactor(btVector3(0,0,0)); + body->setAngularFactor(btVector3(0,1,0)); + bodyA = body; + } + + { + btCollisionShape* cylA = new btCylinderShape(btVector3(0.2,0.26,0.2)); + btCollisionShape* cylB = new btCylinderShape(btVector3(L_2,0.025,L_2)); + btCompoundShape* cyl0 = new btCompoundShape(); + cyl0->addChildShape(btTransform::getIdentity(),cylA); + cyl0->addChildShape(btTransform::getIdentity(),cylB); + + btScalar mass = 6.28; + btVector3 localInertia; + cyl0->calculateLocalInertia(mass,localInertia); + btRigidBody::btRigidBodyConstructionInfo ci(mass,0,cyl0,localInertia); + ci.m_startWorldTransform.setOrigin(btVector3(-10,2,-8)); + + + btQuaternion orn(btVector3(0,0,1),-THETA); + ci.m_startWorldTransform.setRotation(orn); + + btRigidBody* body = new btRigidBody(ci);//1,0,cyl0,localInertia); + body->setLinearFactor(btVector3(0,0,0)); + btHingeConstraint* hinge = new btHingeConstraint(*body,btVector3(0,0,0),btVector3(0,1,0),true); + m_dynamicsWorld->addConstraint(hinge); + bodyB= body; + body->setAngularVelocity(btVector3(0,3,0)); + + m_dynamicsWorld->addRigidBody(body); + } + + btVector3 axisA(0,1,0); + btVector3 axisB(0,1,0); + btQuaternion orn(btVector3(0,0,1),-THETA); + btMatrix3x3 mat(orn); + axisB = mat.getRow(1); + + btGearConstraint* gear = new btGearConstraint(*bodyA,*bodyB, axisA,axisB,RATIO); + m_dynamicsWorld->addConstraint(gear,true); + + +#endif + + +#if ENABLE_ALL_DEMOS + //point to point constraint with a breaking threshold + { + trans.setIdentity(); + trans.setOrigin(btVector3(1,30,-5)); + createRigidBody( mass,trans,shape); + trans.setOrigin(btVector3(0,0,-5)); + + btRigidBody* body0 = createRigidBody( mass,trans,shape); + trans.setOrigin(btVector3(2*CUBE_HALF_EXTENTS,20,0)); + mass = 1.f; + // btRigidBody* body1 = 0;//createRigidBody( mass,trans,shape); + btVector3 pivotInA(CUBE_HALF_EXTENTS,CUBE_HALF_EXTENTS,0); + btTypedConstraint* p2p = new btPoint2PointConstraint(*body0,pivotInA); + m_dynamicsWorld->addConstraint(p2p); + p2p ->setBreakingImpulseThreshold(10.2); + p2p->setDbgDrawSize(btScalar(5.f)); + } +#endif + + + +#if ENABLE_ALL_DEMOS + //point to point constraint (ball socket) + { + btRigidBody* body0 = createRigidBody( mass,trans,shape); + trans.setOrigin(btVector3(2*CUBE_HALF_EXTENTS,20,0)); + + mass = 1.f; +// btRigidBody* body1 = 0;//createRigidBody( mass,trans,shape); +// btRigidBody* body1 = createRigidBody( 0.0,trans,0); + //body1->setActivationState(DISABLE_DEACTIVATION); + //body1->setDamping(0.3,0.3); + + btVector3 pivotInA(CUBE_HALF_EXTENTS,-CUBE_HALF_EXTENTS,-CUBE_HALF_EXTENTS); + btVector3 axisInA(0,0,1); + + // btVector3 pivotInB = body1 ? body1->getCenterOfMassTransform().inverse()(body0->getCenterOfMassTransform()(pivotInA)) : pivotInA; +// btVector3 axisInB = body1? +// (body1->getCenterOfMassTransform().getBasis().inverse()*(body1->getCenterOfMassTransform().getBasis() * axisInA)) : + body0->getCenterOfMassTransform().getBasis() * axisInA; + +#define P2P +#ifdef P2P + btTypedConstraint* p2p = new btPoint2PointConstraint(*body0,pivotInA); + //btTypedConstraint* p2p = new btPoint2PointConstraint(*body0,*body1,pivotInA,pivotInB); + //btTypedConstraint* hinge = new btHingeConstraint(*body0,*body1,pivotInA,pivotInB,axisInA,axisInB); + m_dynamicsWorld->addConstraint(p2p); + p2p->setDbgDrawSize(btScalar(5.f)); +#else + btHingeConstraint* hinge = new btHingeConstraint(*body0,pivotInA,axisInA); + + //use zero targetVelocity and a small maxMotorImpulse to simulate joint friction + //float targetVelocity = 0.f; + //float maxMotorImpulse = 0.01; + float targetVelocity = 1.f; + float maxMotorImpulse = 1.0f; + hinge->enableAngularMotor(true,targetVelocity,maxMotorImpulse); + m_dynamicsWorld->addConstraint(hinge); + hinge->setDbgDrawSize(btScalar(5.f)); +#endif //P2P + + + + + } +#endif + + +#if ENABLE_ALL_DEMOS + { + btTransform trans; + trans.setIdentity(); + btVector3 worldPos(-20,0,30); + trans.setOrigin(worldPos); + + btTransform frameInA, frameInB; + frameInA = btTransform::getIdentity(); + frameInB = btTransform::getIdentity(); + + btRigidBody* pRbA1 = createRigidBody(mass, trans, shape); +// btRigidBody* pRbA1 = createRigidBody(0.f, trans, shape); + pRbA1->setActivationState(DISABLE_DEACTIVATION); + + // add dynamic rigid body B1 + worldPos.setValue(-30,0,30); + trans.setOrigin(worldPos); + btRigidBody* pRbB1 = createRigidBody(mass, trans, shape); +// btRigidBody* pRbB1 = createRigidBody(0.f, trans, shape); + pRbB1->setActivationState(DISABLE_DEACTIVATION); + + // create slider constraint between A1 and B1 and add it to world + + btSliderConstraint* spSlider1 = new btSliderConstraint(*pRbA1, *pRbB1, frameInA, frameInB, true); +// spSlider1 = new btSliderConstraint(*pRbA1, *pRbB1, frameInA, frameInB, false); + spSlider1->setLowerLinLimit(-15.0F); + spSlider1->setUpperLinLimit(-5.0F); +// spSlider1->setLowerLinLimit(5.0F); +// spSlider1->setUpperLinLimit(15.0F); +// spSlider1->setLowerLinLimit(-10.0F); +// spSlider1->setUpperLinLimit(-10.0F); + + spSlider1->setLowerAngLimit(-SIMD_PI / 3.0F); + spSlider1->setUpperAngLimit( SIMD_PI / 3.0F); + + + m_dynamicsWorld->addConstraint(spSlider1, true); + spSlider1->setDbgDrawSize(btScalar(5.f)); + } +#endif + +#if ENABLE_ALL_DEMOS + //create a slider, using the generic D6 constraint + { + mass = 1.f; + btVector3 sliderWorldPos(0,10,0); + btVector3 sliderAxis(1,0,0); + btScalar angle=0.f;//SIMD_RADS_PER_DEG * 10.f; + btMatrix3x3 sliderOrientation(btQuaternion(sliderAxis ,angle)); + trans.setIdentity(); + trans.setOrigin(sliderWorldPos); + //trans.setBasis(sliderOrientation); + sliderTransform = trans; + + d6body0 = createRigidBody( mass,trans,shape); + d6body0->setActivationState(DISABLE_DEACTIVATION); + btRigidBody* fixedBody1 = createRigidBody(0,trans,0); + m_dynamicsWorld->addRigidBody(fixedBody1); + + btTransform frameInA, frameInB; + frameInA = btTransform::getIdentity(); + frameInB = btTransform::getIdentity(); + frameInA.setOrigin(btVector3(0., 5., 0.)); + frameInB.setOrigin(btVector3(0., 5., 0.)); + +// bool useLinearReferenceFrameA = false;//use fixed frame B for linear llimits + bool useLinearReferenceFrameA = true;//use fixed frame A for linear llimits + spSlider6Dof = new btGeneric6DofConstraint(*fixedBody1, *d6body0,frameInA,frameInB,useLinearReferenceFrameA); + spSlider6Dof->setLinearLowerLimit(lowerSliderLimit); + spSlider6Dof->setLinearUpperLimit(hiSliderLimit); + + //range should be small, otherwise singularities will 'explode' the constraint +// spSlider6Dof->setAngularLowerLimit(btVector3(-1.5,0,0)); +// spSlider6Dof->setAngularUpperLimit(btVector3(1.5,0,0)); +// spSlider6Dof->setAngularLowerLimit(btVector3(0,0,0)); +// spSlider6Dof->setAngularUpperLimit(btVector3(0,0,0)); + spSlider6Dof->setAngularLowerLimit(btVector3(-SIMD_PI,0,0)); + spSlider6Dof->setAngularUpperLimit(btVector3(1.5,0,0)); + + spSlider6Dof->getTranslationalLimitMotor()->m_enableMotor[0] = true; + spSlider6Dof->getTranslationalLimitMotor()->m_targetVelocity[0] = -5.0f; + spSlider6Dof->getTranslationalLimitMotor()->m_maxMotorForce[0] = 0.1f; + + + m_dynamicsWorld->addConstraint(spSlider6Dof); + spSlider6Dof->setDbgDrawSize(btScalar(5.f)); + + } +#endif +#if ENABLE_ALL_DEMOS + { // create a door using hinge constraint attached to the world + btCollisionShape* pDoorShape = new btBoxShape(btVector3(2.0f, 5.0f, 0.2f)); + m_collisionShapes.push_back(pDoorShape); + btTransform doorTrans; + doorTrans.setIdentity(); + doorTrans.setOrigin(btVector3(-5.0f, -2.0f, 0.0f)); + btRigidBody* pDoorBody = createRigidBody( 1.0, doorTrans, pDoorShape); + pDoorBody->setActivationState(DISABLE_DEACTIVATION); + const btVector3 btPivotA(10.f + 2.1f, -2.0f, 0.0f ); // right next to the door slightly outside + btVector3 btAxisA( 0.0f, 1.0f, 0.0f ); // pointing upwards, aka Y-axis + + spDoorHinge = new btHingeConstraint( *pDoorBody, btPivotA, btAxisA ); + +// spDoorHinge->setLimit( 0.0f, SIMD_PI_2 ); + // test problem values +// spDoorHinge->setLimit( -SIMD_PI, SIMD_PI*0.8f); + +// spDoorHinge->setLimit( 1.f, -1.f); +// spDoorHinge->setLimit( -SIMD_PI*0.8f, SIMD_PI); +// spDoorHinge->setLimit( -SIMD_PI*0.8f, SIMD_PI, 0.9f, 0.3f, 0.0f); +// spDoorHinge->setLimit( -SIMD_PI*0.8f, SIMD_PI, 0.9f, 0.01f, 0.0f); // "sticky limits" + spDoorHinge->setLimit( -SIMD_PI * 0.25f, SIMD_PI * 0.25f ); +// spDoorHinge->setLimit( 0.0f, 0.0f ); + m_dynamicsWorld->addConstraint(spDoorHinge); + spDoorHinge->setDbgDrawSize(btScalar(5.f)); + + //doorTrans.setOrigin(btVector3(-5.0f, 2.0f, 0.0f)); + //btRigidBody* pDropBody = createRigidBody( 10.0, doorTrans, shape); + } +#endif +#if ENABLE_ALL_DEMOS + { // create a generic 6DOF constraint + + btTransform tr; + tr.setIdentity(); + tr.setOrigin(btVector3(btScalar(10.), btScalar(6.), btScalar(0.))); + tr.getBasis().setEulerZYX(0,0,0); +// btRigidBody* pBodyA = createRigidBody( mass, tr, shape); + btRigidBody* pBodyA = createRigidBody( 0.0, tr, shape); +// btRigidBody* pBodyA = createRigidBody( 0.0, tr, 0); + pBodyA->setActivationState(DISABLE_DEACTIVATION); + + tr.setIdentity(); + tr.setOrigin(btVector3(btScalar(0.), btScalar(6.), btScalar(0.))); + tr.getBasis().setEulerZYX(0,0,0); + btRigidBody* pBodyB = createRigidBody(mass, tr, shape); +// btRigidBody* pBodyB = createRigidBody(0.f, tr, shape); + pBodyB->setActivationState(DISABLE_DEACTIVATION); + + btTransform frameInA, frameInB; + frameInA = btTransform::getIdentity(); + frameInA.setOrigin(btVector3(btScalar(-5.), btScalar(0.), btScalar(0.))); + frameInB = btTransform::getIdentity(); + frameInB.setOrigin(btVector3(btScalar(5.), btScalar(0.), btScalar(0.))); + + btGeneric6DofConstraint* pGen6DOF = new btGeneric6DofConstraint(*pBodyA, *pBodyB, frameInA, frameInB, true); +// btGeneric6DofConstraint* pGen6DOF = new btGeneric6DofConstraint(*pBodyA, *pBodyB, frameInA, frameInB, false); + pGen6DOF->setLinearLowerLimit(btVector3(-10., -2., -1.)); + pGen6DOF->setLinearUpperLimit(btVector3(10., 2., 1.)); +// pGen6DOF->setLinearLowerLimit(btVector3(-10., 0., 0.)); +// pGen6DOF->setLinearUpperLimit(btVector3(10., 0., 0.)); +// pGen6DOF->setLinearLowerLimit(btVector3(0., 0., 0.)); +// pGen6DOF->setLinearUpperLimit(btVector3(0., 0., 0.)); + +// pGen6DOF->getTranslationalLimitMotor()->m_enableMotor[0] = true; +// pGen6DOF->getTranslationalLimitMotor()->m_targetVelocity[0] = 5.0f; +// pGen6DOF->getTranslationalLimitMotor()->m_maxMotorForce[0] = 0.1f; + + +// pGen6DOF->setAngularLowerLimit(btVector3(0., SIMD_HALF_PI*0.9, 0.)); +// pGen6DOF->setAngularUpperLimit(btVector3(0., -SIMD_HALF_PI*0.9, 0.)); +// pGen6DOF->setAngularLowerLimit(btVector3(0., 0., -SIMD_HALF_PI)); +// pGen6DOF->setAngularUpperLimit(btVector3(0., 0., SIMD_HALF_PI)); + + pGen6DOF->setAngularLowerLimit(btVector3(-SIMD_HALF_PI * 0.5f, -0.75, -SIMD_HALF_PI * 0.8f)); + pGen6DOF->setAngularUpperLimit(btVector3(SIMD_HALF_PI * 0.5f, 0.75, SIMD_HALF_PI * 0.8f)); +// pGen6DOF->setAngularLowerLimit(btVector3(0.f, -0.75, SIMD_HALF_PI * 0.8f)); +// pGen6DOF->setAngularUpperLimit(btVector3(0.f, 0.75, -SIMD_HALF_PI * 0.8f)); +// pGen6DOF->setAngularLowerLimit(btVector3(0.f, -SIMD_HALF_PI * 0.8f, SIMD_HALF_PI * 1.98f)); +// pGen6DOF->setAngularUpperLimit(btVector3(0.f, SIMD_HALF_PI * 0.8f, -SIMD_HALF_PI * 1.98f)); + + + +// pGen6DOF->setAngularLowerLimit(btVector3(-0.75,-0.5, -0.5)); +// pGen6DOF->setAngularUpperLimit(btVector3(0.75,0.5, 0.5)); +// pGen6DOF->setAngularLowerLimit(btVector3(-0.75,0., 0.)); +// pGen6DOF->setAngularUpperLimit(btVector3(0.75,0., 0.)); +// pGen6DOF->setAngularLowerLimit(btVector3(0., -0.7,0.)); +// pGen6DOF->setAngularUpperLimit(btVector3(0., 0.7, 0.)); +// pGen6DOF->setAngularLowerLimit(btVector3(-1., 0.,0.)); +// pGen6DOF->setAngularUpperLimit(btVector3(1., 0., 0.)); + + m_dynamicsWorld->addConstraint(pGen6DOF, true); + pGen6DOF->setDbgDrawSize(btScalar(5.f)); + } +#endif +#if ENABLE_ALL_DEMOS + { // create a ConeTwist constraint + + btTransform tr; + tr.setIdentity(); + tr.setOrigin(btVector3(btScalar(-10.), btScalar(5.), btScalar(0.))); + tr.getBasis().setEulerZYX(0,0,0); + btRigidBody* pBodyA = createRigidBody( 1.0, tr, shape); +// btRigidBody* pBodyA = createRigidBody( 0.0, tr, shape); + pBodyA->setActivationState(DISABLE_DEACTIVATION); + + tr.setIdentity(); + tr.setOrigin(btVector3(btScalar(-10.), btScalar(-5.), btScalar(0.))); + tr.getBasis().setEulerZYX(0,0,0); + btRigidBody* pBodyB = createRigidBody(0.0, tr, shape); +// btRigidBody* pBodyB = createRigidBody(1.0, tr, shape); + + btTransform frameInA, frameInB; + frameInA = btTransform::getIdentity(); + frameInA.getBasis().setEulerZYX(0, 0, SIMD_PI_2); + frameInA.setOrigin(btVector3(btScalar(0.), btScalar(-5.), btScalar(0.))); + frameInB = btTransform::getIdentity(); + frameInB.getBasis().setEulerZYX(0,0, SIMD_PI_2); + frameInB.setOrigin(btVector3(btScalar(0.), btScalar(5.), btScalar(0.))); + + m_ctc = new btConeTwistConstraint(*pBodyA, *pBodyB, frameInA, frameInB); +// m_ctc->setLimit(btScalar(SIMD_PI_4), btScalar(SIMD_PI_4), btScalar(SIMD_PI) * 0.8f); +// m_ctc->setLimit(btScalar(SIMD_PI_4*0.6f), btScalar(SIMD_PI_4), btScalar(SIMD_PI) * 0.8f, 1.0f); // soft limit == hard limit + m_ctc->setLimit(btScalar(SIMD_PI_4*0.6f), btScalar(SIMD_PI_4), btScalar(SIMD_PI) * 0.8f, 0.5f); + m_dynamicsWorld->addConstraint(m_ctc, true); + m_ctc->setDbgDrawSize(btScalar(5.f)); + // s_bTestConeTwistMotor = true; // use only with old solver for now + s_bTestConeTwistMotor = false; + } +#endif +#if ENABLE_ALL_DEMOS + { // Hinge connected to the world, with motor (to hinge motor with new and old constraint solver) + btTransform tr; + tr.setIdentity(); + tr.setOrigin(btVector3(btScalar(0.), btScalar(0.), btScalar(0.))); + btRigidBody* pBody = createRigidBody( 1.0, tr, shape); + pBody->setActivationState(DISABLE_DEACTIVATION); + const btVector3 btPivotA( 10.0f, 0.0f, 0.0f ); + btVector3 btAxisA( 0.0f, 0.0f, 1.0f ); + + btHingeConstraint* pHinge = new btHingeConstraint( *pBody, btPivotA, btAxisA ); +// pHinge->enableAngularMotor(true, -1.0, 0.165); // use for the old solver + pHinge->enableAngularMotor(true, -1.0f, 1.65f); // use for the new SIMD solver + m_dynamicsWorld->addConstraint(pHinge); + pHinge->setDbgDrawSize(btScalar(5.f)); + } +#endif + +#if ENABLE_ALL_DEMOS + { + // create a universal joint using generic 6DOF constraint + // create two rigid bodies + // static bodyA (parent) on top: + btTransform tr; + tr.setIdentity(); + tr.setOrigin(btVector3(btScalar(20.), btScalar(4.), btScalar(0.))); + btRigidBody* pBodyA = createRigidBody( 0.0, tr, shape); + pBodyA->setActivationState(DISABLE_DEACTIVATION); + // dynamic bodyB (child) below it : + tr.setIdentity(); + tr.setOrigin(btVector3(btScalar(20.), btScalar(0.), btScalar(0.))); + btRigidBody* pBodyB = createRigidBody(1.0, tr, shape); + pBodyB->setActivationState(DISABLE_DEACTIVATION); + // add some (arbitrary) data to build constraint frames + btVector3 parentAxis(1.f, 0.f, 0.f); + btVector3 childAxis(0.f, 0.f, 1.f); + btVector3 anchor(20.f, 2.f, 0.f); + + btUniversalConstraint* pUniv = new btUniversalConstraint(*pBodyA, *pBodyB, anchor, parentAxis, childAxis); + pUniv->setLowerLimit(-SIMD_HALF_PI * 0.5f, -SIMD_HALF_PI * 0.5f); + pUniv->setUpperLimit(SIMD_HALF_PI * 0.5f, SIMD_HALF_PI * 0.5f); + // add constraint to world + m_dynamicsWorld->addConstraint(pUniv, true); + // draw constraint frames and limits for debugging + pUniv->setDbgDrawSize(btScalar(5.f)); + } +#endif + +#if ENABLE_ALL_DEMOS + { // create a generic 6DOF constraint with springs + + btTransform tr; + tr.setIdentity(); + tr.setOrigin(btVector3(btScalar(-20.), btScalar(16.), btScalar(0.))); + tr.getBasis().setEulerZYX(0,0,0); + btRigidBody* pBodyA = createRigidBody( 0.0, tr, shape); + pBodyA->setActivationState(DISABLE_DEACTIVATION); + + tr.setIdentity(); + tr.setOrigin(btVector3(btScalar(-10.), btScalar(16.), btScalar(0.))); + tr.getBasis().setEulerZYX(0,0,0); + btRigidBody* pBodyB = createRigidBody(1.0, tr, shape); + pBodyB->setActivationState(DISABLE_DEACTIVATION); + + btTransform frameInA, frameInB; + frameInA = btTransform::getIdentity(); + frameInA.setOrigin(btVector3(btScalar(10.), btScalar(0.), btScalar(0.))); + frameInB = btTransform::getIdentity(); + frameInB.setOrigin(btVector3(btScalar(0.), btScalar(0.), btScalar(0.))); + + btGeneric6DofSpringConstraint* pGen6DOFSpring = new btGeneric6DofSpringConstraint(*pBodyA, *pBodyB, frameInA, frameInB, true); + pGen6DOFSpring->setLinearUpperLimit(btVector3(5., 0., 0.)); + pGen6DOFSpring->setLinearLowerLimit(btVector3(-5., 0., 0.)); + + pGen6DOFSpring->setAngularLowerLimit(btVector3(0.f, 0.f, -1.5f)); + pGen6DOFSpring->setAngularUpperLimit(btVector3(0.f, 0.f, 1.5f)); + + m_dynamicsWorld->addConstraint(pGen6DOFSpring, true); + pGen6DOFSpring->setDbgDrawSize(btScalar(5.f)); + + pGen6DOFSpring->enableSpring(0, true); + pGen6DOFSpring->setStiffness(0, 39.478f); + pGen6DOFSpring->setDamping(0, 0.5f); + pGen6DOFSpring->enableSpring(5, true); + pGen6DOFSpring->setStiffness(5, 39.478f); + pGen6DOFSpring->setDamping(0, 0.3f); + pGen6DOFSpring->setEquilibriumPoint(); + } +#endif +#if ENABLE_ALL_DEMOS + { + // create a Hinge2 joint + // create two rigid bodies + // static bodyA (parent) on top: + btTransform tr; + tr.setIdentity(); + tr.setOrigin(btVector3(btScalar(-20.), btScalar(4.), btScalar(0.))); + btRigidBody* pBodyA = createRigidBody( 0.0, tr, shape); + pBodyA->setActivationState(DISABLE_DEACTIVATION); + // dynamic bodyB (child) below it : + tr.setIdentity(); + tr.setOrigin(btVector3(btScalar(-20.), btScalar(0.), btScalar(0.))); + btRigidBody* pBodyB = createRigidBody(1.0, tr, shape); + pBodyB->setActivationState(DISABLE_DEACTIVATION); + // add some data to build constraint frames + btVector3 parentAxis(0.f, 1.f, 0.f); + btVector3 childAxis(1.f, 0.f, 0.f); + btVector3 anchor(-20.f, 0.f, 0.f); + btHinge2Constraint* pHinge2 = new btHinge2Constraint(*pBodyA, *pBodyB, anchor, parentAxis, childAxis); + pHinge2->setLowerLimit(-SIMD_HALF_PI * 0.5f); + pHinge2->setUpperLimit( SIMD_HALF_PI * 0.5f); + // add constraint to world + m_dynamicsWorld->addConstraint(pHinge2, true); + // draw constraint frames and limits for debugging + pHinge2->setDbgDrawSize(btScalar(5.f)); + } +#endif +#if ENABLE_ALL_DEMOS + { + // create a Hinge joint between two dynamic bodies + // create two rigid bodies + // static bodyA (parent) on top: + btTransform tr; + tr.setIdentity(); + tr.setOrigin(btVector3(btScalar(-20.), btScalar(-2.), btScalar(0.))); + btRigidBody* pBodyA = createRigidBody( 1.0f, tr, shape); + pBodyA->setActivationState(DISABLE_DEACTIVATION); + // dynamic bodyB: + tr.setIdentity(); + tr.setOrigin(btVector3(btScalar(-30.), btScalar(-2.), btScalar(0.))); + btRigidBody* pBodyB = createRigidBody(10.0, tr, shape); + pBodyB->setActivationState(DISABLE_DEACTIVATION); + // add some data to build constraint frames + btVector3 axisA(0.f, 1.f, 0.f); + btVector3 axisB(0.f, 1.f, 0.f); + btVector3 pivotA(-5.f, 0.f, 0.f); + btVector3 pivotB( 5.f, 0.f, 0.f); + spHingeDynAB = new btHingeConstraint(*pBodyA, *pBodyB, pivotA, pivotB, axisA, axisB); + spHingeDynAB->setLimit(-SIMD_HALF_PI * 0.5f, SIMD_HALF_PI * 0.5f); + // add constraint to world + m_dynamicsWorld->addConstraint(spHingeDynAB, true); + // draw constraint frames and limits for debugging + spHingeDynAB->setDbgDrawSize(btScalar(5.f)); + } +#endif + +#if ENABLE_ALL_DEMOS + { // 6DOF connected to the world, with motor + btTransform tr; + tr.setIdentity(); + tr.setOrigin(btVector3(btScalar(10.), btScalar(-15.), btScalar(0.))); + btRigidBody* pBody = createRigidBody( 1.0, tr, shape); + pBody->setActivationState(DISABLE_DEACTIVATION); + btTransform frameB; + frameB.setIdentity(); + btGeneric6DofConstraint* pGen6Dof = new btGeneric6DofConstraint( *pBody, frameB, false ); + m_dynamicsWorld->addConstraint(pGen6Dof); + pGen6Dof->setDbgDrawSize(btScalar(5.f)); + + pGen6Dof->setAngularLowerLimit(btVector3(0,0,0)); + pGen6Dof->setAngularUpperLimit(btVector3(0,0,0)); + pGen6Dof->setLinearLowerLimit(btVector3(-10., 0, 0)); + pGen6Dof->setLinearUpperLimit(btVector3(10., 0, 0)); + + pGen6Dof->getTranslationalLimitMotor()->m_enableMotor[0] = true; + pGen6Dof->getTranslationalLimitMotor()->m_targetVelocity[0] = 5.0f; + pGen6Dof->getTranslationalLimitMotor()->m_maxMotorForce[0] = 0.1f; + } +#endif + + m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); + + +} + +void AllConstraintDemo::exitPhysics() +{ + + int i; + + //removed/delete constraints + for (i=m_dynamicsWorld->getNumConstraints()-1; i>=0 ;i--) + { + btTypedConstraint* constraint = m_dynamicsWorld->getConstraint(i); + m_dynamicsWorld->removeConstraint(constraint); + delete constraint; + } + m_ctc = NULL; + + //remove the rigidbodies from the dynamics world and delete them + for (i=m_dynamicsWorld->getNumCollisionObjects()-1; i>=0 ;i--) + { + btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i]; + btRigidBody* body = btRigidBody::upcast(obj); + if (body && body->getMotionState()) + { + delete body->getMotionState(); + } + m_dynamicsWorld->removeCollisionObject( obj ); + delete obj; + } + + + + + //delete collision shapes + for (int j=0;jenableMotor(true); + m_ctc->setMotorTargetInConstraintSpace(q1); + } + + { + static bool once = true; + if ( m_dynamicsWorld->getDebugDrawer() && once) + { + m_dynamicsWorld->getDebugDrawer()->setDebugMode(btIDebugDraw::DBG_DrawConstraints+btIDebugDraw::DBG_DrawConstraintLimits); + once=false; + } + } + + + { + //during idle mode, just run 1 simulation step maximum + int maxSimSubSteps = m_idle ? 1 : 1; + if (m_idle) + dt = 1.0f/420.f; + + int numSimSteps = m_dynamicsWorld->stepSimulation(dt,maxSimSubSteps); + + //optional but useful: debug drawing + m_dynamicsWorld->debugDrawWorld(); + + bool verbose = false; + if (verbose) + { + if (!numSimSteps) + printf("Interpolated transforms\n"); + else + { + if (numSimSteps > maxSimSubSteps) + { + //detect dropping frames + printf("Dropped (%i) simulation steps out of %i\n",numSimSteps - maxSimSubSteps,numSimSteps); + } else + { + printf("Simulated (%i) steps\n",numSimSteps); + } + } + } + } + renderme(); + +// drawLimit(); + + glFlush(); + swapBuffers(); +} + + + + +void AllConstraintDemo::displayCallback(void) { + + glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + if (m_dynamicsWorld) + m_dynamicsWorld->debugDrawWorld(); + +// drawLimit(); + + renderme(); + + glFlush(); + swapBuffers(); +} +#endif + +void AllConstraintDemo::keyboardCallback(unsigned char key, int x, int y) +{ + (void)x; + (void)y; + switch (key) + { + case 'O' : + { + bool offectOnOff; + if(spDoorHinge) + { + offectOnOff = spDoorHinge->getUseFrameOffset(); + offectOnOff = !offectOnOff; + spDoorHinge->setUseFrameOffset(offectOnOff); + printf("DoorHinge %s frame offset\n", offectOnOff ? "uses" : "does not use"); + } + if(spHingeDynAB) + { + offectOnOff = spHingeDynAB->getUseFrameOffset(); + offectOnOff = !offectOnOff; + spHingeDynAB->setUseFrameOffset(offectOnOff); + printf("HingeDynAB %s frame offset\n", offectOnOff ? "uses" : "does not use"); + } + if(spSlider6Dof) + { + offectOnOff = spSlider6Dof->getUseFrameOffset(); + offectOnOff = !offectOnOff; + spSlider6Dof->setUseFrameOffset(offectOnOff); + printf("Slider6Dof %s frame offset\n", offectOnOff ? "uses" : "does not use"); + } + } + break; + default : + { + + } + break; + } +} + +class ExampleInterface* AllConstraintCreateFunc(struct PhysicsInterface* pint, struct GUIHelperInterface* helper, int option) +{ + return new AllConstraintDemo(helper); +} \ No newline at end of file diff --git a/examples/Constraints/ConstraintDemo.h b/examples/Constraints/ConstraintDemo.h new file mode 100644 index 000000000..864b4faad --- /dev/null +++ b/examples/Constraints/ConstraintDemo.h @@ -0,0 +1,22 @@ +/* +Bullet Continuous Collision Detection and Physics Library +Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ + +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +*/ +#ifndef ALL_CONSTRAINT_DEMO_H +#define ALL_CONSTRAINT_DEMO_H + +class ExampleInterface* AllConstraintCreateFunc(struct PhysicsInterface* pint, struct GUIHelperInterface* helper, int option); + + +#endif //ALL_CONSTRAINT_DEMO_H + diff --git a/examples/ExampleBrowser/ExampleEntries.cpp b/examples/ExampleBrowser/ExampleEntries.cpp index 1635f96f6..819f86e87 100644 --- a/examples/ExampleBrowser/ExampleEntries.cpp +++ b/examples/ExampleBrowser/ExampleEntries.cpp @@ -24,7 +24,8 @@ #include "../MultiBody/MultiBodyCustomURDFDemo.h" #include "../VoronoiFracture/VoronoiFractureDemo.h" #include "../SoftDemo/SoftDemo.h" - +#include "../Constraints/ConstraintDemo.h" +#include "../Vehicles/Hinge2Vehicle.h" struct ExampleEntry { @@ -59,9 +60,11 @@ static ExampleEntry gDefaultExamples[]= ExampleEntry(1,"Constraints","Use of a btHingeConstraint. You can adjust the first slider to change the target velocity, and the second slider to adjust the maximum impulse applied to reach the target velocity. Note that the hinge angle can reach beyond -360 and 360 degrees.", ConstraintCreateFunc), ExampleEntry(1,"6DofSpring2","Show the use of the btGeneric6DofSpring2Constraint.", Dof6Spring2CreateFunc), - ExampleEntry(1,"Voronoi Fracture", "Automatically create a compound rigid body using voronoi tesselation. Individual parts are modeled as rigid bodies using a btConvexHullShape.", - VoronoiFractureCreateFunc), + ExampleEntry(1,"Constraints","Show the use of the various constraints in Bullet.", + AllConstraintCreateFunc), + + ExampleEntry(0,"MultiBody"), ExampleEntry(1,"MultiDofCreateFunc","Create a basic btMultiBody.", MultiDofCreateFunc), ExampleEntry(1,"TestJointTorque","Apply a torque to a btMultiBody.", TestJointTorqueCreateFunc), @@ -122,6 +125,8 @@ static ExampleEntry gDefaultExamples[]= #endif + + ExampleEntry(0,"Importers"), ExampleEntry(1,"Wavefront Obj", "Import a Wavefront .obj file", ImportObjCreateFunc, 0), @@ -134,12 +139,18 @@ static ExampleEntry gDefaultExamples[]= ImportURDFCreateFunc, 1), ExampleEntry(0,"Vehicles"), - + ExampleEntry(1,"Hinge2 Vehicle", "A rigid body chassis with 4 rigid body wheels attached by a btHinge2Constraint",Hinge2VehicleCreateFunc), ExampleEntry(1,"ForkLift","Simulate a fork lift vehicle with a working fork lift that can be moved using the cursor keys. The wheels collision is simplified using ray tests." "There are currently some issues with the wheel rendering, the wheels rotate when picking up the object." "The demo implementation allows to choose various MLCP constraint solvers.", ForkLiftCreateFunc), + ExampleEntry(1,"Advanced"), + + ExampleEntry(1,"Voronoi Fracture", "Automatically create a compound rigid body using voronoi tesselation. Individual parts are modeled as rigid bodies using a btConvexHullShape.", + VoronoiFractureCreateFunc), + + ExampleEntry(0,"Rendering"), ExampleEntry(1,"Instanced Rendering", "Simple example of fast instanced rendering, only active when using OpenGL3+.",RenderInstancingCreateFunc), ExampleEntry(1,"CoordinateSystemDemo","Show the axis and positive rotation direction around the axis.", CoordinateSystemCreateFunc), diff --git a/examples/ExampleBrowser/premake4.lua b/examples/ExampleBrowser/premake4.lua index d913dd178..db8537ebd 100644 --- a/examples/ExampleBrowser/premake4.lua +++ b/examples/ExampleBrowser/premake4.lua @@ -31,6 +31,7 @@ "../VoronoiFracture/*", "../SoftDemo/*", "../Constraints/*", + "../Vehicles/*", "../MultiBody/MultiBodyCustomURDFDemo.cpp", "../MultiBody/MultiDofDemo.cpp", "../MultiBody/TestJointTorqueSetup.cpp", diff --git a/examples/SimpleOpenGL3/CMakeLists.txt b/examples/SimpleOpenGL3/CMakeLists.txt new file mode 100644 index 000000000..7931eee85 --- /dev/null +++ b/examples/SimpleOpenGL3/CMakeLists.txt @@ -0,0 +1,52 @@ + + +INCLUDE_DIRECTORIES( + ${BULLET_PHYSICS_SOURCE_DIR}/src + ${BULLET_PHYSICS_SOURCE_DIR}/btgui +) + + +SET(AppSimpleOpenGL3_SRCS + main.cpp + ${BULLET_PHYSICS_SOURCE_DIR}/build3/bullet.rc +) + +LINK_LIBRARIES( + gwen OpenGLWindow Bullet3Common ${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY} +) + +IF (WIN32) + SET(AppSimpleOpenGL3_SRCS ${AppSimpleOpenGL3_SRCS} ${AppSimpleOpenGL3_Common_SRCS}) + INCLUDE_DIRECTORIES( + ${BULLET_PHYSICS_SOURCE_DIR}/btgui/OpenGLWindow/GlewWindows + ) + ADD_DEFINITIONS(-DGLEW_STATIC) +ELSE(WIN32) + IF(APPLE) + find_library(COCOA NAMES Cocoa) + MESSAGE(${COCOA}) + link_libraries(${COCOA}) + ELSE(APPLE) + + INCLUDE_DIRECTORIES( + ${BULLET_PHYSICS_SOURCE_DIR}/btgui/OpenGLWindow/GlewWindows + ) + ADD_DEFINITIONS("-DGLEW_INIT_OPENGL11_FUNCTIONS=1") + ADD_DEFINITIONS("-DGLEW_STATIC") + ADD_DEFINITIONS("-DGLEW_DYNAMIC_LOAD_ALL_GLX_FUNCTIONS=1") + + LINK_LIBRARIES( X11 pthread dl Xext) + ENDIF(APPLE) +ENDIF(WIN32) + + +ADD_EXECUTABLE(AppSimpleOpenGL3 + ${AppSimpleOpenGL3_SRCS} +) + + +IF (INTERNAL_ADD_POSTFIX_EXECUTABLE_NAMES) + SET_TARGET_PROPERTIES(AppSimpleOpenGL3 PROPERTIES DEBUG_POSTFIX "_Debug") + SET_TARGET_PROPERTIES(AppSimpleOpenGL3 PROPERTIES MINSIZEREL_POSTFIX "_MinsizeRel") + SET_TARGET_PROPERTIES(AppSimpleOpenGL3 PROPERTIES RELWITHDEBINFO_POSTFIX "_RelWithDebugInfo") +ENDIF(INTERNAL_ADD_POSTFIX_EXECUTABLE_NAMES) diff --git a/examples/SimpleOpenGL3/main.cpp b/examples/SimpleOpenGL3/main.cpp new file mode 100644 index 000000000..3003a0978 --- /dev/null +++ b/examples/SimpleOpenGL3/main.cpp @@ -0,0 +1,57 @@ +#include "OpenGLWindow/SimpleOpenGL3App.h" +#include "Bullet3Common/b3Vector3.h" +#include "Bullet3Common/b3CommandLineArgs.h" +#include "assert.h" +#include +#include "OpenGLWindow/OpenGLInclude.h" + +char* gVideoFileName = 0; +char* gPngFileName = 0; + +int main(int argc, char* argv[]) +{ + b3CommandLineArgs myArgs(argc,argv); + + + SimpleOpenGL3App* app = new SimpleOpenGL3App("SimpleOpenGL3App",1024,768); + app->m_instancingRenderer->setCameraDistance(13); + app->m_instancingRenderer->setCameraPitch(0); + app->m_instancingRenderer->setCameraTargetPosition(b3MakeVector3(0,0,0)); + + assert(glGetError()==GL_NO_ERROR); + + myArgs.GetCmdLineArgument("mp4_file",gVideoFileName); + if (gVideoFileName) + app->dumpFramesToVideo(gVideoFileName); + + myArgs.GetCmdLineArgument("png_file",gPngFileName); + char fileName[1024]; + + do + { + static int frameCount = 0; + frameCount++; + if (gPngFileName) + { + printf("gPngFileName=%s\n",gPngFileName); + + sprintf(fileName,"%s%d.png",gPngFileName,frameCount++); + app->dumpNextFrameToPng(fileName); + } + + assert(glGetError()==GL_NO_ERROR); + app->m_instancingRenderer->init(); + app->m_instancingRenderer->updateCamera(); + + app->drawGrid(); + char bla[1024]; + sprintf(bla,"Simple test frame %d", frameCount); + + app->drawText(bla,10,10); + app->swapBuffer(); + } while (!app->m_window->requestedExit()); + + + delete app; + return 0; +} diff --git a/examples/SimpleOpenGL3/premake4.lua b/examples/SimpleOpenGL3/premake4.lua new file mode 100644 index 000000000..4bd8bbdda --- /dev/null +++ b/examples/SimpleOpenGL3/premake4.lua @@ -0,0 +1,28 @@ + + project "App_SimpleOpenGL3" + + language "C++" + + kind "ConsoleApp" + + includedirs { + ".", + "../../src", + ".." + } + + + links{ "OpenGL_Window","Bullet3Common"} + initOpenGL() + initGlew() + + files { + "*.cpp", + "*.h", + } + +if os.is("Linux") then initX11() end + +if os.is("MacOSX") then + links{"Cocoa.framework"} +end diff --git a/examples/Vehicles/Hinge2Vehicle.cpp b/examples/Vehicles/Hinge2Vehicle.cpp new file mode 100644 index 000000000..ff8e44434 --- /dev/null +++ b/examples/Vehicles/Hinge2Vehicle.cpp @@ -0,0 +1,1323 @@ +/* +Bullet Continuous Collision Detection and Physics Library +Copyright (c) 2003-2015 Erwin Coumans http://bulletphysics.org + +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +*/ + +///May 2015: implemented the wheels using the Hinge2Constraint +///todo: add controls for the motors etc. + +#include "Hinge2Vehicle.h" + +#include "btBulletDynamicsCommon.h" +#include "BulletCollision/CollisionShapes/btHeightfieldTerrainShape.h" + + +#include "BulletDynamics/MLCPSolvers/btDantzigSolver.h" +#include "BulletDynamics/MLCPSolvers/btSolveProjectedGaussSeidel.h" +#include "BulletDynamics/MLCPSolvers/btMLCPSolver.h" + +class btVehicleTuning; + +class btCollisionShape; + + +#include "BulletDynamics/ConstraintSolver/btHingeConstraint.h" +#include "BulletDynamics/ConstraintSolver/btSliderConstraint.h" + +#include "../CommonInterfaces/ExampleInterface.h" +#include "LinearMath/btAlignedObjectArray.h" +#include "btBulletCollisionCommon.h" +#include "../CommonInterfaces/CommonGUIHelperInterface.h" +#include "../CommonInterfaces/CommonRenderInterface.h" +#include "../CommonInterfaces/CommonWindowInterface.h" +#include "../CommonInterfaces/CommonGraphicsAppInterface.h" + +#include "../CommonInterfaces/CommonRigidBodyBase.h" + +class Hinge2Vehicle : public CommonRigidBodyBase +{ + public: + + /* extra stuff*/ + btVector3 m_cameraPosition; + + btRigidBody* m_carChassis; + btRigidBody* localCreateRigidBody(btScalar mass, const btTransform& worldTransform, btCollisionShape* colSape); + + GUIHelperInterface* m_guiHelper; + int m_wheelInstances[4]; + +//---------------------------- + btRigidBody* m_liftBody; + btVector3 m_liftStartPos; + btHingeConstraint* m_liftHinge; + + btRigidBody* m_forkBody; + btVector3 m_forkStartPos; + btSliderConstraint* m_forkSlider; + + btRigidBody* m_loadBody; + btVector3 m_loadStartPos; + + void lockLiftHinge(void); + void lockForkSlider(void); + + bool m_useDefaultCamera; +//---------------------------- + + + class btTriangleIndexVertexArray* m_indexVertexArrays; + + btVector3* m_vertices; + + + + btCollisionShape* m_wheelShape; + + float m_cameraHeight; + + float m_minCameraDistance; + float m_maxCameraDistance; + + + Hinge2Vehicle(struct GUIHelperInterface* helper); + + virtual ~Hinge2Vehicle(); + + virtual void stepSimulation(float deltaTime); + + virtual void resetForklift(); + + virtual void clientResetScene(); + + virtual void displayCallback(); + + ///a very basic camera following the vehicle + virtual void updateCamera(); + + virtual void specialKeyboard(int key, int x, int y); + + virtual void specialKeyboardUp(int key, int x, int y); + + + virtual bool keyboardCallback(int key, int state); + + virtual void renderScene(); + + virtual void physicsDebugDraw(int debugFlags); + + + void initPhysics(); + void exitPhysics(); + + /*static DemoApplication* Create() + { + Hinge2Vehicle* demo = new Hinge2Vehicle(); + demo->myinit(); + demo->initPhysics(); + return demo; + } + */ +}; + + +static btScalar maxMotorImpulse = 1400.f; + +//the sequential impulse solver has difficulties dealing with large mass ratios (differences), between loadMass and the fork parts +static btScalar loadMass = 350.f;// +//btScalar loadMass = 10.f;//this should work fine for the SI solver + + +#ifndef M_PI +#define M_PI 3.14159265358979323846 +#endif + +#ifndef M_PI_2 +#define M_PI_2 1.57079632679489661923 +#endif + +#ifndef M_PI_4 +#define M_PI_4 0.785398163397448309616 +#endif + +//#define LIFT_EPS 0.0000001f +// +// By default, Bullet Vehicle uses Y as up axis. +// You can override the up axis, for example Z-axis up. Enable this define to see how to: +//#define FORCE_ZAXIS_UP 1 +// + +#ifdef FORCE_ZAXIS_UP + static int rightIndex = 0; + static int upIndex = 2; + static int forwardIndex = 1; + static btVector3 wheelDirectionCS0(0,0,-1); + static btVector3 wheelAxleCS(1,0,0); +#else + static int rightIndex = 0; + static int upIndex = 1; + static int forwardIndex = 2; + static btVector3 wheelDirectionCS0(0,-1,0); + static btVector3 wheelAxleCS(-1,0,0); +#endif + +static bool useMCLPSolver = false;//true; + + +#include //printf debugging + + +#include "Hinge2Vehicle.h" + + +static const int maxProxies = 32766; +static const int maxOverlap = 65535; + +static float gEngineForce = 0.f; + +static float defaultBreakingForce = 10.f; +static float gBreakingForce = 100.f; + +static float maxEngineForce = 1000.f;//this should be engine/velocity dependent +static float maxBreakingForce = 100.f; + +static float gVehicleSteering = 0.f; +static float steeringIncrement = 0.04f; +static float steeringClamp = 0.3f; +static float wheelRadius = 0.5f; +static float wheelWidth = 0.4f; +static float wheelFriction = 1000;//BT_LARGE_FLOAT; +static float suspensionStiffness = 20.f; +static float suspensionDamping = 2.3f; +static float suspensionCompression = 4.4f; +static float rollInfluence = 0.1f;//1.0f; + + +static btScalar suspensionRestLength(0.6); + +#define CUBE_HALF_EXTENTS 1 + + + +//////////////////////////////////// + + + + +Hinge2Vehicle::Hinge2Vehicle(struct GUIHelperInterface* helper) +:CommonRigidBodyBase(helper), +m_guiHelper(helper), +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) +{ + helper->setUpAxis(1); + + m_wheelShape = 0; + m_cameraPosition = btVector3(30,30,30); + m_useDefaultCamera = false; +// setTexturing(true); +// setShadows(true); + +} + + +void Hinge2Vehicle::exitPhysics() +{ + //cleanup in the reverse order of creation/initialization + + //remove the rigidbodies from the dynamics world and delete them + int i; + for (i=m_dynamicsWorld->getNumCollisionObjects()-1; i>=0 ;i--) + { + btCollisionObject* obj = m_dynamicsWorld->getCollisionObjectArray()[i]; + btRigidBody* body = btRigidBody::upcast(obj); + if (body && body->getMotionState()) + { + + while (body->getNumConstraintRefs()) + { + btTypedConstraint* constraint = body->getConstraintRef(0); + m_dynamicsWorld->removeConstraint(constraint); + delete constraint; + } + delete body->getMotionState(); + m_dynamicsWorld->removeRigidBody(body); + } else + { + m_dynamicsWorld->removeCollisionObject( obj ); + } + delete obj; + } + + //delete collision shapes + for (int j=0;jgetSolverInfo().m_minimumSolverBatchSize = 1;//for direct solver it is better to have a small A matrix + } else + { + m_dynamicsWorld ->getSolverInfo().m_minimumSolverBatchSize = 128;//for direct solver, it is better to solve multiple objects together, small batches have high overhead + } + m_dynamicsWorld->getSolverInfo().m_numIterations = 100; + m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld); + +#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_collisionShapes.push_back(chassisShape); + + btCompoundShape* compound = new btCompoundShape(); + 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)); + + btScalar chassisMass = 800; + m_carChassis = localCreateRigidBody(chassisMass,tr,compound);//chassisShape); + //m_carChassis->setDamping(0.2,0.2); + + //m_wheelShape = new btCylinderShapeX(btVector3(wheelWidth,wheelRadius,wheelRadius)); + m_wheelShape = new btCylinderShapeX(btVector3(wheelWidth,wheelRadius,wheelRadius)); + + + 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}; + + btVector3 wheelPos[4] = { + btVector3(btScalar(-1.), btScalar(-0.25), btScalar(1.25)), + btVector3(btScalar(1.), btScalar(-0.25), btScalar(1.25)), + btVector3(btScalar(1.), btScalar(-0.25), btScalar(-1.25)), + btVector3(btScalar(-1.), btScalar(-0.25), btScalar(-1.25)) + }; + + + for (int i=0;i<4;i++) + { + // create a Hinge2 joint + // create two rigid bodies + // static bodyA (parent) on top: + + + btRigidBody* pBodyA = this->m_carChassis;//m_chassis;//createRigidBody( 0.0, tr, m_wheelShape); + pBodyA->setActivationState(DISABLE_DEACTIVATION); + // dynamic bodyB (child) below it : + btTransform tr; + tr.setIdentity(); + tr.setOrigin(wheelPos[i]); + + btRigidBody* pBodyB = createRigidBody(10.0, tr, m_wheelShape); + pBodyB->setFriction(1110); + pBodyB->setActivationState(DISABLE_DEACTIVATION); + // add some data to build constraint frames + btVector3 parentAxis(0.f, 1.f, 0.f); + btVector3 childAxis(1.f, 0.f, 0.f); + btVector3 anchor = tr.getOrigin();//(0.f, 0.f, 0.f); + btHinge2Constraint* pHinge2 = new btHinge2Constraint(*pBodyA, *pBodyB, anchor, parentAxis, childAxis); + + //m_guiHelper->get2dCanvasInterface(); + + + pHinge2->setLowerLimit(-SIMD_HALF_PI * 0.5f); + pHinge2->setUpperLimit( SIMD_HALF_PI * 0.5f); + // add constraint to world + m_dynamicsWorld->addConstraint(pHinge2, true); + // draw constraint frames and limits for debugging + { + int motorAxis = 3; + pHinge2->enableMotor(motorAxis,true); + pHinge2->setMaxMotorForce(motorAxis,1000); + pHinge2->setTargetVelocity(motorAxis,-1); + } + + { + int motorAxis = 5; + pHinge2->enableMotor(motorAxis,true); + pHinge2->setMaxMotorForce(motorAxis,1000); + pHinge2->setTargetVelocity(motorAxis,0); + } + + pHinge2->setDbgDrawSize(btScalar(5.f)); + } + + + { + btCollisionShape* liftShape = new btBoxShape(btVector3(0.5f,2.0f,0.05f)); + m_collisionShapes.push_back(liftShape); + btTransform liftTrans; + m_liftStartPos = btVector3(0.0f, 2.5f, 3.05f); + liftTrans.setIdentity(); + liftTrans.setOrigin(m_liftStartPos); + m_liftBody = localCreateRigidBody(10,liftTrans, liftShape); + + btTransform localA, localB; + localA.setIdentity(); + localB.setIdentity(); + localA.getBasis().setEulerZYX(0, M_PI_2, 0); + localA.setOrigin(btVector3(0.0, 1.0, 3.05)); + localB.getBasis().setEulerZYX(0, M_PI_2, 0); + localB.setOrigin(btVector3(0.0, -1.5, -0.05)); + m_liftHinge = new btHingeConstraint(*m_carChassis,*m_liftBody, localA, localB); +// m_liftHinge->setLimit(-LIFT_EPS, LIFT_EPS); + m_liftHinge->setLimit(0.0f, 0.0f); + m_dynamicsWorld->addConstraint(m_liftHinge, true); + + btCollisionShape* forkShapeA = new btBoxShape(btVector3(1.0f,0.1f,0.1f)); + m_collisionShapes.push_back(forkShapeA); + btCompoundShape* forkCompound = new btCompoundShape(); + 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_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_collisionShapes.push_back(forkShapeC); + forkLocalTrans.setIdentity(); + forkLocalTrans.setOrigin(btVector3(0.9f, -0.08f, 0.7f)); + forkCompound->addChildShape(forkLocalTrans, forkShapeC); + + btTransform forkTrans; + m_forkStartPos = btVector3(0.0f, 0.6f, 3.2f); + forkTrans.setIdentity(); + forkTrans.setOrigin(m_forkStartPos); + m_forkBody = localCreateRigidBody(5, forkTrans, forkCompound); + + localA.setIdentity(); + localB.setIdentity(); + localA.getBasis().setEulerZYX(0, 0, M_PI_2); + localA.setOrigin(btVector3(0.0f, -1.9f, 0.05f)); + localB.getBasis().setEulerZYX(0, 0, M_PI_2); + localB.setOrigin(btVector3(0.0, 0.0, -0.1)); + m_forkSlider = new btSliderConstraint(*m_liftBody, *m_forkBody, localA, localB, true); + m_forkSlider->setLowerLinLimit(0.1f); + m_forkSlider->setUpperLinLimit(0.1f); +// m_forkSlider->setLowerAngLimit(-LIFT_EPS); +// m_forkSlider->setUpperAngLimit(LIFT_EPS); + m_forkSlider->setLowerAngLimit(0.0f); + m_forkSlider->setUpperAngLimit(0.0f); + m_dynamicsWorld->addConstraint(m_forkSlider, true); + + + btCompoundShape* loadCompound = new btCompoundShape(); + m_collisionShapes.push_back(loadCompound); + btCollisionShape* loadShapeA = new btBoxShape(btVector3(2.0f,0.5f,0.5f)); + 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_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_collisionShapes.push_back(loadShapeC); + loadTrans.setIdentity(); + loadTrans.setOrigin(btVector3(-2.1f, 0.0f, 0.0f)); + loadCompound->addChildShape(loadTrans, loadShapeC); + loadTrans.setIdentity(); + m_loadStartPos = btVector3(0.0f, 3.5f, 7.0f); + loadTrans.setOrigin(m_loadStartPos); + m_loadBody = localCreateRigidBody(loadMass, loadTrans, loadCompound); + } + + + + #if 0 + + /// create vehicle + { + + + ///never deactivate the vehicle + m_carChassis->setActivationState(DISABLE_DEACTIVATION); + + + float connectionHeight = 1.2f; + + + bool isFrontWheel=true; + + + +#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_vehicle->addWheel(connectionPointCS0,wheelDirectionCS0,wheelAxleCS,suspensionRestLength,wheelRadius,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_vehicle->addWheel(connectionPointCS0,wheelDirectionCS0,wheelAxleCS,suspensionRestLength,wheelRadius,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_vehicle->addWheel(connectionPointCS0,wheelDirectionCS0,wheelAxleCS,suspensionRestLength,wheelRadius,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_vehicle->addWheel(connectionPointCS0,wheelDirectionCS0,wheelAxleCS,suspensionRestLength,wheelRadius,m_tuning,isFrontWheel); + + for (int i=0;igetNumWheels();i++) + { + btWheelInfo& wheel = m_vehicle->getWheelInfo(i); + wheel.m_suspensionStiffness = suspensionStiffness; + wheel.m_wheelsDampingRelaxation = suspensionDamping; + wheel.m_wheelsDampingCompression = suspensionCompression; + wheel.m_frictionSlip = wheelFriction; + wheel.m_rollInfluence = rollInfluence; + } + + } + #endif + resetForklift(); + +// setCameraDistance(26.f); + + m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld); +} + +void Hinge2Vehicle::physicsDebugDraw(int debugFlags) +{ + if (m_dynamicsWorld && m_dynamicsWorld->getDebugDrawer()) + { + m_dynamicsWorld->getDebugDrawer()->setDebugMode(debugFlags); + m_dynamicsWorld->debugDrawWorld(); + } +} + +//to be implemented by the demo +void Hinge2Vehicle::renderScene() +{ + m_guiHelper->syncPhysicsToGraphics(m_dynamicsWorld); +#if 0 + for (int i=0;igetNumWheels();i++) + { + //synchronize the wheels with the (interpolated) chassis worldtransform + m_vehicle->updateWheelTransform(i,true); + + CommonRenderInterface* renderer = m_guiHelper->getRenderInterface(); + if (renderer) + { + btTransform tr = m_vehicle->getWheelInfo(i).m_worldTransform; + btVector3 pos=tr.getOrigin(); + btQuaternion orn = tr.getRotation(); + renderer->writeSingleInstanceTransformToCPU(pos,orn,m_wheelInstances[i]); + } + } +#endif + updateCamera(); + + m_guiHelper->render(m_dynamicsWorld); + + + + ATTRIBUTE_ALIGNED16(btScalar) m[16]; + int i; + + btVector3 wheelColor(1,0,0); + + btVector3 worldBoundsMin,worldBoundsMax; + getDynamicsWorld()->getBroadphase()->getBroadphaseAabb(worldBoundsMin,worldBoundsMax); + + + + +#if 0 + int lineWidth=400; + int xStart = m_glutScreenWidth - lineWidth; + int yStart = 20; + + if((getDebugMode() & btIDebugDraw::DBG_NoHelpText)==0) + { + setOrthographicProjection(); + glDisable(GL_LIGHTING); + glColor3f(0, 0, 0); + char buf[124]; + + sprintf(buf,"SHIFT+Cursor Left/Right - rotate lift"); + GLDebugDrawString(xStart,20,buf); + yStart+=20; + sprintf(buf,"SHIFT+Cursor UP/Down - fork up/down"); + yStart+=20; + GLDebugDrawString(xStart,yStart,buf); + + if (m_useDefaultCamera) + { + sprintf(buf,"F5 - camera mode (free)"); + } else + { + sprintf(buf,"F5 - camera mode (follow)"); + } + yStart+=20; + GLDebugDrawString(xStart,yStart,buf); + + yStart+=20; + if (m_dynamicsWorld->getConstraintSolver()->getSolverType()==BT_MLCP_SOLVER) + { + sprintf(buf,"F6 - solver (direct MLCP)"); + } else + { + sprintf(buf,"F6 - solver (sequential impulse)"); + } + GLDebugDrawString(xStart,yStart,buf); + btDiscreteDynamicsWorld* world = (btDiscreteDynamicsWorld*) m_dynamicsWorld; + if (world->getLatencyMotionStateInterpolation()) + { + sprintf(buf,"F7 - motionstate interpolation (on)"); + } else + { + sprintf(buf,"F7 - motionstate interpolation (off)"); + } + yStart+=20; + GLDebugDrawString(xStart,yStart,buf); + + sprintf(buf,"Click window for keyboard focus"); + yStart+=20; + GLDebugDrawString(xStart,yStart,buf); + + + resetPerspectiveProjection(); + glEnable(GL_LIGHTING); + } +#endif +} + +void Hinge2Vehicle::stepSimulation(float deltaTime) +{ + + //glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + +#if 0 + { + int wheelIndex = 2; + m_vehicle->applyEngineForce(gEngineForce,wheelIndex); + m_vehicle->setBrake(gBreakingForce,wheelIndex); + wheelIndex = 3; + m_vehicle->applyEngineForce(gEngineForce,wheelIndex); + m_vehicle->setBrake(gBreakingForce,wheelIndex); + + + wheelIndex = 0; + m_vehicle->setSteeringValue(gVehicleSteering,wheelIndex); + wheelIndex = 1; + m_vehicle->setSteeringValue(gVehicleSteering,wheelIndex); + + } +#endif + + float dt = deltaTime; + + if (m_dynamicsWorld) + { + //during idle mode, just run 1 simulation step maximum + int maxSimSubSteps = 2; + + int numSimSteps; + numSimSteps = m_dynamicsWorld->stepSimulation(dt,maxSimSubSteps); + + if (m_dynamicsWorld->getConstraintSolver()->getSolverType()==BT_MLCP_SOLVER) + { + btMLCPSolver* sol = (btMLCPSolver*) m_dynamicsWorld->getConstraintSolver(); + int numFallbacks = sol->getNumFallbacks(); + if (numFallbacks) + { + static int totalFailures = 0; + totalFailures+=numFallbacks; + printf("MLCP solver failed %d times, falling back to btSequentialImpulseSolver (SI)\n",totalFailures); + } + sol->setNumFallbacks(0); + } + + +//#define VERBOSE_FEEDBACK +#ifdef VERBOSE_FEEDBACK + if (!numSimSteps) + printf("Interpolated transforms\n"); + else + { + if (numSimSteps > maxSimSubSteps) + { + //detect dropping frames + printf("Dropped (%i) simulation steps out of %i\n",numSimSteps - maxSimSubSteps,numSimSteps); + } else + { + printf("Simulated (%i) steps\n",numSimSteps); + } + } +#endif //VERBOSE_FEEDBACK + + } + + + + +} + + + +void Hinge2Vehicle::displayCallback(void) +{ +// glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT); + + //renderme(); + +//optional but useful: debug drawing + if (m_dynamicsWorld) + m_dynamicsWorld->debugDrawWorld(); + +// glFlush(); +// glutSwapBuffers(); +} + + +void Hinge2Vehicle::clientResetScene() +{ + exitPhysics(); + initPhysics(); +} + +void Hinge2Vehicle::resetForklift() +{ + gVehicleSteering = 0.f; + gBreakingForce = defaultBreakingForce; + gEngineForce = 0.f; + + m_carChassis->setCenterOfMassTransform(btTransform::getIdentity()); + m_carChassis->setLinearVelocity(btVector3(0,0,0)); + m_carChassis->setAngularVelocity(btVector3(0,0,0)); + m_dynamicsWorld->getBroadphase()->getOverlappingPairCache()->cleanProxyFromPairs(m_carChassis->getBroadphaseHandle(),getDynamicsWorld()->getDispatcher()); +#if 0 + if (m_vehicle) + { + m_vehicle->resetSuspension(); + for (int i=0;igetNumWheels();i++) + { + //synchronize the wheels with the (interpolated) chassis worldtransform + m_vehicle->updateWheelTransform(i,true); + } + } +#endif + btTransform liftTrans; + liftTrans.setIdentity(); + liftTrans.setOrigin(m_liftStartPos); + m_liftBody->activate(); + m_liftBody->setCenterOfMassTransform(liftTrans); + m_liftBody->setLinearVelocity(btVector3(0,0,0)); + m_liftBody->setAngularVelocity(btVector3(0,0,0)); + + btTransform forkTrans; + forkTrans.setIdentity(); + forkTrans.setOrigin(m_forkStartPos); + m_forkBody->activate(); + m_forkBody->setCenterOfMassTransform(forkTrans); + m_forkBody->setLinearVelocity(btVector3(0,0,0)); + m_forkBody->setAngularVelocity(btVector3(0,0,0)); + +// m_liftHinge->setLimit(-LIFT_EPS, LIFT_EPS); + m_liftHinge->setLimit(0.0f, 0.0f); + m_liftHinge->enableAngularMotor(false, 0, 0); + + + m_forkSlider->setLowerLinLimit(0.1f); + m_forkSlider->setUpperLinLimit(0.1f); + m_forkSlider->setPoweredLinMotor(false); + + btTransform loadTrans; + loadTrans.setIdentity(); + loadTrans.setOrigin(m_loadStartPos); + m_loadBody->activate(); + m_loadBody->setCenterOfMassTransform(loadTrans); + m_loadBody->setLinearVelocity(btVector3(0,0,0)); + m_loadBody->setAngularVelocity(btVector3(0,0,0)); + +} + + +bool Hinge2Vehicle::keyboardCallback(int key, int state) +{ + bool handled = false; + bool isShiftPressed = m_guiHelper->getAppInterface()->m_window->isModifierKeyPressed(B3G_SHIFT); + + if (state) + { + if (isShiftPressed) + { + switch (key) + { + case B3G_LEFT_ARROW : + { + + m_liftHinge->setLimit(-M_PI/16.0f, M_PI/8.0f); + m_liftHinge->enableAngularMotor(true, -0.1, maxMotorImpulse); + handled = true; + break; + } + case B3G_RIGHT_ARROW : + { + + m_liftHinge->setLimit(-M_PI/16.0f, M_PI/8.0f); + m_liftHinge->enableAngularMotor(true, 0.1, maxMotorImpulse); + handled = true; + break; + } + case B3G_UP_ARROW : + { + m_forkSlider->setLowerLinLimit(0.1f); + m_forkSlider->setUpperLinLimit(3.9f); + m_forkSlider->setPoweredLinMotor(true); + m_forkSlider->setMaxLinMotorForce(maxMotorImpulse); + m_forkSlider->setTargetLinMotorVelocity(1.0); + handled = true; + break; + } + case B3G_DOWN_ARROW : + { + m_forkSlider->setLowerLinLimit(0.1f); + m_forkSlider->setUpperLinLimit(3.9f); + m_forkSlider->setPoweredLinMotor(true); + m_forkSlider->setMaxLinMotorForce(maxMotorImpulse); + m_forkSlider->setTargetLinMotorVelocity(-1.0); + handled = true; + break; + } + } + + } else + { + switch (key) + { + case B3G_LEFT_ARROW : + { + handled = true; + gVehicleSteering += steeringIncrement; + if ( gVehicleSteering > steeringClamp) + gVehicleSteering = steeringClamp; + + break; + } + case B3G_RIGHT_ARROW : + { + handled = true; + gVehicleSteering -= steeringIncrement; + if ( gVehicleSteering < -steeringClamp) + gVehicleSteering = -steeringClamp; + + break; + } + case B3G_UP_ARROW : + { + handled = true; + gEngineForce = maxEngineForce; + gBreakingForce = 0.f; + break; + } + case B3G_DOWN_ARROW : + { + handled = true; + gEngineForce = -maxEngineForce; + gBreakingForce = 0.f; + break; + } + + case B3G_F7: + { + handled = true; + btDiscreteDynamicsWorld* world = (btDiscreteDynamicsWorld*)m_dynamicsWorld; + world->setLatencyMotionStateInterpolation(!world->getLatencyMotionStateInterpolation()); + printf("world latencyMotionStateInterpolation = %d\n", world->getLatencyMotionStateInterpolation()); + break; + } + case B3G_F6: + { + handled = true; + //switch solver (needs demo restart) + useMCLPSolver = !useMCLPSolver; + printf("switching to useMLCPSolver = %d\n", useMCLPSolver); + + delete m_solver; + if (useMCLPSolver) + { + btDantzigSolver* mlcp = new btDantzigSolver(); + //btSolveProjectedGaussSeidel* mlcp = new btSolveProjectedGaussSeidel; + btMLCPSolver* sol = new btMLCPSolver(mlcp); + m_solver = sol; + } else + { + m_solver = new btSequentialImpulseConstraintSolver(); + } + + m_dynamicsWorld->setConstraintSolver(m_solver); + + + //exitPhysics(); + //initPhysics(); + break; + } + + case B3G_F5: + handled = true; + m_useDefaultCamera = !m_useDefaultCamera; + break; + default: + break; + } + } + + } else + { + switch (key) + { + case B3G_UP_ARROW: + { + lockForkSlider(); + gEngineForce = 0.f; + gBreakingForce = defaultBreakingForce; + handled=true; + break; + } + case B3G_DOWN_ARROW: + { + lockForkSlider(); + gEngineForce = 0.f; + gBreakingForce = defaultBreakingForce; + handled=true; + break; + } + case B3G_LEFT_ARROW: + case B3G_RIGHT_ARROW: + { + lockLiftHinge(); + handled=true; + break; + } + default: + + break; + } + } + return handled; +} + +void Hinge2Vehicle::specialKeyboardUp(int key, int x, int y) +{ +#if 0 + +#endif +} + + +void Hinge2Vehicle::specialKeyboard(int key, int x, int y) +{ +#if 0 + if (key==GLUT_KEY_END) + return; + + // printf("key = %i x=%i y=%i\n",key,x,y); + + int state; + state=glutGetModifiers(); + if (state & GLUT_ACTIVE_SHIFT) + { + switch (key) + { + case GLUT_KEY_LEFT : + { + + m_liftHinge->setLimit(-M_PI/16.0f, M_PI/8.0f); + m_liftHinge->enableAngularMotor(true, -0.1, maxMotorImpulse); + break; + } + case GLUT_KEY_RIGHT : + { + + m_liftHinge->setLimit(-M_PI/16.0f, M_PI/8.0f); + m_liftHinge->enableAngularMotor(true, 0.1, maxMotorImpulse); + break; + } + case GLUT_KEY_UP : + { + m_forkSlider->setLowerLinLimit(0.1f); + m_forkSlider->setUpperLinLimit(3.9f); + m_forkSlider->setPoweredLinMotor(true); + m_forkSlider->setMaxLinMotorForce(maxMotorImpulse); + m_forkSlider->setTargetLinMotorVelocity(1.0); + break; + } + case GLUT_KEY_DOWN : + { + m_forkSlider->setLowerLinLimit(0.1f); + m_forkSlider->setUpperLinLimit(3.9f); + m_forkSlider->setPoweredLinMotor(true); + m_forkSlider->setMaxLinMotorForce(maxMotorImpulse); + m_forkSlider->setTargetLinMotorVelocity(-1.0); + break; + } + + default: + DemoApplication::specialKeyboard(key,x,y); + break; + } + + } else + { + switch (key) + { + case GLUT_KEY_LEFT : + { + gVehicleSteering += steeringIncrement; + if ( gVehicleSteering > steeringClamp) + gVehicleSteering = steeringClamp; + + break; + } + case GLUT_KEY_RIGHT : + { + gVehicleSteering -= steeringIncrement; + if ( gVehicleSteering < -steeringClamp) + gVehicleSteering = -steeringClamp; + + break; + } + case GLUT_KEY_UP : + { + gEngineForce = maxEngineForce; + gBreakingForce = 0.f; + break; + } + case GLUT_KEY_DOWN : + { + gEngineForce = -maxEngineForce; + gBreakingForce = 0.f; + break; + } + + case GLUT_KEY_F7: + { + btDiscreteDynamicsWorld* world = (btDiscreteDynamicsWorld*)m_dynamicsWorld; + world->setLatencyMotionStateInterpolation(!world->getLatencyMotionStateInterpolation()); + printf("world latencyMotionStateInterpolation = %d\n", world->getLatencyMotionStateInterpolation()); + break; + } + case GLUT_KEY_F6: + { + //switch solver (needs demo restart) + useMCLPSolver = !useMCLPSolver; + printf("switching to useMLCPSolver = %d\n", useMCLPSolver); + + delete m_solver; + if (useMCLPSolver) + { + btDantzigSolver* mlcp = new btDantzigSolver(); + //btSolveProjectedGaussSeidel* mlcp = new btSolveProjectedGaussSeidel; + btMLCPSolver* sol = new btMLCPSolver(mlcp); + m_solver = sol; + } else + { + m_solver = new btSequentialImpulseConstraintSolver(); + } + + m_dynamicsWorld->setConstraintSolver(m_solver); + + + //exitPhysics(); + //initPhysics(); + break; + } + + case GLUT_KEY_F5: + m_useDefaultCamera = !m_useDefaultCamera; + break; + default: + DemoApplication::specialKeyboard(key,x,y); + break; + } + + } + // glutPostRedisplay(); + +#endif +} + +void Hinge2Vehicle::updateCamera() +{ + +#if 0 +//#define DISABLE_CAMERA 1 + if(m_useDefaultCamera) + { + DemoApplication::updateCamera(); + return; + } + + glMatrixMode(GL_PROJECTION); + glLoadIdentity(); + + btTransform chassisWorldTrans; + + //look at the vehicle + m_carChassis->getMotionState()->getWorldTransform(chassisWorldTrans); + m_cameraTargetPosition = chassisWorldTrans.getOrigin(); + + //interpolate the camera height +#ifdef FORCE_ZAXIS_UP + m_cameraPosition[2] = (15.0*m_cameraPosition[2] + m_cameraTargetPosition[2] + m_cameraHeight)/16.0; +#else + m_cameraPosition[1] = (15.0*m_cameraPosition[1] + m_cameraTargetPosition[1] + m_cameraHeight)/16.0; +#endif + + btVector3 camToObject = m_cameraTargetPosition - m_cameraPosition; + + //keep distance between min and max distance + float cameraDistance = camToObject.length(); + float correctionFactor = 0.f; + if (cameraDistance < m_minCameraDistance) + { + correctionFactor = 0.15*(m_minCameraDistance-cameraDistance)/cameraDistance; + } + if (cameraDistance > m_maxCameraDistance) + { + correctionFactor = 0.15*(m_maxCameraDistance-cameraDistance)/cameraDistance; + } + m_cameraPosition -= correctionFactor*camToObject; + + //update OpenGL camera settings + btScalar aspect = m_glutScreenWidth / (btScalar)m_glutScreenHeight; + glFrustum (-aspect, aspect, -1.0, 1.0, 1.0, 10000.0); + + glMatrixMode(GL_MODELVIEW); + glLoadIdentity(); + + gluLookAt(m_cameraPosition[0],m_cameraPosition[1],m_cameraPosition[2], + m_cameraTargetPosition[0],m_cameraTargetPosition[1], m_cameraTargetPosition[2], + m_cameraUp.getX(),m_cameraUp.getY(),m_cameraUp.getZ()); + + +#endif +} + +void Hinge2Vehicle::lockLiftHinge(void) +{ + btScalar hingeAngle = m_liftHinge->getHingeAngle(); + btScalar lowLim = m_liftHinge->getLowerLimit(); + btScalar hiLim = m_liftHinge->getUpperLimit(); + m_liftHinge->enableAngularMotor(false, 0, 0); + if(hingeAngle < lowLim) + { +// m_liftHinge->setLimit(lowLim, lowLim + LIFT_EPS); + m_liftHinge->setLimit(lowLim, lowLim); + } + else if(hingeAngle > hiLim) + { +// m_liftHinge->setLimit(hiLim - LIFT_EPS, hiLim); + m_liftHinge->setLimit(hiLim, hiLim); + } + else + { +// m_liftHinge->setLimit(hingeAngle - LIFT_EPS, hingeAngle + LIFT_EPS); + m_liftHinge->setLimit(hingeAngle, hingeAngle); + } + return; +} // Hinge2Vehicle::lockLiftHinge() + +void Hinge2Vehicle::lockForkSlider(void) +{ + btScalar linDepth = m_forkSlider->getLinearPos(); + btScalar lowLim = m_forkSlider->getLowerLinLimit(); + btScalar hiLim = m_forkSlider->getUpperLinLimit(); + m_forkSlider->setPoweredLinMotor(false); + if(linDepth <= lowLim) + { + m_forkSlider->setLowerLinLimit(lowLim); + m_forkSlider->setUpperLinLimit(lowLim); + } + else if(linDepth > hiLim) + { + m_forkSlider->setLowerLinLimit(hiLim); + m_forkSlider->setUpperLinLimit(hiLim); + } + else + { + m_forkSlider->setLowerLinLimit(linDepth); + m_forkSlider->setUpperLinLimit(linDepth); + } + return; +} // Hinge2Vehicle::lockForkSlider() + +btRigidBody* Hinge2Vehicle::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(m_defaultContactProcessingThreshold); + +#else + btRigidBody* body = new btRigidBody(mass,0,shape,localInertia); + body->setWorldTransform(startTransform); +#endif// + + m_dynamicsWorld->addRigidBody(body); + return body; +} + +ExampleInterface* Hinge2VehicleCreateFunc(struct PhysicsInterface* pint, struct GUIHelperInterface* helper, int option) +{ + return new Hinge2Vehicle(helper); +} diff --git a/examples/Vehicles/Hinge2Vehicle.h b/examples/Vehicles/Hinge2Vehicle.h new file mode 100644 index 000000000..56869d911 --- /dev/null +++ b/examples/Vehicles/Hinge2Vehicle.h @@ -0,0 +1,23 @@ +/* +Bullet Continuous Collision Detection and Physics Library +Copyright (c) 2003-2015 Erwin Coumans http://continuousphysics.com/Bullet/ + +This software is provided 'as-is', without any express or implied warranty. +In no event will the authors be held liable for any damages arising from the use of this software. +Permission is granted to anyone to use this software for any purpose, +including commercial applications, and to alter it and redistribute it freely, +subject to the following restrictions: + +1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required. +2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. +3. This notice may not be removed or altered from any source distribution. +*/ + +#ifndef HINGE2_VEHICLE_H +#define HINGE2_VEHICLE_H + +class ExampleInterface* Hinge2VehicleCreateFunc(struct PhysicsInterface* pint, struct GUIHelperInterface* helper, int option); + +#endif // HINGE2_VEHICLE_H + + diff --git a/src/BulletDynamics/ConstraintSolver/btHinge2Constraint.cpp b/src/BulletDynamics/ConstraintSolver/btHinge2Constraint.cpp index 29123d526..4be2aabe4 100644 --- a/src/BulletDynamics/ConstraintSolver/btHinge2Constraint.cpp +++ b/src/BulletDynamics/ConstraintSolver/btHinge2Constraint.cpp @@ -25,7 +25,7 @@ subject to the following restrictions: // anchor, axis1 and axis2 are in world coordinate system // axis1 must be orthogonal to axis2 btHinge2Constraint::btHinge2Constraint(btRigidBody& rbA, btRigidBody& rbB, btVector3& anchor, btVector3& axis1, btVector3& axis2) -: btGeneric6DofSpringConstraint(rbA, rbB, btTransform::getIdentity(), btTransform::getIdentity(), true), +: btGeneric6DofSpring2Constraint(rbA, rbB, btTransform::getIdentity(), btTransform::getIdentity(),RO_XYZ), m_anchor(anchor), m_axis1(axis1), m_axis2(axis2) @@ -59,7 +59,7 @@ btHinge2Constraint::btHinge2Constraint(btRigidBody& rbA, btRigidBody& rbB, btVec setAngularUpperLimit(btVector3(-1.f, 0.f, SIMD_HALF_PI * 0.5f)); // enable suspension enableSpring(2, true); - setStiffness(2, SIMD_PI * SIMD_PI * 4.f); // period 1 sec for 1 kilogramm weel :-) + setStiffness(2, SIMD_PI * SIMD_PI * 4.f); setDamping(2, 0.01f); setEquilibriumPoint(); } diff --git a/src/BulletDynamics/ConstraintSolver/btHinge2Constraint.h b/src/BulletDynamics/ConstraintSolver/btHinge2Constraint.h index 9a0049869..06a8e3ecd 100644 --- a/src/BulletDynamics/ConstraintSolver/btHinge2Constraint.h +++ b/src/BulletDynamics/ConstraintSolver/btHinge2Constraint.h @@ -20,7 +20,7 @@ subject to the following restrictions: #include "LinearMath/btVector3.h" #include "btTypedConstraint.h" -#include "btGeneric6DofSpringConstraint.h" +#include "btGeneric6DofSpring2Constraint.h" @@ -29,7 +29,7 @@ subject to the following restrictions: // 2 rotational degrees of freedom, similar to Euler rotations around Z (axis 1) and X (axis 2) // 1 translational (along axis Z) with suspension spring -ATTRIBUTE_ALIGNED16(class) btHinge2Constraint : public btGeneric6DofSpringConstraint +ATTRIBUTE_ALIGNED16(class) btHinge2Constraint : public btGeneric6DofSpring2Constraint { protected: btVector3 m_anchor;