2015-04-29 01:12:49 +00:00
/*
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"
2015-04-29 20:33:26 +00:00
# include "../CommonInterfaces/CommonExampleInterface.h"
2015-04-29 01:12:49 +00:00
# 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"
2018-09-23 21:17:31 +00:00
class Hinge2Vehicle : public CommonRigidBodyBase
2015-04-29 01:12:49 +00:00
{
2018-09-23 21:17:31 +00:00
public :
/* extra stuff*/
2015-04-29 01:12:49 +00:00
btVector3 m_cameraPosition ;
2018-09-23 21:17:31 +00:00
2015-04-29 01:12:49 +00:00
btRigidBody * m_carChassis ;
btRigidBody * localCreateRigidBody ( btScalar mass , const btTransform & worldTransform , btCollisionShape * colSape ) ;
GUIHelperInterface * m_guiHelper ;
int m_wheelInstances [ 4 ] ;
bool m_useDefaultCamera ;
2018-09-23 21:17:31 +00:00
//----------------------------
2015-04-29 01:12:49 +00:00
2018-09-23 21:17:31 +00:00
class btTriangleIndexVertexArray * m_indexVertexArrays ;
2015-04-29 01:12:49 +00:00
2018-09-23 21:17:31 +00:00
btVector3 * m_vertices ;
2015-04-29 01:12:49 +00:00
2018-09-23 21:17:31 +00:00
btCollisionShape * m_wheelShape ;
2015-04-29 01:12:49 +00:00
2018-09-23 21:17:31 +00:00
float m_cameraHeight ;
2015-04-29 01:12:49 +00:00
2018-09-23 21:17:31 +00:00
float m_minCameraDistance ;
float m_maxCameraDistance ;
2015-04-29 01:12:49 +00:00
Hinge2Vehicle ( struct GUIHelperInterface * helper ) ;
virtual ~ Hinge2Vehicle ( ) ;
virtual void stepSimulation ( float deltaTime ) ;
2018-09-23 21:17:31 +00:00
virtual void resetForklift ( ) ;
2015-04-29 01:12:49 +00:00
virtual void clientResetScene ( ) ;
virtual void displayCallback ( ) ;
2018-09-23 21:17:31 +00:00
2015-04-29 01:12:49 +00:00
virtual void specialKeyboard ( int key , int x , int y ) ;
virtual void specialKeyboardUp ( int key , int x , int y ) ;
2018-09-23 21:17:31 +00:00
virtual bool keyboardCallback ( int key , int state ) ;
2015-04-29 01:12:49 +00:00
virtual void renderScene ( ) ;
virtual void physicsDebugDraw ( int debugFlags ) ;
void initPhysics ( ) ;
void exitPhysics ( ) ;
2015-05-01 18:42:14 +00:00
virtual void resetCamera ( )
{
float dist = 8 ;
2017-06-01 22:30:37 +00:00
float pitch = - 32 ;
float yaw = - 45 ;
2018-11-19 22:47:03 +00:00
float targetPos [ 3 ] = { 0 , 0 , 2 } ;
2018-09-23 21:17:31 +00:00
m_guiHelper - > resetCamera ( dist , yaw , pitch , targetPos [ 0 ] , targetPos [ 1 ] , targetPos [ 2 ] ) ;
2015-05-01 18:42:14 +00:00
}
2015-04-29 01:12:49 +00:00
/*static DemoApplication* Create()
{
Hinge2Vehicle * demo = new Hinge2Vehicle ( ) ;
demo - > myinit ( ) ;
demo - > initPhysics ( ) ;
return demo ;
}
*/
} ;
2015-04-29 18:05:00 +00:00
static btScalar maxMotorImpulse = 4000.f ;
2015-04-29 01:12:49 +00:00
# ifndef M_PI
2018-09-23 21:17:31 +00:00
# define M_PI 3.14159265358979323846
2015-04-29 01:12:49 +00:00
# endif
# ifndef M_PI_2
2018-09-23 21:17:31 +00:00
# define M_PI_2 1.57079632679489661923
2015-04-29 01:12:49 +00:00
# endif
# ifndef M_PI_4
2018-09-23 21:17:31 +00:00
# define M_PI_4 0.785398163397448309616
2015-04-29 01:12:49 +00:00
# endif
2017-01-16 06:26:11 +00:00
//static int rightIndex = 0;
//static int upIndex = 1;
//static int forwardIndex = 2;
2018-09-23 21:17:31 +00:00
static btVector3 wheelDirectionCS0 ( 0 , - 1 , 0 ) ;
static btVector3 wheelAxleCS ( - 1 , 0 , 0 ) ;
2015-04-29 01:12:49 +00:00
2018-09-23 21:17:31 +00:00
static bool useMCLPSolver = false ; //true;
2015-04-29 01:12:49 +00:00
2018-09-23 21:17:31 +00:00
# include <stdio.h> //printf debugging
2015-04-29 01:12:49 +00:00
# include "Hinge2Vehicle.h"
2017-01-16 06:26:11 +00:00
//static const int maxProxies = 32766;
//static const int maxOverlap = 65535;
2015-04-29 01:12:49 +00:00
2018-09-23 21:17:31 +00:00
static float gEngineForce = 0.f ;
2015-04-29 01:12:49 +00:00
2018-09-23 21:17:31 +00:00
static float defaultBreakingForce = 10.f ;
static float gBreakingForce = 100.f ;
2015-04-29 01:12:49 +00:00
2018-09-23 21:17:31 +00:00
static float maxEngineForce = 1000.f ; //this should be engine/velocity dependent
2017-01-16 06:26:11 +00:00
//static float maxBreakingForce = 100.f;
2015-04-29 01:12:49 +00:00
2018-09-23 21:17:31 +00:00
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 ;
2017-01-16 06:26:11 +00:00
//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;
2015-04-29 01:12:49 +00:00
2017-01-16 06:26:11 +00:00
//static btScalar suspensionRestLength(0.6);
2015-04-29 01:12:49 +00:00
# define CUBE_HALF_EXTENTS 1
////////////////////////////////////
Hinge2Vehicle : : Hinge2Vehicle ( struct GUIHelperInterface * helper )
2018-09-23 21:17:31 +00:00
: CommonRigidBodyBase ( helper ) ,
m_carChassis ( 0 ) ,
m_guiHelper ( helper ) ,
m_indexVertexArrays ( 0 ) ,
m_vertices ( 0 ) ,
m_cameraHeight ( 4.f ) ,
m_minCameraDistance ( 3.f ) ,
m_maxCameraDistance ( 10.f )
2015-04-29 01:12:49 +00:00
{
helper - > setUpAxis ( 1 ) ;
m_wheelShape = 0 ;
2018-09-23 21:17:31 +00:00
m_cameraPosition = btVector3 ( 30 , 30 , 30 ) ;
2015-04-29 01:12:49 +00:00
m_useDefaultCamera = false ;
}
void Hinge2Vehicle : : exitPhysics ( )
{
2018-09-23 21:17:31 +00:00
//cleanup in the reverse order of creation/initialization
2015-04-29 01:12:49 +00:00
//remove the rigidbodies from the dynamics world and delete them
int i ;
2018-09-23 21:17:31 +00:00
for ( i = m_dynamicsWorld - > getNumCollisionObjects ( ) - 1 ; i > = 0 ; i - - )
2015-04-29 01:12:49 +00:00
{
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 ) ;
2018-09-23 21:17:31 +00:00
}
else
2015-04-29 01:12:49 +00:00
{
2018-09-23 21:17:31 +00:00
m_dynamicsWorld - > removeCollisionObject ( obj ) ;
2015-04-29 01:12:49 +00:00
}
delete obj ;
}
//delete collision shapes
2018-09-23 21:17:31 +00:00
for ( int j = 0 ; j < m_collisionShapes . size ( ) ; j + + )
2015-04-29 01:12:49 +00:00
{
btCollisionShape * shape = m_collisionShapes [ j ] ;
delete shape ;
}
m_collisionShapes . clear ( ) ;
delete m_indexVertexArrays ;
delete m_vertices ;
//delete dynamics world
delete m_dynamicsWorld ;
2018-09-23 21:17:31 +00:00
m_dynamicsWorld = 0 ;
2015-04-29 01:12:49 +00:00
delete m_wheelShape ;
2018-09-23 21:17:31 +00:00
m_wheelShape = 0 ;
2015-04-29 01:12:49 +00:00
//delete solver
delete m_solver ;
2018-09-23 21:17:31 +00:00
m_solver = 0 ;
2015-04-29 01:12:49 +00:00
//delete broadphase
delete m_broadphase ;
2018-09-23 21:17:31 +00:00
m_broadphase = 0 ;
2015-04-29 01:12:49 +00:00
//delete dispatcher
delete m_dispatcher ;
2018-09-23 21:17:31 +00:00
m_dispatcher = 0 ;
2015-04-29 01:12:49 +00:00
delete m_collisionConfiguration ;
2018-09-23 21:17:31 +00:00
m_collisionConfiguration = 0 ;
2015-04-29 01:12:49 +00:00
}
Hinge2Vehicle : : ~ Hinge2Vehicle ( )
{
//exitPhysics();
}
void Hinge2Vehicle : : initPhysics ( )
{
2015-04-29 21:02:50 +00:00
m_guiHelper - > setUpAxis ( 1 ) ;
2018-09-23 21:17:31 +00:00
btCollisionShape * groundShape = new btBoxShape ( btVector3 ( 50 , 3 , 50 ) ) ;
2015-04-29 01:12:49 +00:00
m_collisionShapes . push_back ( groundShape ) ;
m_collisionConfiguration = new btDefaultCollisionConfiguration ( ) ;
m_dispatcher = new btCollisionDispatcher ( m_collisionConfiguration ) ;
2018-09-23 21:17:31 +00:00
btVector3 worldMin ( - 1000 , - 1000 , - 1000 ) ;
btVector3 worldMax ( 1000 , 1000 , 1000 ) ;
m_broadphase = new btAxisSweep3 ( worldMin , worldMax ) ;
2015-04-29 01:12:49 +00:00
if ( useMCLPSolver )
{
btDantzigSolver * mlcp = new btDantzigSolver ( ) ;
//btSolveProjectedGaussSeidel* mlcp = new btSolveProjectedGaussSeidel;
btMLCPSolver * sol = new btMLCPSolver ( mlcp ) ;
m_solver = sol ;
2018-09-23 21:17:31 +00:00
}
else
2015-04-29 01:12:49 +00:00
{
m_solver = new btSequentialImpulseConstraintSolver ( ) ;
}
2018-09-23 21:17:31 +00:00
m_dynamicsWorld = new btDiscreteDynamicsWorld ( m_dispatcher , m_broadphase , m_solver , m_collisionConfiguration ) ;
2015-04-29 01:12:49 +00:00
if ( useMCLPSolver )
{
2018-09-23 21:17:31 +00:00
m_dynamicsWorld - > getSolverInfo ( ) . m_minimumSolverBatchSize = 1 ; //for direct solver it is better to have a small A matrix
}
else
2015-04-29 01:12:49 +00:00
{
2018-09-23 21:17:31 +00:00
m_dynamicsWorld - > getSolverInfo ( ) . m_minimumSolverBatchSize = 128 ; //for direct solver, it is better to solve multiple objects together, small batches have high overhead
2015-04-29 01:12:49 +00:00
}
m_dynamicsWorld - > getSolverInfo ( ) . m_numIterations = 100 ;
m_guiHelper - > createPhysicsDebugDrawer ( m_dynamicsWorld ) ;
//m_dynamicsWorld->setGravity(btVector3(0,0,0));
2018-09-23 21:17:31 +00:00
btTransform tr ;
tr . setIdentity ( ) ;
tr . setOrigin ( btVector3 ( 0 , - 3 , 0 ) ) ;
2015-04-29 01:12:49 +00:00
2018-09-23 21:17:31 +00:00
//either use heightfield or triangle mesh
2015-04-29 01:12:49 +00:00
//create ground object
2018-09-23 21:17:31 +00:00
localCreateRigidBody ( 0 , tr , groundShape ) ;
2015-04-29 01:12:49 +00:00
2018-09-23 21:17:31 +00:00
btCollisionShape * chassisShape = new btBoxShape ( btVector3 ( 1.f , 0.5f , 2.f ) ) ;
2015-04-29 01:12:49 +00:00
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
2018-09-23 21:17:31 +00:00
localTrans . setOrigin ( btVector3 ( 0 , 1 , 0 ) ) ;
2015-04-29 01:12:49 +00:00
2018-09-23 21:17:31 +00:00
compound - > addChildShape ( localTrans , chassisShape ) ;
2015-04-29 01:12:49 +00:00
{
2018-09-23 21:17:31 +00:00
btCollisionShape * suppShape = new btBoxShape ( btVector3 ( 0.5f , 0.1f , 0.5f ) ) ;
2015-04-29 01:12:49 +00:00
btTransform suppLocalTrans ;
suppLocalTrans . setIdentity ( ) ;
//localTrans effectively shifts the center of mass with respect to the chassis
2018-09-23 21:17:31 +00:00
suppLocalTrans . setOrigin ( btVector3 ( 0 , 1.0 , 2.5 ) ) ;
2015-04-29 01:12:49 +00:00
compound - > addChildShape ( suppLocalTrans , suppShape ) ;
}
2018-11-19 22:47:03 +00:00
const btScalar FALLHEIGHT = 5 ;
tr . setOrigin ( btVector3 ( 0 , FALLHEIGHT , 0 ) ) ;
2015-04-29 01:12:49 +00:00
2018-11-19 22:47:03 +00:00
const btScalar chassisMass = 2.0f ;
const btScalar wheelMass = 1.0f ;
2018-09-23 21:17:31 +00:00
m_carChassis = localCreateRigidBody ( chassisMass , tr , compound ) ; //chassisShape);
2015-04-29 01:12:49 +00:00
//m_carChassis->setDamping(0.2,0.2);
2018-09-23 21:17:31 +00:00
2015-04-29 01:12:49 +00:00
//m_wheelShape = new btCylinderShapeX(btVector3(wheelWidth,wheelRadius,wheelRadius));
2018-09-23 21:17:31 +00:00
m_wheelShape = new btCylinderShapeX ( btVector3 ( wheelWidth , wheelRadius , wheelRadius ) ) ;
2015-04-29 01:12:49 +00:00
btVector3 wheelPos [ 4 ] = {
2018-11-19 22:47:03 +00:00
btVector3 ( btScalar ( - 1. ) , btScalar ( FALLHEIGHT - 0.25 ) , btScalar ( 1.25 ) ) ,
btVector3 ( btScalar ( 1. ) , btScalar ( FALLHEIGHT - 0.25 ) , btScalar ( 1.25 ) ) ,
btVector3 ( btScalar ( 1. ) , btScalar ( FALLHEIGHT - 0.25 ) , btScalar ( - 1.25 ) ) ,
btVector3 ( btScalar ( - 1. ) , btScalar ( FALLHEIGHT - 0.25 ) , btScalar ( - 1.25 ) ) } ;
2015-04-29 01:12:49 +00:00
2018-09-23 21:17:31 +00:00
for ( int i = 0 ; i < 4 ; i + + )
{
2015-04-29 01:12:49 +00:00
// create a Hinge2 joint
// create two rigid bodies
// static bodyA (parent) on top:
2018-09-23 21:17:31 +00:00
2018-11-19 22:47:03 +00:00
btRigidBody * pBodyA = this - > m_carChassis ;
2015-04-29 01:12:49 +00:00
pBodyA - > setActivationState ( DISABLE_DEACTIVATION ) ;
// dynamic bodyB (child) below it :
btTransform tr ;
tr . setIdentity ( ) ;
tr . setOrigin ( wheelPos [ i ] ) ;
2018-09-23 21:17:31 +00:00
2018-11-19 22:47:03 +00:00
btRigidBody * pBodyB = createRigidBody ( wheelMass , tr , m_wheelShape ) ;
2015-04-29 01:12:49 +00:00
pBodyB - > setFriction ( 1110 ) ;
pBodyB - > setActivationState ( DISABLE_DEACTIVATION ) ;
// add some data to build constraint frames
2018-09-23 21:17:31 +00:00
btVector3 parentAxis ( 0.f , 1.f , 0.f ) ;
btVector3 childAxis ( 1.f , 0.f , 0.f ) ;
2018-11-19 22:47:03 +00:00
btVector3 anchor = tr . getOrigin ( ) ;
2015-04-29 01:12:49 +00:00
btHinge2Constraint * pHinge2 = new btHinge2Constraint ( * pBodyA , * pBodyB , anchor , parentAxis , childAxis ) ;
2018-09-23 21:17:31 +00:00
2015-04-29 01:12:49 +00:00
//m_guiHelper->get2dCanvasInterface();
2018-11-19 22:47:03 +00:00
//pHinge2->setLowerLimit(-SIMD_HALF_PI * 0.5f);
//pHinge2->setUpperLimit(SIMD_HALF_PI * 0.5f);
2015-04-29 01:12:49 +00:00
// add constraint to world
m_dynamicsWorld - > addConstraint ( pHinge2 , true ) ;
2018-11-19 22:47:03 +00:00
// Drive engine.
pHinge2 - > enableMotor ( 3 , true ) ;
pHinge2 - > setMaxMotorForce ( 3 , 1000 ) ;
pHinge2 - > setTargetVelocity ( 3 , 0 ) ;
2015-04-29 01:12:49 +00:00
2018-11-19 22:47:03 +00:00
// Steering engine.
pHinge2 - > enableMotor ( 5 , true ) ;
pHinge2 - > setMaxMotorForce ( 5 , 1000 ) ;
pHinge2 - > setTargetVelocity ( 5 , 0 ) ;
2015-04-29 01:12:49 +00:00
2018-11-19 22:47:03 +00:00
pHinge2 - > setParam ( BT_CONSTRAINT_CFM , 0.15f , 2 ) ;
pHinge2 - > setParam ( BT_CONSTRAINT_ERP , 0.35f , 2 ) ;
pHinge2 - > setDamping ( 2 , 2.0 ) ;
pHinge2 - > setStiffness ( 2 , 40.0 ) ;
pHinge2 - > setDbgDrawSize ( btScalar ( 5.f ) ) ;
2015-04-29 01:12:49 +00:00
}
resetForklift ( ) ;
2018-09-23 21:17:31 +00:00
2015-04-29 01:12:49 +00:00
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 ) ;
2018-09-23 21:17:31 +00:00
m_guiHelper - > render ( m_dynamicsWorld ) ;
2015-04-29 01:12:49 +00:00
2018-09-23 21:17:31 +00:00
btVector3 wheelColor ( 1 , 0 , 0 ) ;
2015-04-29 01:12:49 +00:00
2018-09-23 21:17:31 +00:00
btVector3 worldBoundsMin , worldBoundsMax ;
getDynamicsWorld ( ) - > getBroadphase ( ) - > getBroadphaseAabb ( worldBoundsMin , worldBoundsMax ) ;
2015-04-29 01:12:49 +00:00
}
void Hinge2Vehicle : : stepSimulation ( float deltaTime )
{
float dt = deltaTime ;
2018-09-23 21:17:31 +00:00
2015-04-29 01:12:49 +00:00
if ( m_dynamicsWorld )
{
//during idle mode, just run 1 simulation step maximum
2018-09-23 21:17:31 +00:00
int maxSimSubSteps = 2 ;
2015-04-29 01:12:49 +00:00
int numSimSteps ;
2018-09-23 21:17:31 +00:00
numSimSteps = m_dynamicsWorld - > stepSimulation ( dt , maxSimSubSteps ) ;
2015-04-29 01:12:49 +00:00
2018-09-23 21:17:31 +00:00
if ( m_dynamicsWorld - > getConstraintSolver ( ) - > getSolverType ( ) = = BT_MLCP_SOLVER )
2015-04-29 01:12:49 +00:00
{
2018-09-23 21:17:31 +00:00
btMLCPSolver * sol = ( btMLCPSolver * ) m_dynamicsWorld - > getConstraintSolver ( ) ;
2015-04-29 01:12:49 +00:00
int numFallbacks = sol - > getNumFallbacks ( ) ;
if ( numFallbacks )
{
static int totalFailures = 0 ;
2018-09-23 21:17:31 +00:00
totalFailures + = numFallbacks ;
printf ( " MLCP solver failed %d times, falling back to btSequentialImpulseSolver (SI) \n " , totalFailures ) ;
2015-04-29 01:12:49 +00:00
}
sol - > setNumFallbacks ( 0 ) ;
}
//#define VERBOSE_FEEDBACK
# ifdef VERBOSE_FEEDBACK
2018-09-23 21:17:31 +00:00
if ( ! numSimSteps )
2015-04-29 01:12:49 +00:00
printf ( " Interpolated transforms \n " ) ;
else
{
if ( numSimSteps > maxSimSubSteps )
{
//detect dropping frames
2018-09-23 21:17:31 +00:00
printf ( " Dropped (%i) simulation steps out of %i \n " , numSimSteps - maxSimSubSteps , numSimSteps ) ;
}
else
2015-04-29 01:12:49 +00:00
{
2018-09-23 21:17:31 +00:00
printf ( " Simulated (%i) steps \n " , numSimSteps ) ;
2015-04-29 01:12:49 +00:00
}
}
2018-09-23 21:17:31 +00:00
# endif //VERBOSE_FEEDBACK
2015-04-29 01:12:49 +00:00
}
}
2018-09-23 21:17:31 +00:00
void Hinge2Vehicle : : displayCallback ( void )
2015-04-29 01:12:49 +00:00
{
2018-09-23 21:17:31 +00:00
// glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);
2015-04-29 01:12:49 +00:00
//renderme();
2018-09-23 21:17:31 +00:00
//optional but useful: debug drawing
2015-04-29 01:12:49 +00:00
if ( m_dynamicsWorld )
m_dynamicsWorld - > debugDrawWorld ( ) ;
2018-09-23 21:17:31 +00:00
// glFlush();
// glutSwapBuffers();
2015-04-29 01:12:49 +00:00
}
void Hinge2Vehicle : : clientResetScene ( )
{
exitPhysics ( ) ;
initPhysics ( ) ;
}
void Hinge2Vehicle : : resetForklift ( )
{
gVehicleSteering = 0.f ;
gBreakingForce = defaultBreakingForce ;
gEngineForce = 0.f ;
m_carChassis - > setCenterOfMassTransform ( btTransform : : getIdentity ( ) ) ;
2018-09-23 21:17:31 +00:00
m_carChassis - > setLinearVelocity ( btVector3 ( 0 , 0 , 0 ) ) ;
m_carChassis - > setAngularVelocity ( btVector3 ( 0 , 0 , 0 ) ) ;
m_dynamicsWorld - > getBroadphase ( ) - > getOverlappingPairCache ( ) - > cleanProxyFromPairs ( m_carChassis - > getBroadphaseHandle ( ) , getDynamicsWorld ( ) - > getDispatcher ( ) ) ;
2015-04-29 01:12:49 +00:00
}
2018-09-23 21:17:31 +00:00
bool Hinge2Vehicle : : keyboardCallback ( int key , int state )
2015-04-29 01:12:49 +00:00
{
bool handled = false ;
bool isShiftPressed = m_guiHelper - > getAppInterface ( ) - > m_window - > isModifierKeyPressed ( B3G_SHIFT ) ;
if ( state )
{
2018-09-23 21:17:31 +00:00
if ( isShiftPressed )
{
}
else
{
switch ( key )
2015-04-29 01:12:49 +00:00
{
2018-09-23 21:17:31 +00:00
case B3G_LEFT_ARROW :
2015-04-29 01:12:49 +00:00
{
handled = true ;
gVehicleSteering + = steeringIncrement ;
2018-09-23 21:17:31 +00:00
if ( gVehicleSteering > steeringClamp )
2015-04-29 01:12:49 +00:00
gVehicleSteering = steeringClamp ;
break ;
}
2018-09-23 21:17:31 +00:00
case B3G_RIGHT_ARROW :
2015-04-29 01:12:49 +00:00
{
handled = true ;
gVehicleSteering - = steeringIncrement ;
2018-09-23 21:17:31 +00:00
if ( gVehicleSteering < - steeringClamp )
2015-04-29 01:12:49 +00:00
gVehicleSteering = - steeringClamp ;
break ;
}
2018-09-23 21:17:31 +00:00
case B3G_UP_ARROW :
2015-04-29 01:12:49 +00:00
{
handled = true ;
gEngineForce = maxEngineForce ;
gBreakingForce = 0.f ;
break ;
}
2018-09-23 21:17:31 +00:00
case B3G_DOWN_ARROW :
2015-04-29 01:12:49 +00:00
{
handled = true ;
gEngineForce = - maxEngineForce ;
gBreakingForce = 0.f ;
break ;
}
2018-09-23 21:17:31 +00:00
case B3G_F7 :
2015-04-29 01:12:49 +00:00
{
handled = true ;
btDiscreteDynamicsWorld * world = ( btDiscreteDynamicsWorld * ) m_dynamicsWorld ;
world - > setLatencyMotionStateInterpolation ( ! world - > getLatencyMotionStateInterpolation ( ) ) ;
printf ( " world latencyMotionStateInterpolation = %d \n " , world - > getLatencyMotionStateInterpolation ( ) ) ;
break ;
}
2018-09-23 21:17:31 +00:00
case B3G_F6 :
2015-04-29 01:12:49 +00:00
{
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 ;
2018-09-23 21:17:31 +00:00
}
else
2015-04-29 01:12:49 +00:00
{
m_solver = new btSequentialImpulseConstraintSolver ( ) ;
}
m_dynamicsWorld - > setConstraintSolver ( m_solver ) ;
//exitPhysics();
//initPhysics();
break ;
}
2018-09-23 21:17:31 +00:00
case B3G_F5 :
handled = true ;
m_useDefaultCamera = ! m_useDefaultCamera ;
break ;
default :
break ;
2015-04-29 01:12:49 +00:00
}
2018-09-23 21:17:31 +00:00
}
2015-04-29 01:12:49 +00:00
}
2018-09-23 21:17:31 +00:00
else
2015-04-29 01:12:49 +00:00
{
}
return handled ;
}
void Hinge2Vehicle : : specialKeyboardUp ( int key , int x , int y )
{
}
void Hinge2Vehicle : : specialKeyboard ( int key , int x , int y )
{
}
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 ) ;
2018-09-23 21:17:31 +00:00
btVector3 localInertia ( 0 , 0 , 0 ) ;
2015-04-29 01:12:49 +00:00
if ( isDynamic )
2018-09-23 21:17:31 +00:00
shape - > calculateLocalInertia ( mass , localInertia ) ;
2015-04-29 01:12:49 +00:00
2018-09-23 21:17:31 +00:00
//using motionstate is recommended, it provides interpolation capabilities, and only synchronizes 'active' objects
2015-04-29 01:12:49 +00:00
# define USE_MOTIONSTATE 1
# ifdef USE_MOTIONSTATE
btDefaultMotionState * myMotionState = new btDefaultMotionState ( startTransform ) ;
2018-09-23 21:17:31 +00:00
btRigidBody : : btRigidBodyConstructionInfo cInfo ( mass , myMotionState , shape , localInertia ) ;
2015-04-29 01:12:49 +00:00
btRigidBody * body = new btRigidBody ( cInfo ) ;
//body->setContactProcessingThreshold(m_defaultContactProcessingThreshold);
# else
2018-09-23 21:17:31 +00:00
btRigidBody * body = new btRigidBody ( mass , 0 , shape , localInertia ) ;
2015-04-29 01:12:49 +00:00
body - > setWorldTransform ( startTransform ) ;
2018-09-23 21:17:31 +00:00
# endif //
2015-04-29 01:12:49 +00:00
m_dynamicsWorld - > addRigidBody ( body ) ;
return body ;
}
2018-09-23 21:17:31 +00:00
CommonExampleInterface * Hinge2VehicleCreateFunc ( struct CommonExampleOptions & options )
2015-04-29 01:12:49 +00:00
{
2015-05-01 18:42:14 +00:00
return new Hinge2Vehicle ( options . m_guiHelper ) ;
2015-04-29 01:12:49 +00:00
}