Blender V2.61 - r43446
|
00001 00004 /* 00005 Bullet Continuous Collision Detection and Physics Library 00006 Copyright (c) 2003-2006 Erwin Coumans http://continuousphysics.com/Bullet/ 00007 00008 This software is provided 'as-is', without any express or implied warranty. 00009 In no event will the authors be held liable for any damages arising from the use of this software. 00010 Permission is granted to anyone to use this software for any purpose, 00011 including commercial applications, and to alter it and redistribute it freely, 00012 subject to the following restrictions: 00013 00014 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. 00015 2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software. 00016 3. This notice may not be removed or altered from any source distribution. 00017 */ 00018 00019 00020 00021 00022 #include "CcdPhysicsEnvironment.h" 00023 #include "CcdPhysicsController.h" 00024 #include "CcdGraphicController.h" 00025 00026 #include <algorithm> 00027 #include "btBulletDynamicsCommon.h" 00028 #include "LinearMath/btIDebugDraw.h" 00029 #include "BulletCollision/CollisionDispatch/btSimulationIslandManager.h" 00030 #include "BulletSoftBody/btSoftRigidDynamicsWorld.h" 00031 #include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h" 00032 #include "BulletCollision/Gimpact/btGImpactCollisionAlgorithm.h" 00033 00034 //profiling/timings 00035 #include "LinearMath/btQuickprof.h" 00036 00037 00038 #include "PHY_IMotionState.h" 00039 #include "KX_GameObject.h" 00040 #include "RAS_MeshObject.h" 00041 #include "RAS_Polygon.h" 00042 #include "RAS_TexVert.h" 00043 00044 #define CCD_CONSTRAINT_DISABLE_LINKED_COLLISION 0x80 00045 00046 bool useIslands = true; 00047 00048 #ifdef NEW_BULLET_VEHICLE_SUPPORT 00049 #include "BulletDynamics/Vehicle/btRaycastVehicle.h" 00050 #include "BulletDynamics/Vehicle/btVehicleRaycaster.h" 00051 #include "BulletDynamics/Vehicle/btWheelInfo.h" 00052 #include "PHY_IVehicle.h" 00053 btRaycastVehicle::btVehicleTuning gTuning; 00054 00055 #endif //NEW_BULLET_VEHICLE_SUPPORT 00056 #include "LinearMath/btAabbUtil2.h" 00057 #include "MT_Matrix4x4.h" 00058 #include "MT_Vector3.h" 00059 #include "GL/glew.h" 00060 00061 #ifdef WIN32 00062 void DrawRasterizerLine(const float* from,const float* to,int color); 00063 #endif 00064 00065 00066 #include "BulletDynamics/ConstraintSolver/btContactConstraint.h" 00067 00068 00069 #include <stdio.h> 00070 #include <string.h> // for memset 00071 00072 #ifdef NEW_BULLET_VEHICLE_SUPPORT 00073 class WrapperVehicle : public PHY_IVehicle 00074 { 00075 00076 btRaycastVehicle* m_vehicle; 00077 PHY_IPhysicsController* m_chassis; 00078 00079 public: 00080 00081 WrapperVehicle(btRaycastVehicle* vehicle,PHY_IPhysicsController* chassis) 00082 :m_vehicle(vehicle), 00083 m_chassis(chassis) 00084 { 00085 } 00086 00087 btRaycastVehicle* GetVehicle() 00088 { 00089 return m_vehicle; 00090 } 00091 00092 PHY_IPhysicsController* GetChassis() 00093 { 00094 return m_chassis; 00095 } 00096 00097 virtual void AddWheel( 00098 PHY_IMotionState* motionState, 00099 PHY__Vector3 connectionPoint, 00100 PHY__Vector3 downDirection, 00101 PHY__Vector3 axleDirection, 00102 float suspensionRestLength, 00103 float wheelRadius, 00104 bool hasSteering 00105 ) 00106 { 00107 btVector3 connectionPointCS0(connectionPoint[0],connectionPoint[1],connectionPoint[2]); 00108 btVector3 wheelDirectionCS0(downDirection[0],downDirection[1],downDirection[2]); 00109 btVector3 wheelAxle(axleDirection[0],axleDirection[1],axleDirection[2]); 00110 00111 00112 btWheelInfo& info = m_vehicle->addWheel(connectionPointCS0,wheelDirectionCS0,wheelAxle, 00113 suspensionRestLength,wheelRadius,gTuning,hasSteering); 00114 info.m_clientInfo = motionState; 00115 00116 } 00117 00118 void SyncWheels() 00119 { 00120 int numWheels = GetNumWheels(); 00121 int i; 00122 for (i=0;i<numWheels;i++) 00123 { 00124 btWheelInfo& info = m_vehicle->getWheelInfo(i); 00125 PHY_IMotionState* motionState = (PHY_IMotionState*)info.m_clientInfo ; 00126 // m_vehicle->updateWheelTransformsWS(info,false); 00127 m_vehicle->updateWheelTransform(i,false); 00128 btTransform trans = m_vehicle->getWheelInfo(i).m_worldTransform; 00129 btQuaternion orn = trans.getRotation(); 00130 const btVector3& pos = trans.getOrigin(); 00131 motionState->setWorldOrientation(orn.x(),orn.y(),orn.z(),orn[3]); 00132 motionState->setWorldPosition(pos.x(),pos.y(),pos.z()); 00133 00134 } 00135 } 00136 00137 virtual int GetNumWheels() const 00138 { 00139 return m_vehicle->getNumWheels(); 00140 } 00141 00142 virtual void GetWheelPosition(int wheelIndex,float& posX,float& posY,float& posZ) const 00143 { 00144 btTransform trans = m_vehicle->getWheelTransformWS(wheelIndex); 00145 posX = trans.getOrigin().x(); 00146 posY = trans.getOrigin().y(); 00147 posZ = trans.getOrigin().z(); 00148 } 00149 virtual void GetWheelOrientationQuaternion(int wheelIndex,float& quatX,float& quatY,float& quatZ,float& quatW) const 00150 { 00151 btTransform trans = m_vehicle->getWheelTransformWS(wheelIndex); 00152 btQuaternion quat = trans.getRotation(); 00153 btMatrix3x3 orn2(quat); 00154 00155 quatX = trans.getRotation().x(); 00156 quatY = trans.getRotation().y(); 00157 quatZ = trans.getRotation().z(); 00158 quatW = trans.getRotation()[3]; 00159 00160 00161 //printf("test"); 00162 00163 00164 } 00165 00166 virtual float GetWheelRotation(int wheelIndex) const 00167 { 00168 float rotation = 0.f; 00169 00170 if ((wheelIndex>=0) && (wheelIndex< m_vehicle->getNumWheels())) 00171 { 00172 btWheelInfo& info = m_vehicle->getWheelInfo(wheelIndex); 00173 rotation = info.m_rotation; 00174 } 00175 return rotation; 00176 00177 } 00178 00179 00180 00181 virtual int GetUserConstraintId() const 00182 { 00183 return m_vehicle->getUserConstraintId(); 00184 } 00185 00186 virtual int GetUserConstraintType() const 00187 { 00188 return m_vehicle->getUserConstraintType(); 00189 } 00190 00191 virtual void SetSteeringValue(float steering,int wheelIndex) 00192 { 00193 m_vehicle->setSteeringValue(steering,wheelIndex); 00194 } 00195 00196 virtual void ApplyEngineForce(float force,int wheelIndex) 00197 { 00198 m_vehicle->applyEngineForce(force,wheelIndex); 00199 } 00200 00201 virtual void ApplyBraking(float braking,int wheelIndex) 00202 { 00203 if ((wheelIndex>=0) && (wheelIndex< m_vehicle->getNumWheels())) 00204 { 00205 btWheelInfo& info = m_vehicle->getWheelInfo(wheelIndex); 00206 info.m_brake = braking; 00207 } 00208 } 00209 00210 virtual void SetWheelFriction(float friction,int wheelIndex) 00211 { 00212 if ((wheelIndex>=0) && (wheelIndex< m_vehicle->getNumWheels())) 00213 { 00214 btWheelInfo& info = m_vehicle->getWheelInfo(wheelIndex); 00215 info.m_frictionSlip = friction; 00216 } 00217 00218 } 00219 00220 virtual void SetSuspensionStiffness(float suspensionStiffness,int wheelIndex) 00221 { 00222 if ((wheelIndex>=0) && (wheelIndex< m_vehicle->getNumWheels())) 00223 { 00224 btWheelInfo& info = m_vehicle->getWheelInfo(wheelIndex); 00225 info.m_suspensionStiffness = suspensionStiffness; 00226 00227 } 00228 } 00229 00230 virtual void SetSuspensionDamping(float suspensionDamping,int wheelIndex) 00231 { 00232 if ((wheelIndex>=0) && (wheelIndex< m_vehicle->getNumWheels())) 00233 { 00234 btWheelInfo& info = m_vehicle->getWheelInfo(wheelIndex); 00235 info.m_wheelsDampingRelaxation = suspensionDamping; 00236 } 00237 } 00238 00239 virtual void SetSuspensionCompression(float suspensionCompression,int wheelIndex) 00240 { 00241 if ((wheelIndex>=0) && (wheelIndex< m_vehicle->getNumWheels())) 00242 { 00243 btWheelInfo& info = m_vehicle->getWheelInfo(wheelIndex); 00244 info.m_wheelsDampingCompression = suspensionCompression; 00245 } 00246 } 00247 00248 00249 00250 virtual void SetRollInfluence(float rollInfluence,int wheelIndex) 00251 { 00252 if ((wheelIndex>=0) && (wheelIndex< m_vehicle->getNumWheels())) 00253 { 00254 btWheelInfo& info = m_vehicle->getWheelInfo(wheelIndex); 00255 info.m_rollInfluence = rollInfluence; 00256 } 00257 } 00258 00259 virtual void SetCoordinateSystem(int rightIndex,int upIndex,int forwardIndex) 00260 { 00261 m_vehicle->setCoordinateSystem(rightIndex,upIndex,forwardIndex); 00262 } 00263 00264 00265 00266 }; 00267 #endif //NEW_BULLET_VEHICLE_SUPPORT 00268 00269 class CcdOverlapFilterCallBack : public btOverlapFilterCallback 00270 { 00271 private: 00272 class CcdPhysicsEnvironment* m_physEnv; 00273 public: 00274 CcdOverlapFilterCallBack(CcdPhysicsEnvironment* env) : 00275 m_physEnv(env) 00276 { 00277 } 00278 virtual ~CcdOverlapFilterCallBack() 00279 { 00280 } 00281 // return true when pairs need collision 00282 virtual bool needBroadphaseCollision(btBroadphaseProxy* proxy0,btBroadphaseProxy* proxy1) const; 00283 }; 00284 00285 00286 void CcdPhysicsEnvironment::setDebugDrawer(btIDebugDraw* debugDrawer) 00287 { 00288 if (debugDrawer && m_dynamicsWorld) 00289 m_dynamicsWorld->setDebugDrawer(debugDrawer); 00290 m_debugDrawer = debugDrawer; 00291 } 00292 00293 #if 0 00294 static void DrawAabb(btIDebugDraw* debugDrawer,const btVector3& from,const btVector3& to,const btVector3& color) 00295 { 00296 btVector3 halfExtents = (to-from)* 0.5f; 00297 btVector3 center = (to+from) *0.5f; 00298 int i,j; 00299 00300 btVector3 edgecoord(1.f,1.f,1.f),pa,pb; 00301 for (i=0;i<4;i++) 00302 { 00303 for (j=0;j<3;j++) 00304 { 00305 pa = btVector3(edgecoord[0]*halfExtents[0], edgecoord[1]*halfExtents[1], 00306 edgecoord[2]*halfExtents[2]); 00307 pa+=center; 00308 00309 int othercoord = j%3; 00310 edgecoord[othercoord]*=-1.f; 00311 pb = btVector3(edgecoord[0]*halfExtents[0], edgecoord[1]*halfExtents[1], 00312 edgecoord[2]*halfExtents[2]); 00313 pb+=center; 00314 00315 debugDrawer->drawLine(pa,pb,color); 00316 } 00317 edgecoord = btVector3(-1.f,-1.f,-1.f); 00318 if (i<3) 00319 edgecoord[i]*=-1.f; 00320 } 00321 } 00322 #endif 00323 00324 00325 00326 00327 00328 CcdPhysicsEnvironment::CcdPhysicsEnvironment(bool useDbvtCulling,btDispatcher* dispatcher,btOverlappingPairCache* pairCache) 00329 :m_cullingCache(NULL), 00330 m_cullingTree(NULL), 00331 m_numIterations(10), 00332 m_numTimeSubSteps(1), 00333 m_ccdMode(0), 00334 m_solverType(-1), 00335 m_profileTimings(0), 00336 m_enableSatCollisionDetection(false), 00337 m_solver(NULL), 00338 m_ownPairCache(NULL), 00339 m_filterCallback(NULL), 00340 m_ownDispatcher(NULL), 00341 m_scalingPropagated(false) 00342 { 00343 00344 for (int i=0;i<PHY_NUM_RESPONSE;i++) 00345 { 00346 m_triggerCallbacks[i] = 0; 00347 } 00348 00349 // m_collisionConfiguration = new btDefaultCollisionConfiguration(); 00350 m_collisionConfiguration = new btSoftBodyRigidBodyCollisionConfiguration(); 00351 //m_collisionConfiguration->setConvexConvexMultipointIterations(); 00352 00353 if (!dispatcher) 00354 { 00355 btCollisionDispatcher* disp = new btCollisionDispatcher(m_collisionConfiguration); 00356 dispatcher = disp; 00357 btGImpactCollisionAlgorithm::registerAlgorithm(disp); 00358 m_ownDispatcher = dispatcher; 00359 } 00360 00361 //m_broadphase = new btAxisSweep3(btVector3(-1000,-1000,-1000),btVector3(1000,1000,1000)); 00362 //m_broadphase = new btSimpleBroadphase(); 00363 m_broadphase = new btDbvtBroadphase(); 00364 // avoid any collision in the culling tree 00365 if (useDbvtCulling) { 00366 m_cullingCache = new btNullPairCache(); 00367 m_cullingTree = new btDbvtBroadphase(m_cullingCache); 00368 } 00369 00370 m_filterCallback = new CcdOverlapFilterCallBack(this); 00371 m_broadphase->getOverlappingPairCache()->setOverlapFilterCallback(m_filterCallback); 00372 00373 setSolverType(1);//issues with quickstep and memory allocations 00374 // m_dynamicsWorld = new btDiscreteDynamicsWorld(dispatcher,m_broadphase,m_solver,m_collisionConfiguration); 00375 m_dynamicsWorld = new btSoftRigidDynamicsWorld(dispatcher,m_broadphase,m_solver,m_collisionConfiguration); 00376 //m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.01f; 00377 //m_dynamicsWorld->getSolverInfo().m_solverMode= SOLVER_USE_WARMSTARTING + SOLVER_USE_2_FRICTION_DIRECTIONS + SOLVER_RANDMIZE_ORDER + SOLVER_USE_FRICTION_WARMSTARTING; 00378 00379 m_debugDrawer = 0; 00380 setGravity(0.f,0.f,-9.81f); 00381 } 00382 00383 void CcdPhysicsEnvironment::addCcdPhysicsController(CcdPhysicsController* ctrl) 00384 { 00385 btRigidBody* body = ctrl->GetRigidBody(); 00386 btCollisionObject* obj = ctrl->GetCollisionObject(); 00387 00388 //this m_userPointer is just used for triggers, see CallbackTriggers 00389 obj->setUserPointer(ctrl); 00390 if (body) 00391 body->setGravity( m_gravity ); 00392 00393 m_controllers.insert(ctrl); 00394 00395 if (body) 00396 { 00397 //use explicit group/filter for finer control over collision in bullet => near/radar sensor 00398 m_dynamicsWorld->addRigidBody(body, ctrl->GetCollisionFilterGroup(), ctrl->GetCollisionFilterMask()); 00399 } else 00400 { 00401 if (ctrl->GetSoftBody()) 00402 { 00403 btSoftBody* softBody = ctrl->GetSoftBody(); 00404 m_dynamicsWorld->addSoftBody(softBody); 00405 } else 00406 { 00407 if (obj->getCollisionShape()) 00408 { 00409 m_dynamicsWorld->addCollisionObject(obj,ctrl->GetCollisionFilterGroup(), ctrl->GetCollisionFilterMask()); 00410 } 00411 } 00412 } 00413 if (obj->isStaticOrKinematicObject()) 00414 { 00415 obj->setActivationState(ISLAND_SLEEPING); 00416 } 00417 00418 assert(obj->getBroadphaseHandle()); 00419 } 00420 00421 00422 00423 bool CcdPhysicsEnvironment::removeCcdPhysicsController(CcdPhysicsController* ctrl) 00424 { 00425 //also remove constraint 00426 btRigidBody* body = ctrl->GetRigidBody(); 00427 if (body) 00428 { 00429 for (int i=body->getNumConstraintRefs()-1;i>=0;i--) 00430 { 00431 btTypedConstraint* con = body->getConstraintRef(i); 00432 m_dynamicsWorld->removeConstraint(con); 00433 body->removeConstraintRef(con); 00434 //delete con; //might be kept by python KX_ConstraintWrapper 00435 } 00436 m_dynamicsWorld->removeRigidBody(ctrl->GetRigidBody()); 00437 } else 00438 { 00439 //if a softbody 00440 if (ctrl->GetSoftBody()) 00441 { 00442 m_dynamicsWorld->removeSoftBody(ctrl->GetSoftBody()); 00443 } else 00444 { 00445 m_dynamicsWorld->removeCollisionObject(ctrl->GetCollisionObject()); 00446 } 00447 } 00448 if (ctrl->m_registerCount != 0) 00449 printf("Warning: removing controller with non-zero m_registerCount: %d\n", ctrl->m_registerCount); 00450 00451 //remove it from the triggers 00452 m_triggerControllers.erase(ctrl); 00453 00454 return (m_controllers.erase(ctrl) != 0); 00455 } 00456 00457 void CcdPhysicsEnvironment::updateCcdPhysicsController(CcdPhysicsController* ctrl, btScalar newMass, int newCollisionFlags, short int newCollisionGroup, short int newCollisionMask) 00458 { 00459 // this function is used when the collisionning group of a controller is changed 00460 // remove and add the collistioning object 00461 btRigidBody* body = ctrl->GetRigidBody(); 00462 btCollisionObject* obj = ctrl->GetCollisionObject(); 00463 if (obj) 00464 { 00465 btVector3 inertia(0.0,0.0,0.0); 00466 m_dynamicsWorld->removeCollisionObject(obj); 00467 obj->setCollisionFlags(newCollisionFlags); 00468 if (body) 00469 { 00470 if (newMass) 00471 body->getCollisionShape()->calculateLocalInertia(newMass, inertia); 00472 body->setMassProps(newMass, inertia); 00473 m_dynamicsWorld->addRigidBody(body, newCollisionGroup, newCollisionMask); 00474 } 00475 else 00476 { 00477 m_dynamicsWorld->addCollisionObject(obj, newCollisionGroup, newCollisionMask); 00478 } 00479 } 00480 // to avoid nasty interaction, we must update the property of the controller as well 00481 ctrl->m_cci.m_mass = newMass; 00482 ctrl->m_cci.m_collisionFilterGroup = newCollisionGroup; 00483 ctrl->m_cci.m_collisionFilterMask = newCollisionMask; 00484 ctrl->m_cci.m_collisionFlags = newCollisionFlags; 00485 } 00486 00487 void CcdPhysicsEnvironment::enableCcdPhysicsController(CcdPhysicsController* ctrl) 00488 { 00489 if (m_controllers.insert(ctrl).second) 00490 { 00491 btCollisionObject* obj = ctrl->GetCollisionObject(); 00492 obj->setUserPointer(ctrl); 00493 // update the position of the object from the user 00494 if (ctrl->GetMotionState()) 00495 { 00496 btTransform xform = CcdPhysicsController::GetTransformFromMotionState(ctrl->GetMotionState()); 00497 ctrl->SetCenterOfMassTransform(xform); 00498 } 00499 m_dynamicsWorld->addCollisionObject(obj, 00500 ctrl->GetCollisionFilterGroup(), ctrl->GetCollisionFilterMask()); 00501 } 00502 } 00503 00504 void CcdPhysicsEnvironment::disableCcdPhysicsController(CcdPhysicsController* ctrl) 00505 { 00506 if (m_controllers.erase(ctrl)) 00507 { 00508 btRigidBody* body = ctrl->GetRigidBody(); 00509 if (body) 00510 { 00511 m_dynamicsWorld->removeRigidBody(body); 00512 } else 00513 { 00514 if (ctrl->GetSoftBody()) 00515 { 00516 } else 00517 { 00518 m_dynamicsWorld->removeCollisionObject(ctrl->GetCollisionObject()); 00519 } 00520 } 00521 } 00522 } 00523 00524 void CcdPhysicsEnvironment::refreshCcdPhysicsController(CcdPhysicsController* ctrl) 00525 { 00526 btCollisionObject* obj = ctrl->GetCollisionObject(); 00527 if (obj) 00528 { 00529 btBroadphaseProxy* proxy = obj->getBroadphaseHandle(); 00530 if (proxy) 00531 { 00532 m_dynamicsWorld->getPairCache()->cleanProxyFromPairs(proxy,m_dynamicsWorld->getDispatcher()); 00533 } 00534 } 00535 } 00536 00537 void CcdPhysicsEnvironment::addCcdGraphicController(CcdGraphicController* ctrl) 00538 { 00539 if (m_cullingTree && !ctrl->getBroadphaseHandle()) 00540 { 00541 btVector3 minAabb; 00542 btVector3 maxAabb; 00543 ctrl->getAabb(minAabb, maxAabb); 00544 00545 ctrl->setBroadphaseHandle(m_cullingTree->createProxy( 00546 minAabb, 00547 maxAabb, 00548 INVALID_SHAPE_PROXYTYPE, // this parameter is not used 00549 ctrl, 00550 0, // this object does not collision with anything 00551 0, 00552 NULL, // dispatcher => this parameter is not used 00553 0)); 00554 00555 assert(ctrl->getBroadphaseHandle()); 00556 } 00557 } 00558 00559 void CcdPhysicsEnvironment::removeCcdGraphicController(CcdGraphicController* ctrl) 00560 { 00561 if (m_cullingTree) 00562 { 00563 btBroadphaseProxy* bp = ctrl->getBroadphaseHandle(); 00564 if (bp) 00565 { 00566 m_cullingTree->destroyProxy(bp,NULL); 00567 ctrl->setBroadphaseHandle(0); 00568 } 00569 } 00570 } 00571 00572 void CcdPhysicsEnvironment::beginFrame() 00573 { 00574 00575 } 00576 00577 void CcdPhysicsEnvironment::debugDrawWorld() 00578 { 00579 if (m_dynamicsWorld->getDebugDrawer() && m_dynamicsWorld->getDebugDrawer()->getDebugMode() >0) 00580 m_dynamicsWorld->debugDrawWorld(); 00581 } 00582 00583 bool CcdPhysicsEnvironment::proceedDeltaTime(double curTime,float timeStep,float interval) 00584 { 00585 std::set<CcdPhysicsController*>::iterator it; 00586 int i; 00587 00588 for (it=m_controllers.begin(); it!=m_controllers.end(); it++) 00589 { 00590 (*it)->SynchronizeMotionStates(timeStep); 00591 } 00592 00593 float subStep = timeStep / float(m_numTimeSubSteps); 00594 i = m_dynamicsWorld->stepSimulation(interval,25,subStep);//perform always a full simulation step 00595 //uncomment next line to see where Bullet spend its time (printf in console) 00596 //CProfileManager::dumpAll(); 00597 00598 processFhSprings(curTime,i*subStep); 00599 00600 for (it=m_controllers.begin(); it!=m_controllers.end(); it++) 00601 { 00602 (*it)->SynchronizeMotionStates(timeStep); 00603 } 00604 00605 //for (it=m_controllers.begin(); it!=m_controllers.end(); it++) 00606 //{ 00607 // (*it)->SynchronizeMotionStates(timeStep); 00608 //} 00609 00610 for (i=0;i<m_wrapperVehicles.size();i++) 00611 { 00612 WrapperVehicle* veh = m_wrapperVehicles[i]; 00613 veh->SyncWheels(); 00614 } 00615 00616 00617 CallbackTriggers(); 00618 00619 return true; 00620 } 00621 00622 class ClosestRayResultCallbackNotMe : public btCollisionWorld::ClosestRayResultCallback 00623 { 00624 btCollisionObject* m_owner; 00625 btCollisionObject* m_parent; 00626 00627 public: 00628 ClosestRayResultCallbackNotMe(const btVector3& rayFromWorld,const btVector3& rayToWorld,btCollisionObject* owner,btCollisionObject* parent) 00629 :btCollisionWorld::ClosestRayResultCallback(rayFromWorld,rayToWorld), 00630 m_owner(owner), 00631 m_parent(parent) 00632 { 00633 00634 } 00635 00636 virtual bool needsCollision(btBroadphaseProxy* proxy0) const 00637 { 00638 //don't collide with self 00639 if (proxy0->m_clientObject == m_owner) 00640 return false; 00641 00642 if (proxy0->m_clientObject == m_parent) 00643 return false; 00644 00645 return btCollisionWorld::ClosestRayResultCallback::needsCollision(proxy0); 00646 } 00647 00648 }; 00649 00650 void CcdPhysicsEnvironment::processFhSprings(double curTime,float interval) 00651 { 00652 std::set<CcdPhysicsController*>::iterator it; 00653 // dynamic of Fh spring is based on a timestep of 1/60 00654 int numIter = (int)(interval*60.0001f); 00655 00656 for (it=m_controllers.begin(); it!=m_controllers.end(); it++) 00657 { 00658 CcdPhysicsController* ctrl = (*it); 00659 btRigidBody* body = ctrl->GetRigidBody(); 00660 00661 if (body && (ctrl->getConstructionInfo().m_do_fh || ctrl->getConstructionInfo().m_do_rot_fh)) 00662 { 00663 //printf("has Fh or RotFh\n"); 00664 //re-implement SM_FhObject.cpp using btCollisionWorld::rayTest and info from ctrl->getConstructionInfo() 00665 //send a ray from {0.0, 0.0, 0.0} towards {0.0, 0.0, -10.0}, in local coordinates 00666 CcdPhysicsController* parentCtrl = ctrl->getParentCtrl(); 00667 btRigidBody* parentBody = parentCtrl?parentCtrl->GetRigidBody() : 0; 00668 btRigidBody* cl_object = parentBody ? parentBody : body; 00669 00670 if (body->isStaticOrKinematicObject()) 00671 continue; 00672 00673 btVector3 rayDirLocal(0,0,-10); 00674 00675 //m_dynamicsWorld 00676 //ctrl->GetRigidBody(); 00677 btVector3 rayFromWorld = body->getCenterOfMassPosition(); 00678 //btVector3 rayToWorld = rayFromWorld + body->getCenterOfMassTransform().getBasis() * rayDirLocal; 00679 //ray always points down the z axis in world space... 00680 btVector3 rayToWorld = rayFromWorld + rayDirLocal; 00681 00682 ClosestRayResultCallbackNotMe resultCallback(rayFromWorld,rayToWorld,body,parentBody); 00683 00684 m_dynamicsWorld->rayTest(rayFromWorld,rayToWorld,resultCallback); 00685 if (resultCallback.hasHit()) 00686 { 00687 //we hit this one: resultCallback.m_collisionObject; 00688 CcdPhysicsController* controller = static_cast<CcdPhysicsController*>(resultCallback.m_collisionObject->getUserPointer()); 00689 00690 if (controller) 00691 { 00692 if (controller->getConstructionInfo().m_fh_distance < SIMD_EPSILON) 00693 continue; 00694 00695 btRigidBody* hit_object = controller->GetRigidBody(); 00696 if (!hit_object) 00697 continue; 00698 00699 CcdConstructionInfo& hitObjShapeProps = controller->getConstructionInfo(); 00700 00701 float distance = resultCallback.m_closestHitFraction*rayDirLocal.length()-ctrl->getConstructionInfo().m_radius; 00702 if (distance >= hitObjShapeProps.m_fh_distance) 00703 continue; 00704 00705 00706 00707 //btVector3 ray_dir = cl_object->getCenterOfMassTransform().getBasis()* rayDirLocal.normalized(); 00708 btVector3 ray_dir = rayDirLocal.normalized(); 00709 btVector3 normal = resultCallback.m_hitNormalWorld; 00710 normal.normalize(); 00711 00712 for (int i=0; i<numIter; i++) 00713 { 00714 if (ctrl->getConstructionInfo().m_do_fh) 00715 { 00716 btVector3 lspot = cl_object->getCenterOfMassPosition() 00717 + rayDirLocal * resultCallback.m_closestHitFraction; 00718 00719 00720 00721 00722 lspot -= hit_object->getCenterOfMassPosition(); 00723 btVector3 rel_vel = cl_object->getLinearVelocity() - hit_object->getVelocityInLocalPoint(lspot); 00724 btScalar rel_vel_ray = ray_dir.dot(rel_vel); 00725 btScalar spring_extent = 1.0 - distance / hitObjShapeProps.m_fh_distance; 00726 00727 btScalar i_spring = spring_extent * hitObjShapeProps.m_fh_spring; 00728 btScalar i_damp = rel_vel_ray * hitObjShapeProps.m_fh_damping; 00729 00730 cl_object->setLinearVelocity(cl_object->getLinearVelocity() + (-(i_spring + i_damp) * ray_dir)); 00731 if (hitObjShapeProps.m_fh_normal) 00732 { 00733 cl_object->setLinearVelocity(cl_object->getLinearVelocity()+(i_spring + i_damp) *(normal - normal.dot(ray_dir) * ray_dir)); 00734 } 00735 00736 btVector3 lateral = rel_vel - rel_vel_ray * ray_dir; 00737 00738 00739 if (ctrl->getConstructionInfo().m_do_anisotropic) { 00740 //Bullet basis contains no scaling/shear etc. 00741 const btMatrix3x3& lcs = cl_object->getCenterOfMassTransform().getBasis(); 00742 btVector3 loc_lateral = lateral * lcs; 00743 const btVector3& friction_scaling = cl_object->getAnisotropicFriction(); 00744 loc_lateral *= friction_scaling; 00745 lateral = lcs * loc_lateral; 00746 } 00747 00748 btScalar rel_vel_lateral = lateral.length(); 00749 00750 if (rel_vel_lateral > SIMD_EPSILON) { 00751 btScalar friction_factor = hit_object->getFriction();//cl_object->getFriction(); 00752 00753 btScalar max_friction = friction_factor * btMax(btScalar(0.0), i_spring); 00754 00755 btScalar rel_mom_lateral = rel_vel_lateral / cl_object->getInvMass(); 00756 00757 btVector3 friction = (rel_mom_lateral > max_friction) ? 00758 -lateral * (max_friction / rel_vel_lateral) : 00759 -lateral; 00760 00761 cl_object->applyCentralImpulse(friction); 00762 } 00763 } 00764 00765 00766 if (ctrl->getConstructionInfo().m_do_rot_fh) { 00767 btVector3 up2 = cl_object->getWorldTransform().getBasis().getColumn(2); 00768 00769 btVector3 t_spring = up2.cross(normal) * hitObjShapeProps.m_fh_spring; 00770 btVector3 ang_vel = cl_object->getAngularVelocity(); 00771 00772 // only rotations that tilt relative to the normal are damped 00773 ang_vel -= ang_vel.dot(normal) * normal; 00774 00775 btVector3 t_damp = ang_vel * hitObjShapeProps.m_fh_damping; 00776 00777 cl_object->setAngularVelocity(cl_object->getAngularVelocity() + (t_spring - t_damp)); 00778 } 00779 } 00780 } 00781 } 00782 } 00783 } 00784 } 00785 00786 void CcdPhysicsEnvironment::setDebugMode(int debugMode) 00787 { 00788 if (m_debugDrawer){ 00789 m_debugDrawer->setDebugMode(debugMode); 00790 } 00791 } 00792 00793 void CcdPhysicsEnvironment::setNumIterations(int numIter) 00794 { 00795 m_numIterations = numIter; 00796 } 00797 void CcdPhysicsEnvironment::setDeactivationTime(float dTime) 00798 { 00799 gDeactivationTime = dTime; 00800 } 00801 void CcdPhysicsEnvironment::setDeactivationLinearTreshold(float linTresh) 00802 { 00803 gLinearSleepingTreshold = linTresh; 00804 } 00805 void CcdPhysicsEnvironment::setDeactivationAngularTreshold(float angTresh) 00806 { 00807 gAngularSleepingTreshold = angTresh; 00808 } 00809 00810 void CcdPhysicsEnvironment::setContactBreakingTreshold(float contactBreakingTreshold) 00811 { 00812 gContactBreakingThreshold = contactBreakingTreshold; 00813 00814 } 00815 00816 00817 void CcdPhysicsEnvironment::setCcdMode(int ccdMode) 00818 { 00819 m_ccdMode = ccdMode; 00820 } 00821 00822 00823 void CcdPhysicsEnvironment::setSolverSorConstant(float sor) 00824 { 00825 m_solverInfo.m_sor = sor; 00826 } 00827 00828 void CcdPhysicsEnvironment::setSolverTau(float tau) 00829 { 00830 m_solverInfo.m_tau = tau; 00831 } 00832 void CcdPhysicsEnvironment::setSolverDamping(float damping) 00833 { 00834 m_solverInfo.m_damping = damping; 00835 } 00836 00837 00838 void CcdPhysicsEnvironment::setLinearAirDamping(float damping) 00839 { 00840 //gLinearAirDamping = damping; 00841 } 00842 00843 void CcdPhysicsEnvironment::setUseEpa(bool epa) 00844 { 00845 //gUseEpa = epa; 00846 } 00847 00848 void CcdPhysicsEnvironment::setSolverType(int solverType) 00849 { 00850 00851 switch (solverType) 00852 { 00853 case 1: 00854 { 00855 if (m_solverType != solverType) 00856 { 00857 00858 m_solver = new btSequentialImpulseConstraintSolver(); 00859 00860 00861 break; 00862 } 00863 } 00864 00865 case 0: 00866 default: 00867 if (m_solverType != solverType) 00868 { 00869 // m_solver = new OdeConstraintSolver(); 00870 00871 break; 00872 } 00873 00874 }; 00875 00876 m_solverType = solverType ; 00877 } 00878 00879 00880 00881 void CcdPhysicsEnvironment::getGravity(PHY__Vector3& grav) 00882 { 00883 const btVector3& gravity = m_dynamicsWorld->getGravity(); 00884 grav[0] = gravity.getX(); 00885 grav[1] = gravity.getY(); 00886 grav[2] = gravity.getZ(); 00887 } 00888 00889 00890 void CcdPhysicsEnvironment::setGravity(float x,float y,float z) 00891 { 00892 m_gravity = btVector3(x,y,z); 00893 m_dynamicsWorld->setGravity(m_gravity); 00894 m_dynamicsWorld->getWorldInfo().m_gravity.setValue(x,y,z); 00895 } 00896 00897 00898 00899 00900 static int gConstraintUid = 1; 00901 00902 //Following the COLLADA physics specification for constraints 00903 int CcdPhysicsEnvironment::createUniversalD6Constraint( 00904 class PHY_IPhysicsController* ctrlRef,class PHY_IPhysicsController* ctrlOther, 00905 btTransform& frameInA, 00906 btTransform& frameInB, 00907 const btVector3& linearMinLimits, 00908 const btVector3& linearMaxLimits, 00909 const btVector3& angularMinLimits, 00910 const btVector3& angularMaxLimits,int flags 00911 ) 00912 { 00913 00914 bool disableCollisionBetweenLinkedBodies = (0!=(flags & CCD_CONSTRAINT_DISABLE_LINKED_COLLISION)); 00915 00916 //we could either add some logic to recognize ball-socket and hinge, or let that up to the user 00917 //perhaps some warning or hint that hinge/ball-socket is more efficient? 00918 00919 00920 btGeneric6DofConstraint* genericConstraint = 0; 00921 CcdPhysicsController* ctrl0 = (CcdPhysicsController*) ctrlRef; 00922 CcdPhysicsController* ctrl1 = (CcdPhysicsController*) ctrlOther; 00923 00924 btRigidBody* rb0 = ctrl0->GetRigidBody(); 00925 btRigidBody* rb1 = ctrl1->GetRigidBody(); 00926 00927 if (rb1) 00928 { 00929 00930 00931 bool useReferenceFrameA = true; 00932 genericConstraint = new btGeneric6DofSpringConstraint( 00933 *rb0,*rb1, 00934 frameInA,frameInB,useReferenceFrameA); 00935 genericConstraint->setLinearLowerLimit(linearMinLimits); 00936 genericConstraint->setLinearUpperLimit(linearMaxLimits); 00937 genericConstraint->setAngularLowerLimit(angularMinLimits); 00938 genericConstraint->setAngularUpperLimit(angularMaxLimits); 00939 } else 00940 { 00941 // TODO: Implement single body case... 00942 //No, we can use a fixed rigidbody in above code, rather than unnecessary duplation of code 00943 00944 } 00945 00946 if (genericConstraint) 00947 { 00948 // m_constraints.push_back(genericConstraint); 00949 m_dynamicsWorld->addConstraint(genericConstraint,disableCollisionBetweenLinkedBodies); 00950 00951 genericConstraint->setUserConstraintId(gConstraintUid++); 00952 genericConstraint->setUserConstraintType(PHY_GENERIC_6DOF_CONSTRAINT); 00953 //64 bit systems can't cast pointer to int. could use size_t instead. 00954 return genericConstraint->getUserConstraintId(); 00955 } 00956 return 0; 00957 } 00958 00959 00960 00961 void CcdPhysicsEnvironment::removeConstraint(int constraintId) 00962 { 00963 00964 int i; 00965 int numConstraints = m_dynamicsWorld->getNumConstraints(); 00966 for (i=0;i<numConstraints;i++) 00967 { 00968 btTypedConstraint* constraint = m_dynamicsWorld->getConstraint(i); 00969 if (constraint->getUserConstraintId() == constraintId) 00970 { 00971 constraint->getRigidBodyA().activate(); 00972 constraint->getRigidBodyB().activate(); 00973 m_dynamicsWorld->removeConstraint(constraint); 00974 break; 00975 } 00976 } 00977 } 00978 00979 00980 struct FilterClosestRayResultCallback : public btCollisionWorld::ClosestRayResultCallback 00981 { 00982 PHY_IRayCastFilterCallback& m_phyRayFilter; 00983 const btCollisionShape* m_hitTriangleShape; 00984 int m_hitTriangleIndex; 00985 00986 00987 FilterClosestRayResultCallback (PHY_IRayCastFilterCallback& phyRayFilter,const btVector3& rayFrom,const btVector3& rayTo) 00988 : btCollisionWorld::ClosestRayResultCallback(rayFrom,rayTo), 00989 m_phyRayFilter(phyRayFilter), 00990 m_hitTriangleShape(NULL), 00991 m_hitTriangleIndex(0) 00992 { 00993 } 00994 00995 virtual ~FilterClosestRayResultCallback() 00996 { 00997 } 00998 00999 virtual bool needsCollision(btBroadphaseProxy* proxy0) const 01000 { 01001 if (!(proxy0->m_collisionFilterGroup & m_collisionFilterMask)) 01002 return false; 01003 if (!(m_collisionFilterGroup & proxy0->m_collisionFilterMask)) 01004 return false; 01005 btCollisionObject* object = (btCollisionObject*)proxy0->m_clientObject; 01006 CcdPhysicsController* phyCtrl = static_cast<CcdPhysicsController*>(object->getUserPointer()); 01007 if (phyCtrl == m_phyRayFilter.m_ignoreController) 01008 return false; 01009 return m_phyRayFilter.needBroadphaseRayCast(phyCtrl); 01010 } 01011 01012 virtual btScalar addSingleResult(btCollisionWorld::LocalRayResult& rayResult,bool normalInWorldSpace) 01013 { 01014 //CcdPhysicsController* curHit = static_cast<CcdPhysicsController*>(rayResult.m_collisionObject->getUserPointer()); 01015 // save shape information as ClosestRayResultCallback::AddSingleResult() does not do it 01016 if (rayResult.m_localShapeInfo) 01017 { 01018 m_hitTriangleShape = rayResult.m_collisionObject->getCollisionShape(); 01019 m_hitTriangleIndex = rayResult.m_localShapeInfo->m_triangleIndex; 01020 } else 01021 { 01022 m_hitTriangleShape = NULL; 01023 m_hitTriangleIndex = 0; 01024 } 01025 return ClosestRayResultCallback::addSingleResult(rayResult,normalInWorldSpace); 01026 } 01027 01028 }; 01029 01030 static bool GetHitTriangle(btCollisionShape* shape, CcdShapeConstructionInfo* shapeInfo, int hitTriangleIndex, btVector3 triangle[]) 01031 { 01032 // this code is copied from Bullet 01033 const unsigned char *vertexbase; 01034 int numverts; 01035 PHY_ScalarType type; 01036 int stride; 01037 const unsigned char *indexbase; 01038 int indexstride; 01039 int numfaces; 01040 PHY_ScalarType indicestype; 01041 btStridingMeshInterface* meshInterface = NULL; 01042 btTriangleMeshShape* triangleShape = shapeInfo->GetMeshShape(); 01043 01044 if (triangleShape) 01045 meshInterface = triangleShape->getMeshInterface(); 01046 else 01047 { 01048 // other possibility is gImpact 01049 if (shape->getShapeType() == GIMPACT_SHAPE_PROXYTYPE) 01050 meshInterface = (static_cast<btGImpactMeshShape*>(shape))->getMeshInterface(); 01051 } 01052 if (!meshInterface) 01053 return false; 01054 01055 meshInterface->getLockedReadOnlyVertexIndexBase( 01056 &vertexbase, 01057 numverts, 01058 type, 01059 stride, 01060 &indexbase, 01061 indexstride, 01062 numfaces, 01063 indicestype, 01064 0); 01065 01066 unsigned int* gfxbase = (unsigned int*)(indexbase+hitTriangleIndex*indexstride); 01067 const btVector3& meshScaling = shape->getLocalScaling(); 01068 for (int j=2;j>=0;j--) 01069 { 01070 int graphicsindex = indicestype==PHY_SHORT?((unsigned short*)gfxbase)[j]:gfxbase[j]; 01071 01072 btScalar* graphicsbase = (btScalar*)(vertexbase+graphicsindex*stride); 01073 01074 triangle[j] = btVector3(graphicsbase[0]*meshScaling.getX(),graphicsbase[1]*meshScaling.getY(),graphicsbase[2]*meshScaling.getZ()); 01075 } 01076 meshInterface->unLockReadOnlyVertexBase(0); 01077 return true; 01078 } 01079 01080 PHY_IPhysicsController* CcdPhysicsEnvironment::rayTest(PHY_IRayCastFilterCallback &filterCallback, float fromX,float fromY,float fromZ, float toX,float toY,float toZ) 01081 { 01082 btVector3 rayFrom(fromX,fromY,fromZ); 01083 btVector3 rayTo(toX,toY,toZ); 01084 01085 btVector3 hitPointWorld,normalWorld; 01086 01087 //Either Ray Cast with or without filtering 01088 01089 //btCollisionWorld::ClosestRayResultCallback rayCallback(rayFrom,rayTo); 01090 FilterClosestRayResultCallback rayCallback(filterCallback,rayFrom,rayTo); 01091 01092 01093 PHY_RayCastResult result; 01094 memset(&result, 0, sizeof(result)); 01095 01096 // don't collision with sensor object 01097 rayCallback.m_collisionFilterMask = CcdConstructionInfo::AllFilter ^ CcdConstructionInfo::SensorFilter; 01098 //, ,filterCallback.m_faceNormal); 01099 01100 m_dynamicsWorld->rayTest(rayFrom,rayTo,rayCallback); 01101 if (rayCallback.hasHit()) 01102 { 01103 CcdPhysicsController* controller = static_cast<CcdPhysicsController*>(rayCallback.m_collisionObject->getUserPointer()); 01104 result.m_controller = controller; 01105 result.m_hitPoint[0] = rayCallback.m_hitPointWorld.getX(); 01106 result.m_hitPoint[1] = rayCallback.m_hitPointWorld.getY(); 01107 result.m_hitPoint[2] = rayCallback.m_hitPointWorld.getZ(); 01108 01109 if (rayCallback.m_hitTriangleShape != NULL) 01110 { 01111 // identify the mesh polygon 01112 CcdShapeConstructionInfo* shapeInfo = controller->m_shapeInfo; 01113 if (shapeInfo) 01114 { 01115 btCollisionShape* shape = controller->GetCollisionObject()->getCollisionShape(); 01116 if (shape->isCompound()) 01117 { 01118 btCompoundShape* compoundShape = (btCompoundShape*)shape; 01119 CcdShapeConstructionInfo* compoundShapeInfo = shapeInfo; 01120 // need to search which sub-shape has been hit 01121 for (int i=0; i<compoundShape->getNumChildShapes(); i++) 01122 { 01123 shapeInfo = compoundShapeInfo->GetChildShape(i); 01124 shape=compoundShape->getChildShape(i); 01125 if (shape == rayCallback.m_hitTriangleShape) 01126 break; 01127 } 01128 } 01129 if (shape == rayCallback.m_hitTriangleShape && 01130 rayCallback.m_hitTriangleIndex < shapeInfo->m_polygonIndexArray.size()) 01131 { 01132 // save original collision shape triangle for soft body 01133 int hitTriangleIndex = rayCallback.m_hitTriangleIndex; 01134 01135 result.m_meshObject = shapeInfo->GetMesh(); 01136 if (shape->isSoftBody()) 01137 { 01138 // soft body using different face numbering because of randomization 01139 // hopefully we have stored the original face number in m_tag 01140 btSoftBody* softBody = static_cast<btSoftBody*>(rayCallback.m_collisionObject); 01141 if (softBody->m_faces[hitTriangleIndex].m_tag != 0) 01142 { 01143 rayCallback.m_hitTriangleIndex = (int)((uintptr_t)(softBody->m_faces[hitTriangleIndex].m_tag)-1); 01144 } 01145 } 01146 // retrieve the original mesh polygon (in case of quad->tri conversion) 01147 result.m_polygon = shapeInfo->m_polygonIndexArray.at(rayCallback.m_hitTriangleIndex); 01148 // hit triangle in world coordinate, for face normal and UV coordinate 01149 btVector3 triangle[3]; 01150 bool triangleOK = false; 01151 if (filterCallback.m_faceUV && (3*rayCallback.m_hitTriangleIndex) < shapeInfo->m_triFaceUVcoArray.size()) 01152 { 01153 // interpolate the UV coordinate of the hit point 01154 CcdShapeConstructionInfo::UVco* uvCo = &shapeInfo->m_triFaceUVcoArray[3*rayCallback.m_hitTriangleIndex]; 01155 // 1. get the 3 coordinate of the triangle in world space 01156 btVector3 v1, v2, v3; 01157 if (shape->isSoftBody()) 01158 { 01159 // soft body give points directly in world coordinate 01160 btSoftBody* softBody = static_cast<btSoftBody*>(rayCallback.m_collisionObject); 01161 v1 = softBody->m_faces[hitTriangleIndex].m_n[0]->m_x; 01162 v2 = softBody->m_faces[hitTriangleIndex].m_n[1]->m_x; 01163 v3 = softBody->m_faces[hitTriangleIndex].m_n[2]->m_x; 01164 } else 01165 { 01166 // for rigid body we must apply the world transform 01167 triangleOK = GetHitTriangle(shape, shapeInfo, hitTriangleIndex, triangle); 01168 if (!triangleOK) 01169 // if we cannot get the triangle, no use to continue 01170 goto SKIP_UV_NORMAL; 01171 v1 = rayCallback.m_collisionObject->getWorldTransform()(triangle[0]); 01172 v2 = rayCallback.m_collisionObject->getWorldTransform()(triangle[1]); 01173 v3 = rayCallback.m_collisionObject->getWorldTransform()(triangle[2]); 01174 } 01175 // 2. compute barycentric coordinate of the hit point 01176 btVector3 v = v2-v1; 01177 btVector3 w = v3-v1; 01178 btVector3 u = v.cross(w); 01179 btScalar A = u.length(); 01180 01181 v = v2-rayCallback.m_hitPointWorld; 01182 w = v3-rayCallback.m_hitPointWorld; 01183 u = v.cross(w); 01184 btScalar A1 = u.length(); 01185 01186 v = rayCallback.m_hitPointWorld-v1; 01187 w = v3-v1; 01188 u = v.cross(w); 01189 btScalar A2 = u.length(); 01190 01191 btVector3 baryCo; 01192 baryCo.setX(A1/A); 01193 baryCo.setY(A2/A); 01194 baryCo.setZ(1.0f-baryCo.getX()-baryCo.getY()); 01195 // 3. compute UV coordinate 01196 result.m_hitUV[0] = baryCo.getX()*uvCo[0].uv[0] + baryCo.getY()*uvCo[1].uv[0] + baryCo.getZ()*uvCo[2].uv[0]; 01197 result.m_hitUV[1] = baryCo.getX()*uvCo[0].uv[1] + baryCo.getY()*uvCo[1].uv[1] + baryCo.getZ()*uvCo[2].uv[1]; 01198 result.m_hitUVOK = 1; 01199 } 01200 01201 // Bullet returns the normal from "outside". 01202 // If the user requests the real normal, compute it now 01203 if (filterCallback.m_faceNormal) 01204 { 01205 if (shape->isSoftBody()) 01206 { 01207 // we can get the real normal directly from the body 01208 btSoftBody* softBody = static_cast<btSoftBody*>(rayCallback.m_collisionObject); 01209 rayCallback.m_hitNormalWorld = softBody->m_faces[hitTriangleIndex].m_normal; 01210 } else 01211 { 01212 if (!triangleOK) 01213 triangleOK = GetHitTriangle(shape, shapeInfo, hitTriangleIndex, triangle); 01214 if (triangleOK) 01215 { 01216 btVector3 triangleNormal; 01217 triangleNormal = (triangle[1]-triangle[0]).cross(triangle[2]-triangle[0]); 01218 rayCallback.m_hitNormalWorld = rayCallback.m_collisionObject->getWorldTransform().getBasis()*triangleNormal; 01219 } 01220 } 01221 } 01222 SKIP_UV_NORMAL: 01223 ; 01224 } 01225 } 01226 } 01227 if (rayCallback.m_hitNormalWorld.length2() > (SIMD_EPSILON*SIMD_EPSILON)) 01228 { 01229 rayCallback.m_hitNormalWorld.normalize(); 01230 } else 01231 { 01232 rayCallback.m_hitNormalWorld.setValue(1,0,0); 01233 } 01234 result.m_hitNormal[0] = rayCallback.m_hitNormalWorld.getX(); 01235 result.m_hitNormal[1] = rayCallback.m_hitNormalWorld.getY(); 01236 result.m_hitNormal[2] = rayCallback.m_hitNormalWorld.getZ(); 01237 filterCallback.reportHit(&result); 01238 } 01239 01240 01241 return result.m_controller; 01242 } 01243 01244 // Handles occlusion culling. 01245 // The implementation is based on the CDTestFramework 01246 struct OcclusionBuffer 01247 { 01248 struct WriteOCL 01249 { 01250 static inline bool Process(btScalar& q,btScalar v) { if(q<v) q=v;return(false); } 01251 static inline void Occlusion(bool& flag) { flag = true; } 01252 }; 01253 struct QueryOCL 01254 { 01255 static inline bool Process(btScalar& q,btScalar v) { return(q<=v); } 01256 static inline void Occlusion(bool& flag) { } 01257 }; 01258 btScalar* m_buffer; 01259 size_t m_bufferSize; 01260 bool m_initialized; 01261 bool m_occlusion; 01262 int m_sizes[2]; 01263 btScalar m_scales[2]; 01264 btScalar m_offsets[2]; 01265 btScalar m_wtc[16]; // world to clip transform 01266 btScalar m_mtc[16]; // model to clip transform 01267 // constructor: size=largest dimension of the buffer. 01268 // Buffer size depends on aspect ratio 01269 OcclusionBuffer() 01270 { 01271 m_initialized=false; 01272 m_occlusion = false; 01273 m_buffer = NULL; 01274 m_bufferSize = 0; 01275 } 01276 // multiplication of column major matrices: m=m1*m2 01277 template<typename T1, typename T2> 01278 void CMmat4mul(btScalar* m, const T1* m1, const T2* m2) 01279 { 01280 m[ 0] = btScalar(m1[ 0]*m2[ 0]+m1[ 4]*m2[ 1]+m1[ 8]*m2[ 2]+m1[12]*m2[ 3]); 01281 m[ 1] = btScalar(m1[ 1]*m2[ 0]+m1[ 5]*m2[ 1]+m1[ 9]*m2[ 2]+m1[13]*m2[ 3]); 01282 m[ 2] = btScalar(m1[ 2]*m2[ 0]+m1[ 6]*m2[ 1]+m1[10]*m2[ 2]+m1[14]*m2[ 3]); 01283 m[ 3] = btScalar(m1[ 3]*m2[ 0]+m1[ 7]*m2[ 1]+m1[11]*m2[ 2]+m1[15]*m2[ 3]); 01284 01285 m[ 4] = btScalar(m1[ 0]*m2[ 4]+m1[ 4]*m2[ 5]+m1[ 8]*m2[ 6]+m1[12]*m2[ 7]); 01286 m[ 5] = btScalar(m1[ 1]*m2[ 4]+m1[ 5]*m2[ 5]+m1[ 9]*m2[ 6]+m1[13]*m2[ 7]); 01287 m[ 6] = btScalar(m1[ 2]*m2[ 4]+m1[ 6]*m2[ 5]+m1[10]*m2[ 6]+m1[14]*m2[ 7]); 01288 m[ 7] = btScalar(m1[ 3]*m2[ 4]+m1[ 7]*m2[ 5]+m1[11]*m2[ 6]+m1[15]*m2[ 7]); 01289 01290 m[ 8] = btScalar(m1[ 0]*m2[ 8]+m1[ 4]*m2[ 9]+m1[ 8]*m2[10]+m1[12]*m2[11]); 01291 m[ 9] = btScalar(m1[ 1]*m2[ 8]+m1[ 5]*m2[ 9]+m1[ 9]*m2[10]+m1[13]*m2[11]); 01292 m[10] = btScalar(m1[ 2]*m2[ 8]+m1[ 6]*m2[ 9]+m1[10]*m2[10]+m1[14]*m2[11]); 01293 m[11] = btScalar(m1[ 3]*m2[ 8]+m1[ 7]*m2[ 9]+m1[11]*m2[10]+m1[15]*m2[11]); 01294 01295 m[12] = btScalar(m1[ 0]*m2[12]+m1[ 4]*m2[13]+m1[ 8]*m2[14]+m1[12]*m2[15]); 01296 m[13] = btScalar(m1[ 1]*m2[12]+m1[ 5]*m2[13]+m1[ 9]*m2[14]+m1[13]*m2[15]); 01297 m[14] = btScalar(m1[ 2]*m2[12]+m1[ 6]*m2[13]+m1[10]*m2[14]+m1[14]*m2[15]); 01298 m[15] = btScalar(m1[ 3]*m2[12]+m1[ 7]*m2[13]+m1[11]*m2[14]+m1[15]*m2[15]); 01299 } 01300 void setup(int size) 01301 { 01302 m_initialized=false; 01303 m_occlusion=false; 01304 // compute the size of the buffer 01305 GLint v[4]; 01306 GLdouble m[16],p[16]; 01307 int maxsize; 01308 double ratio; 01309 glGetIntegerv(GL_VIEWPORT,v); 01310 maxsize = (v[2] > v[3]) ? v[2] : v[3]; 01311 assert(maxsize > 0); 01312 ratio = 1.0/(2*maxsize); 01313 // ensure even number 01314 m_sizes[0] = 2*((int)(size*v[2]*ratio+0.5)); 01315 m_sizes[1] = 2*((int)(size*v[3]*ratio+0.5)); 01316 m_scales[0]=btScalar(m_sizes[0]/2); 01317 m_scales[1]=btScalar(m_sizes[1]/2); 01318 m_offsets[0]=m_scales[0]+0.5f; 01319 m_offsets[1]=m_scales[1]+0.5f; 01320 // prepare matrix 01321 // at this time of the rendering, the modelview matrix is the 01322 // world to camera transformation and the projection matrix is 01323 // camera to clip transformation. combine both so that 01324 glGetDoublev(GL_MODELVIEW_MATRIX,m); 01325 glGetDoublev(GL_PROJECTION_MATRIX,p); 01326 CMmat4mul(m_wtc,p,m); 01327 } 01328 void initialize() 01329 { 01330 size_t newsize = (m_sizes[0]*m_sizes[1])*sizeof(btScalar); 01331 if (m_buffer) 01332 { 01333 // see if we can reuse 01334 if (newsize > m_bufferSize) 01335 { 01336 free(m_buffer); 01337 m_buffer = NULL; 01338 m_bufferSize = 0; 01339 } 01340 } 01341 if (!m_buffer) 01342 { 01343 m_buffer = (btScalar*)calloc(1, newsize); 01344 m_bufferSize = newsize; 01345 } else 01346 { 01347 // buffer exists already, just clears it 01348 memset(m_buffer, 0, newsize); 01349 } 01350 // memory allocate must succeed 01351 assert(m_buffer != NULL); 01352 m_initialized = true; 01353 m_occlusion = false; 01354 } 01355 void SetModelMatrix(double *fl) 01356 { 01357 CMmat4mul(m_mtc,m_wtc,fl); 01358 if (!m_initialized) 01359 initialize(); 01360 } 01361 01362 // transform a segment in world coordinate to clip coordinate 01363 void transformW(const btVector3& x, btVector4& t) 01364 { 01365 t[0] = x[0]*m_wtc[0]+x[1]*m_wtc[4]+x[2]*m_wtc[8]+m_wtc[12]; 01366 t[1] = x[0]*m_wtc[1]+x[1]*m_wtc[5]+x[2]*m_wtc[9]+m_wtc[13]; 01367 t[2] = x[0]*m_wtc[2]+x[1]*m_wtc[6]+x[2]*m_wtc[10]+m_wtc[14]; 01368 t[3] = x[0]*m_wtc[3]+x[1]*m_wtc[7]+x[2]*m_wtc[11]+m_wtc[15]; 01369 } 01370 void transformM(const float* x, btVector4& t) 01371 { 01372 t[0] = x[0]*m_mtc[0]+x[1]*m_mtc[4]+x[2]*m_mtc[8]+m_mtc[12]; 01373 t[1] = x[0]*m_mtc[1]+x[1]*m_mtc[5]+x[2]*m_mtc[9]+m_mtc[13]; 01374 t[2] = x[0]*m_mtc[2]+x[1]*m_mtc[6]+x[2]*m_mtc[10]+m_mtc[14]; 01375 t[3] = x[0]*m_mtc[3]+x[1]*m_mtc[7]+x[2]*m_mtc[11]+m_mtc[15]; 01376 } 01377 // convert polygon to device coordinates 01378 static bool project(btVector4* p,int n) 01379 { 01380 for(int i=0;i<n;++i) 01381 { 01382 p[i][2]=1/p[i][3]; 01383 p[i][0]*=p[i][2]; 01384 p[i][1]*=p[i][2]; 01385 } 01386 return(true); 01387 } 01388 // pi: closed polygon in clip coordinate, NP = number of segments 01389 // po: same polygon with clipped segments removed 01390 template <const int NP> 01391 static int clip(const btVector4* pi,btVector4* po) 01392 { 01393 btScalar s[2*NP]; 01394 btVector4 pn[2*NP]; 01395 int i, j, m, n, ni; 01396 // deal with near clipping 01397 for(i=0, m=0;i<NP;++i) 01398 { 01399 s[i]=pi[i][2]+pi[i][3]; 01400 if(s[i]<0) m+=1<<i; 01401 } 01402 if(m==((1<<NP)-1)) 01403 return(0); 01404 if(m!=0) 01405 { 01406 for(i=NP-1,j=0,n=0;j<NP;i=j++) 01407 { 01408 const btVector4& a=pi[i]; 01409 const btVector4& b=pi[j]; 01410 const btScalar t=s[i]/(a[3]+a[2]-b[3]-b[2]); 01411 if((t>0)&&(t<1)) 01412 { 01413 pn[n][0] = a[0]+(b[0]-a[0])*t; 01414 pn[n][1] = a[1]+(b[1]-a[1])*t; 01415 pn[n][2] = a[2]+(b[2]-a[2])*t; 01416 pn[n][3] = a[3]+(b[3]-a[3])*t; 01417 ++n; 01418 } 01419 if(s[j]>0) pn[n++]=b; 01420 } 01421 // ready to test far clipping, start from the modified polygon 01422 pi = pn; 01423 ni = n; 01424 } else 01425 { 01426 // no clipping on the near plane, keep same vector 01427 ni = NP; 01428 } 01429 // now deal with far clipping 01430 for(i=0, m=0;i<ni;++i) 01431 { 01432 s[i]=pi[i][2]-pi[i][3]; 01433 if(s[i]>0) m+=1<<i; 01434 } 01435 if(m==((1<<ni)-1)) 01436 return(0); 01437 if(m!=0) 01438 { 01439 for(i=ni-1,j=0,n=0;j<ni;i=j++) 01440 { 01441 const btVector4& a=pi[i]; 01442 const btVector4& b=pi[j]; 01443 const btScalar t=s[i]/(a[2]-a[3]-b[2]+b[3]); 01444 if((t>0)&&(t<1)) 01445 { 01446 po[n][0] = a[0]+(b[0]-a[0])*t; 01447 po[n][1] = a[1]+(b[1]-a[1])*t; 01448 po[n][2] = a[2]+(b[2]-a[2])*t; 01449 po[n][3] = a[3]+(b[3]-a[3])*t; 01450 ++n; 01451 } 01452 if(s[j]<0) po[n++]=b; 01453 } 01454 return(n); 01455 } 01456 for(int i=0;i<ni;++i) po[i]=pi[i]; 01457 return(ni); 01458 } 01459 // write or check a triangle to buffer. a,b,c in device coordinates (-1,+1) 01460 template <typename POLICY> 01461 inline bool draw( const btVector4& a, 01462 const btVector4& b, 01463 const btVector4& c, 01464 const float face, 01465 const btScalar minarea) 01466 { 01467 const btScalar a2=btCross(b-a,c-a)[2]; 01468 if((face*a2)<0.f || btFabs(a2)<minarea) 01469 return false; 01470 // further down we are normally going to write to the Zbuffer, mark it so 01471 POLICY::Occlusion(m_occlusion); 01472 01473 int x[3], y[3], ib=1, ic=2; 01474 btScalar z[3]; 01475 x[0]=(int)(a.x()*m_scales[0]+m_offsets[0]); 01476 y[0]=(int)(a.y()*m_scales[1]+m_offsets[1]); 01477 z[0]=a.z(); 01478 if (a2 < 0.f) 01479 { 01480 // negative aire is possible with double face => must 01481 // change the order of b and c otherwise the algorithm doesn't work 01482 ib=2; 01483 ic=1; 01484 } 01485 x[ib]=(int)(b.x()*m_scales[0]+m_offsets[0]); 01486 x[ic]=(int)(c.x()*m_scales[0]+m_offsets[0]); 01487 y[ib]=(int)(b.y()*m_scales[1]+m_offsets[1]); 01488 y[ic]=(int)(c.y()*m_scales[1]+m_offsets[1]); 01489 z[ib]=b.z(); 01490 z[ic]=c.z(); 01491 const int mix=btMax(0,btMin(x[0],btMin(x[1],x[2]))); 01492 const int mxx=btMin(m_sizes[0],1+btMax(x[0],btMax(x[1],x[2]))); 01493 const int miy=btMax(0,btMin(y[0],btMin(y[1],y[2]))); 01494 const int mxy=btMin(m_sizes[1],1+btMax(y[0],btMax(y[1],y[2]))); 01495 const int width=mxx-mix; 01496 const int height=mxy-miy; 01497 if ((width*height) <= 1) 01498 { 01499 // degenerated in at most one single pixel 01500 btScalar* scan=&m_buffer[miy*m_sizes[0]+mix]; 01501 // use for loop to detect the case where width or height == 0 01502 for(int iy=miy;iy<mxy;++iy) 01503 { 01504 for(int ix=mix;ix<mxx;++ix) 01505 { 01506 if(POLICY::Process(*scan,z[0])) 01507 return(true); 01508 if(POLICY::Process(*scan,z[1])) 01509 return(true); 01510 if(POLICY::Process(*scan,z[2])) 01511 return(true); 01512 } 01513 } 01514 } else if (width == 1) 01515 { 01516 // Degenerated in at least 2 vertical lines 01517 // The algorithm below doesn't work when face has a single pixel width 01518 // We cannot use general formulas because the plane is degenerated. 01519 // We have to interpolate along the 3 edges that overlaps and process each pixel. 01520 // sort the y coord to make formula simpler 01521 int ytmp; 01522 btScalar ztmp; 01523 if (y[0] > y[1]) { ytmp=y[1];y[1]=y[0];y[0]=ytmp;ztmp=z[1];z[1]=z[0];z[0]=ztmp; } 01524 if (y[0] > y[2]) { ytmp=y[2];y[2]=y[0];y[0]=ytmp;ztmp=z[2];z[2]=z[0];z[0]=ztmp; } 01525 if (y[1] > y[2]) { ytmp=y[2];y[2]=y[1];y[1]=ytmp;ztmp=z[2];z[2]=z[1];z[1]=ztmp; } 01526 int dy[]={ y[0]-y[1], 01527 y[1]-y[2], 01528 y[2]-y[0]}; 01529 btScalar dzy[3]; 01530 dzy[0] = (dy[0]) ? (z[0]-z[1])/dy[0] : btScalar(0.f); 01531 dzy[1] = (dy[1]) ? (z[1]-z[2])/dy[1] : btScalar(0.f); 01532 dzy[2] = (dy[2]) ? (z[2]-z[0])/dy[2] : btScalar(0.f); 01533 btScalar v[3] = { dzy[0]*(miy-y[0])+z[0], 01534 dzy[1]*(miy-y[1])+z[1], 01535 dzy[2]*(miy-y[2])+z[2] }; 01536 dy[0] = y[1]-y[0]; 01537 dy[1] = y[0]-y[1]; 01538 dy[2] = y[2]-y[0]; 01539 btScalar* scan=&m_buffer[miy*m_sizes[0]+mix]; 01540 for(int iy=miy;iy<mxy;++iy) 01541 { 01542 if(dy[0] >= 0 && POLICY::Process(*scan,v[0])) 01543 return(true); 01544 if(dy[1] >= 0 && POLICY::Process(*scan,v[1])) 01545 return(true); 01546 if(dy[2] >= 0 && POLICY::Process(*scan,v[2])) 01547 return(true); 01548 scan+=m_sizes[0]; 01549 v[0] += dzy[0]; v[1] += dzy[1]; v[2] += dzy[2]; 01550 dy[0]--; dy[1]++, dy[2]--; 01551 } 01552 } else if (height == 1) 01553 { 01554 // Degenerated in at least 2 horizontal lines 01555 // The algorithm below doesn't work when face has a single pixel width 01556 // We cannot use general formulas because the plane is degenerated. 01557 // We have to interpolate along the 3 edges that overlaps and process each pixel. 01558 int xtmp; 01559 btScalar ztmp; 01560 if (x[0] > x[1]) { xtmp=x[1];x[1]=x[0];x[0]=xtmp;ztmp=z[1];z[1]=z[0];z[0]=ztmp; } 01561 if (x[0] > x[2]) { xtmp=x[2];x[2]=x[0];x[0]=xtmp;ztmp=z[2];z[2]=z[0];z[0]=ztmp; } 01562 if (x[1] > x[2]) { xtmp=x[2];x[2]=x[1];x[1]=xtmp;ztmp=z[2];z[2]=z[1];z[1]=ztmp; } 01563 int dx[]={ x[0]-x[1], 01564 x[1]-x[2], 01565 x[2]-x[0]}; 01566 btScalar dzx[3]; 01567 dzx[0] = (dx[0]) ? (z[0]-z[1])/dx[0] : btScalar(0.f); 01568 dzx[1] = (dx[1]) ? (z[1]-z[2])/dx[1] : btScalar(0.f); 01569 dzx[2] = (dx[2]) ? (z[2]-z[0])/dx[2] : btScalar(0.f); 01570 btScalar v[3] = { dzx[0]*(mix-x[0])+z[0], 01571 dzx[1]*(mix-x[1])+z[1], 01572 dzx[2]*(mix-x[2])+z[2] }; 01573 dx[0] = x[1]-x[0]; 01574 dx[1] = x[0]-x[1]; 01575 dx[2] = x[2]-x[0]; 01576 btScalar* scan=&m_buffer[miy*m_sizes[0]+mix]; 01577 for(int ix=mix;ix<mxx;++ix) 01578 { 01579 if(dx[0] >= 0 && POLICY::Process(*scan,v[0])) 01580 return(true); 01581 if(dx[1] >= 0 && POLICY::Process(*scan,v[1])) 01582 return(true); 01583 if(dx[2] >= 0 && POLICY::Process(*scan,v[2])) 01584 return(true); 01585 scan++; 01586 v[0] += dzx[0]; v[1] += dzx[1]; v[2] += dzx[2]; 01587 dx[0]--; dx[1]++, dx[2]--; 01588 } 01589 } else 01590 { 01591 // general case 01592 const int dx[]={ y[0]-y[1], 01593 y[1]-y[2], 01594 y[2]-y[0]}; 01595 const int dy[]={ x[1]-x[0]-dx[0]*width, 01596 x[2]-x[1]-dx[1]*width, 01597 x[0]-x[2]-dx[2]*width}; 01598 const int a=x[2]*y[0]+x[0]*y[1]-x[2]*y[1]-x[0]*y[2]+x[1]*y[2]-x[1]*y[0]; 01599 const btScalar ia=1/(btScalar)a; 01600 const btScalar dzx=ia*(y[2]*(z[1]-z[0])+y[1]*(z[0]-z[2])+y[0]*(z[2]-z[1])); 01601 const btScalar dzy=ia*(x[2]*(z[0]-z[1])+x[0]*(z[1]-z[2])+x[1]*(z[2]-z[0]))-(dzx*width); 01602 int c[]={ miy*x[1]+mix*y[0]-x[1]*y[0]-mix*y[1]+x[0]*y[1]-miy*x[0], 01603 miy*x[2]+mix*y[1]-x[2]*y[1]-mix*y[2]+x[1]*y[2]-miy*x[1], 01604 miy*x[0]+mix*y[2]-x[0]*y[2]-mix*y[0]+x[2]*y[0]-miy*x[2]}; 01605 btScalar v=ia*((z[2]*c[0])+(z[0]*c[1])+(z[1]*c[2])); 01606 btScalar* scan=&m_buffer[miy*m_sizes[0]]; 01607 for(int iy=miy;iy<mxy;++iy) 01608 { 01609 for(int ix=mix;ix<mxx;++ix) 01610 { 01611 if((c[0]>=0)&&(c[1]>=0)&&(c[2]>=0)) 01612 { 01613 if(POLICY::Process(scan[ix],v)) 01614 return(true); 01615 } 01616 c[0]+=dx[0];c[1]+=dx[1];c[2]+=dx[2];v+=dzx; 01617 } 01618 c[0]+=dy[0];c[1]+=dy[1];c[2]+=dy[2];v+=dzy; 01619 scan+=m_sizes[0]; 01620 } 01621 } 01622 return(false); 01623 } 01624 // clip than write or check a polygon 01625 template <const int NP,typename POLICY> 01626 inline bool clipDraw( const btVector4* p, 01627 const float face, 01628 btScalar minarea) 01629 { 01630 btVector4 o[NP*2]; 01631 int n=clip<NP>(p,o); 01632 bool earlyexit=false; 01633 if (n) 01634 { 01635 project(o,n); 01636 for(int i=2;i<n && !earlyexit;++i) 01637 { 01638 earlyexit|=draw<POLICY>(o[0],o[i-1],o[i],face,minarea); 01639 } 01640 } 01641 return(earlyexit); 01642 } 01643 // add a triangle (in model coordinate) 01644 // face = 0.f if face is double side, 01645 // = 1.f if face is single sided and scale is positive 01646 // = -1.f if face is single sided and scale is negative 01647 void appendOccluderM(const float* a, 01648 const float* b, 01649 const float* c, 01650 const float face) 01651 { 01652 btVector4 p[3]; 01653 transformM(a,p[0]); 01654 transformM(b,p[1]); 01655 transformM(c,p[2]); 01656 clipDraw<3,WriteOCL>(p,face,btScalar(0.f)); 01657 } 01658 // add a quad (in model coordinate) 01659 void appendOccluderM(const float* a, 01660 const float* b, 01661 const float* c, 01662 const float* d, 01663 const float face) 01664 { 01665 btVector4 p[4]; 01666 transformM(a,p[0]); 01667 transformM(b,p[1]); 01668 transformM(c,p[2]); 01669 transformM(d,p[3]); 01670 clipDraw<4,WriteOCL>(p,face,btScalar(0.f)); 01671 } 01672 // query occluder for a box (c=center, e=extend) in world coordinate 01673 inline bool queryOccluderW( const btVector3& c, 01674 const btVector3& e) 01675 { 01676 if (!m_occlusion) 01677 // no occlusion yet, no need to check 01678 return true; 01679 btVector4 x[8]; 01680 transformW(btVector3(c[0]-e[0],c[1]-e[1],c[2]-e[2]),x[0]); 01681 transformW(btVector3(c[0]+e[0],c[1]-e[1],c[2]-e[2]),x[1]); 01682 transformW(btVector3(c[0]+e[0],c[1]+e[1],c[2]-e[2]),x[2]); 01683 transformW(btVector3(c[0]-e[0],c[1]+e[1],c[2]-e[2]),x[3]); 01684 transformW(btVector3(c[0]-e[0],c[1]-e[1],c[2]+e[2]),x[4]); 01685 transformW(btVector3(c[0]+e[0],c[1]-e[1],c[2]+e[2]),x[5]); 01686 transformW(btVector3(c[0]+e[0],c[1]+e[1],c[2]+e[2]),x[6]); 01687 transformW(btVector3(c[0]-e[0],c[1]+e[1],c[2]+e[2]),x[7]); 01688 for(int i=0;i<8;++i) 01689 { 01690 // the box is clipped, it's probably a large box, don't waste our time to check 01691 if((x[i][2]+x[i][3])<=0) return(true); 01692 } 01693 static const int d[]={ 1,0,3,2, 01694 4,5,6,7, 01695 4,7,3,0, 01696 6,5,1,2, 01697 7,6,2,3, 01698 5,4,0,1}; 01699 for(unsigned int i=0;i<(sizeof(d)/sizeof(d[0]));) 01700 { 01701 const btVector4 p[]={ x[d[i++]], 01702 x[d[i++]], 01703 x[d[i++]], 01704 x[d[i++]]}; 01705 if(clipDraw<4,QueryOCL>(p,1.f,0.f)) 01706 return(true); 01707 } 01708 return(false); 01709 } 01710 }; 01711 01712 01713 struct DbvtCullingCallback : btDbvt::ICollide 01714 { 01715 PHY_CullingCallback m_clientCallback; 01716 void* m_userData; 01717 OcclusionBuffer *m_ocb; 01718 01719 DbvtCullingCallback(PHY_CullingCallback clientCallback, void* userData) 01720 { 01721 m_clientCallback = clientCallback; 01722 m_userData = userData; 01723 m_ocb = NULL; 01724 } 01725 bool Descent(const btDbvtNode* node) 01726 { 01727 return(m_ocb->queryOccluderW(node->volume.Center(),node->volume.Extents())); 01728 } 01729 void Process(const btDbvtNode* node,btScalar depth) 01730 { 01731 Process(node); 01732 } 01733 void Process(const btDbvtNode* leaf) 01734 { 01735 btBroadphaseProxy* proxy=(btBroadphaseProxy*)leaf->data; 01736 // the client object is a graphic controller 01737 CcdGraphicController* ctrl = static_cast<CcdGraphicController*>(proxy->m_clientObject); 01738 KX_ClientObjectInfo* info = (KX_ClientObjectInfo*)ctrl->getNewClientInfo(); 01739 if (m_ocb) 01740 { 01741 // means we are doing occlusion culling. Check if this object is an occluders 01742 KX_GameObject* gameobj = KX_GameObject::GetClientObject(info); 01743 if (gameobj && gameobj->GetOccluder()) 01744 { 01745 double* fl = gameobj->GetOpenGLMatrixPtr()->getPointer(); 01746 // this will create the occlusion buffer if not already done 01747 // and compute the transformation from model local space to clip space 01748 m_ocb->SetModelMatrix(fl); 01749 float face = (gameobj->IsNegativeScaling()) ? -1.0f : 1.0f; 01750 // walk through the meshes and for each add to buffer 01751 for (int i=0; i<gameobj->GetMeshCount(); i++) 01752 { 01753 RAS_MeshObject* meshobj = gameobj->GetMesh(i); 01754 const float *v1, *v2, *v3, *v4; 01755 01756 int polycount = meshobj->NumPolygons(); 01757 for (int j=0; j<polycount; j++) 01758 { 01759 RAS_Polygon* poly = meshobj->GetPolygon(j); 01760 switch (poly->VertexCount()) 01761 { 01762 case 3: 01763 v1 = poly->GetVertex(0)->getXYZ(); 01764 v2 = poly->GetVertex(1)->getXYZ(); 01765 v3 = poly->GetVertex(2)->getXYZ(); 01766 m_ocb->appendOccluderM(v1,v2,v3,((poly->IsTwoside())?0.f:face)); 01767 break; 01768 case 4: 01769 v1 = poly->GetVertex(0)->getXYZ(); 01770 v2 = poly->GetVertex(1)->getXYZ(); 01771 v3 = poly->GetVertex(2)->getXYZ(); 01772 v4 = poly->GetVertex(3)->getXYZ(); 01773 m_ocb->appendOccluderM(v1,v2,v3,v4,((poly->IsTwoside())?0.f:face)); 01774 break; 01775 } 01776 } 01777 } 01778 } 01779 } 01780 if (info) 01781 (*m_clientCallback)(info, m_userData); 01782 } 01783 }; 01784 01785 static OcclusionBuffer gOcb; 01786 bool CcdPhysicsEnvironment::cullingTest(PHY_CullingCallback callback, void* userData, PHY__Vector4 *planes, int nplanes, int occlusionRes) 01787 { 01788 if (!m_cullingTree) 01789 return false; 01790 DbvtCullingCallback dispatcher(callback, userData); 01791 btVector3 planes_n[6]; 01792 btScalar planes_o[6]; 01793 if (nplanes > 6) 01794 nplanes = 6; 01795 for (int i=0; i<nplanes; i++) 01796 { 01797 planes_n[i].setValue(planes[i][0], planes[i][1], planes[i][2]); 01798 planes_o[i] = planes[i][3]; 01799 } 01800 // if occlusionRes != 0 => occlusion culling 01801 if (occlusionRes) 01802 { 01803 gOcb.setup(occlusionRes); 01804 dispatcher.m_ocb = &gOcb; 01805 // occlusion culling, the direction of the view is taken from the first plan which MUST be the near plane 01806 btDbvt::collideOCL(m_cullingTree->m_sets[1].m_root,planes_n,planes_o,planes_n[0],nplanes,dispatcher); 01807 btDbvt::collideOCL(m_cullingTree->m_sets[0].m_root,planes_n,planes_o,planes_n[0],nplanes,dispatcher); 01808 }else 01809 { 01810 btDbvt::collideKDOP(m_cullingTree->m_sets[1].m_root,planes_n,planes_o,nplanes,dispatcher); 01811 btDbvt::collideKDOP(m_cullingTree->m_sets[0].m_root,planes_n,planes_o,nplanes,dispatcher); 01812 } 01813 return true; 01814 } 01815 01816 int CcdPhysicsEnvironment::getNumContactPoints() 01817 { 01818 return 0; 01819 } 01820 01821 void CcdPhysicsEnvironment::getContactPoint(int i,float& hitX,float& hitY,float& hitZ,float& normalX,float& normalY,float& normalZ) 01822 { 01823 01824 } 01825 01826 01827 01828 01829 btBroadphaseInterface* CcdPhysicsEnvironment::getBroadphase() 01830 { 01831 return m_dynamicsWorld->getBroadphase(); 01832 } 01833 01834 btDispatcher* CcdPhysicsEnvironment::getDispatcher() 01835 { 01836 return m_dynamicsWorld->getDispatcher(); 01837 } 01838 01839 void CcdPhysicsEnvironment::MergeEnvironment(CcdPhysicsEnvironment *other) 01840 { 01841 std::set<CcdPhysicsController*>::iterator it; 01842 01843 while (other->m_controllers.begin() != other->m_controllers.end()) 01844 { 01845 it= other->m_controllers.begin(); 01846 CcdPhysicsController* ctrl= (*it); 01847 01848 other->removeCcdPhysicsController(ctrl); 01849 this->addCcdPhysicsController(ctrl); 01850 } 01851 } 01852 01853 CcdPhysicsEnvironment::~CcdPhysicsEnvironment() 01854 { 01855 01856 #ifdef NEW_BULLET_VEHICLE_SUPPORT 01857 m_wrapperVehicles.clear(); 01858 #endif //NEW_BULLET_VEHICLE_SUPPORT 01859 01860 //m_broadphase->DestroyScene(); 01861 //delete broadphase ? release reference on broadphase ? 01862 01863 //first delete scene, then dispatcher, because pairs have to release manifolds on the dispatcher 01864 //delete m_dispatcher; 01865 delete m_dynamicsWorld; 01866 01867 01868 if (NULL != m_ownPairCache) 01869 delete m_ownPairCache; 01870 01871 if (NULL != m_ownDispatcher) 01872 delete m_ownDispatcher; 01873 01874 if (NULL != m_solver) 01875 delete m_solver; 01876 01877 if (NULL != m_debugDrawer) 01878 delete m_debugDrawer; 01879 01880 if (NULL != m_filterCallback) 01881 delete m_filterCallback; 01882 01883 if (NULL != m_collisionConfiguration) 01884 delete m_collisionConfiguration; 01885 01886 if (NULL != m_broadphase) 01887 delete m_broadphase; 01888 01889 if (NULL != m_cullingTree) 01890 delete m_cullingTree; 01891 01892 if (NULL != m_cullingCache) 01893 delete m_cullingCache; 01894 01895 } 01896 01897 01898 float CcdPhysicsEnvironment::getConstraintParam(int constraintId,int param) 01899 { 01900 btTypedConstraint* typedConstraint = getConstraintById(constraintId); 01901 switch (typedConstraint->getUserConstraintType()) 01902 { 01903 case PHY_GENERIC_6DOF_CONSTRAINT: 01904 { 01905 01906 switch (param) 01907 { 01908 case 0: case 1: case 2: 01909 { 01910 //param = 0..2 are linear constraint values 01911 btGeneric6DofConstraint* genCons = (btGeneric6DofConstraint*)typedConstraint; 01912 genCons->calculateTransforms(); 01913 return genCons->getRelativePivotPosition(param); 01914 break; 01915 } 01916 case 3: case 4: case 5: 01917 { 01918 //param = 3..5 are relative constraint (Euler) angles 01919 btGeneric6DofConstraint* genCons = (btGeneric6DofConstraint*)typedConstraint; 01920 genCons->calculateTransforms(); 01921 return genCons->getAngle(param-3); 01922 break; 01923 } 01924 default: 01925 { 01926 } 01927 } 01928 break; 01929 }; 01930 default: 01931 { 01932 }; 01933 }; 01934 return 0.f; 01935 } 01936 01937 void CcdPhysicsEnvironment::setConstraintParam(int constraintId,int param,float value0,float value1) 01938 { 01939 btTypedConstraint* typedConstraint = getConstraintById(constraintId); 01940 switch (typedConstraint->getUserConstraintType()) 01941 { 01942 case PHY_GENERIC_6DOF_CONSTRAINT: 01943 { 01944 01945 switch (param) 01946 { 01947 case 0: case 1: case 2: case 3: case 4: case 5: 01948 { 01949 //param = 0..5 are constraint limits, with low/high limit value 01950 btGeneric6DofConstraint* genCons = (btGeneric6DofConstraint*)typedConstraint; 01951 genCons->setLimit(param,value0,value1); 01952 break; 01953 } 01954 case 6: case 7: case 8: 01955 { 01956 //param = 6,7,8 are translational motors, with value0=target velocity, value1 = max motor force 01957 btGeneric6DofConstraint* genCons = (btGeneric6DofConstraint*)typedConstraint; 01958 int transMotorIndex = param-6; 01959 btTranslationalLimitMotor* transMotor = genCons->getTranslationalLimitMotor(); 01960 transMotor->m_targetVelocity[transMotorIndex]= value0; 01961 transMotor->m_maxMotorForce[transMotorIndex]=value1; 01962 transMotor->m_enableMotor[transMotorIndex] = (value1>0.f); 01963 break; 01964 } 01965 case 9: case 10: case 11: 01966 { 01967 //param = 9,10,11 are rotational motors, with value0=target velocity, value1 = max motor force 01968 btGeneric6DofConstraint* genCons = (btGeneric6DofConstraint*)typedConstraint; 01969 int angMotorIndex = param-9; 01970 btRotationalLimitMotor* rotMotor = genCons->getRotationalLimitMotor(angMotorIndex); 01971 rotMotor->m_enableMotor = (value1 > 0.f); 01972 rotMotor->m_targetVelocity = value0; 01973 rotMotor->m_maxMotorForce = value1; 01974 break; 01975 } 01976 01977 case 12: case 13: case 14: case 15: case 16: case 17: 01978 { 01979 //param 13-17 are for motorized springs on each of the degrees of freedom 01980 btGeneric6DofSpringConstraint* genCons = (btGeneric6DofSpringConstraint*)typedConstraint; 01981 int springIndex = param-12; 01982 if (value0!=0.f) 01983 { 01984 bool springEnabled = true; 01985 genCons->setStiffness(springIndex,value0); 01986 genCons->setDamping(springIndex,value1); 01987 genCons->enableSpring(springIndex,springEnabled); 01988 genCons->setEquilibriumPoint(springIndex); 01989 } else 01990 { 01991 bool springEnabled = false; 01992 genCons->enableSpring(springIndex,springEnabled); 01993 } 01994 break; 01995 } 01996 01997 default: 01998 { 01999 } 02000 }; 02001 break; 02002 }; 02003 case PHY_CONE_TWIST_CONSTRAINT: 02004 { 02005 switch (param) 02006 { 02007 case 3: case 4: case 5: 02008 { 02009 //param = 3,4,5 are constraint limits, high limit values 02010 btConeTwistConstraint* coneTwist = (btConeTwistConstraint*)typedConstraint; 02011 if(value1<0.0f) 02012 coneTwist->setLimit(param,btScalar(BT_LARGE_FLOAT)); 02013 else 02014 coneTwist->setLimit(param,value1); 02015 break; 02016 } 02017 default: 02018 { 02019 } 02020 }; 02021 break; 02022 }; 02023 case PHY_ANGULAR_CONSTRAINT: 02024 case PHY_LINEHINGE_CONSTRAINT: 02025 { 02026 switch (param) 02027 { 02028 case 3: 02029 { 02030 //param = 3 is a constraint limit, with low/high limit value 02031 btHingeConstraint* hingeCons = (btHingeConstraint*)typedConstraint; 02032 hingeCons->setLimit(value0,value1); 02033 break; 02034 } 02035 default: 02036 { 02037 } 02038 } 02039 break; 02040 }; 02041 default: 02042 { 02043 }; 02044 }; 02045 } 02046 02047 btTypedConstraint* CcdPhysicsEnvironment::getConstraintById(int constraintId) 02048 { 02049 02050 int numConstraints = m_dynamicsWorld->getNumConstraints(); 02051 int i; 02052 for (i=0;i<numConstraints;i++) 02053 { 02054 btTypedConstraint* constraint = m_dynamicsWorld->getConstraint(i); 02055 if (constraint->getUserConstraintId()==constraintId) 02056 { 02057 return constraint; 02058 } 02059 } 02060 return 0; 02061 } 02062 02063 02064 void CcdPhysicsEnvironment::addSensor(PHY_IPhysicsController* ctrl) 02065 { 02066 02067 CcdPhysicsController* ctrl1 = (CcdPhysicsController* )ctrl; 02068 // addSensor() is a "light" function for bullet because it is used 02069 // dynamically when the sensor is activated. Use enableCcdPhysicsController() instead 02070 //if (m_controllers.insert(ctrl1).second) 02071 //{ 02072 // addCcdPhysicsController(ctrl1); 02073 //} 02074 enableCcdPhysicsController(ctrl1); 02075 } 02076 02077 bool CcdPhysicsEnvironment::removeCollisionCallback(PHY_IPhysicsController* ctrl) 02078 { 02079 CcdPhysicsController* ccdCtrl = (CcdPhysicsController*)ctrl; 02080 if (!ccdCtrl->Unregister()) 02081 return false; 02082 m_triggerControllers.erase(ccdCtrl); 02083 return true; 02084 } 02085 02086 02087 void CcdPhysicsEnvironment::removeSensor(PHY_IPhysicsController* ctrl) 02088 { 02089 disableCcdPhysicsController((CcdPhysicsController*)ctrl); 02090 } 02091 02092 void CcdPhysicsEnvironment::addTouchCallback(int response_class, PHY_ResponseCallback callback, void *user) 02093 { 02094 /* printf("addTouchCallback\n(response class = %i)\n",response_class); 02095 02096 //map PHY_ convention into SM_ convention 02097 switch (response_class) 02098 { 02099 case PHY_FH_RESPONSE: 02100 printf("PHY_FH_RESPONSE\n"); 02101 break; 02102 case PHY_SENSOR_RESPONSE: 02103 printf("PHY_SENSOR_RESPONSE\n"); 02104 break; 02105 case PHY_CAMERA_RESPONSE: 02106 printf("PHY_CAMERA_RESPONSE\n"); 02107 break; 02108 case PHY_OBJECT_RESPONSE: 02109 printf("PHY_OBJECT_RESPONSE\n"); 02110 break; 02111 case PHY_STATIC_RESPONSE: 02112 printf("PHY_STATIC_RESPONSE\n"); 02113 break; 02114 default: 02115 assert(0); 02116 return; 02117 } 02118 */ 02119 02120 m_triggerCallbacks[response_class] = callback; 02121 m_triggerCallbacksUserPtrs[response_class] = user; 02122 02123 } 02124 bool CcdPhysicsEnvironment::requestCollisionCallback(PHY_IPhysicsController* ctrl) 02125 { 02126 CcdPhysicsController* ccdCtrl = static_cast<CcdPhysicsController*>(ctrl); 02127 02128 if (!ccdCtrl->Register()) 02129 return false; 02130 m_triggerControllers.insert(ccdCtrl); 02131 return true; 02132 } 02133 02134 void CcdPhysicsEnvironment::CallbackTriggers() 02135 { 02136 if (m_triggerCallbacks[PHY_OBJECT_RESPONSE] || (m_debugDrawer && (m_debugDrawer->getDebugMode() & btIDebugDraw::DBG_DrawContactPoints))) 02137 { 02138 //walk over all overlapping pairs, and if one of the involved bodies is registered for trigger callback, perform callback 02139 btDispatcher* dispatcher = m_dynamicsWorld->getDispatcher(); 02140 int numManifolds = dispatcher->getNumManifolds(); 02141 for (int i=0;i<numManifolds;i++) 02142 { 02143 btPersistentManifold* manifold = dispatcher->getManifoldByIndexInternal(i); 02144 int numContacts = manifold->getNumContacts(); 02145 if (numContacts) 02146 { 02147 btRigidBody* rb0 = static_cast<btRigidBody*>(manifold->getBody0()); 02148 btRigidBody* rb1 = static_cast<btRigidBody*>(manifold->getBody1()); 02149 if (m_debugDrawer && (m_debugDrawer->getDebugMode() & btIDebugDraw::DBG_DrawContactPoints)) 02150 { 02151 for (int j=0;j<numContacts;j++) 02152 { 02153 btVector3 color(1,0,0); 02154 const btManifoldPoint& cp = manifold->getContactPoint(j); 02155 if (m_debugDrawer) 02156 m_debugDrawer->drawContactPoint(cp.m_positionWorldOnB,cp.m_normalWorldOnB,cp.getDistance(),cp.getLifeTime(),color); 02157 } 02158 } 02159 btRigidBody* obj0 = rb0; 02160 btRigidBody* obj1 = rb1; 02161 02162 //m_internalOwner is set in 'addPhysicsController' 02163 CcdPhysicsController* ctrl0 = static_cast<CcdPhysicsController*>(obj0->getUserPointer()); 02164 CcdPhysicsController* ctrl1 = static_cast<CcdPhysicsController*>(obj1->getUserPointer()); 02165 02166 std::set<CcdPhysicsController*>::const_iterator i = m_triggerControllers.find(ctrl0); 02167 if (i == m_triggerControllers.end()) 02168 { 02169 i = m_triggerControllers.find(ctrl1); 02170 } 02171 02172 if (!(i == m_triggerControllers.end())) 02173 { 02174 m_triggerCallbacks[PHY_OBJECT_RESPONSE](m_triggerCallbacksUserPtrs[PHY_OBJECT_RESPONSE], 02175 ctrl0,ctrl1,0); 02176 } 02177 // Bullet does not refresh the manifold contact point for object without contact response 02178 // may need to remove this when a newer Bullet version is integrated 02179 if (!dispatcher->needsResponse(rb0, rb1)) 02180 { 02181 // Refresh algorithm fails sometimes when there is penetration 02182 // (usuall the case with ghost and sensor objects) 02183 // Let's just clear the manifold, in any case, it is recomputed on each frame. 02184 manifold->clearManifold(); //refreshContactPoints(rb0->getCenterOfMassTransform(),rb1->getCenterOfMassTransform()); 02185 } 02186 } 02187 } 02188 02189 02190 02191 } 02192 02193 02194 } 02195 02196 // This call back is called before a pair is added in the cache 02197 // Handy to remove objects that must be ignored by sensors 02198 bool CcdOverlapFilterCallBack::needBroadphaseCollision(btBroadphaseProxy* proxy0,btBroadphaseProxy* proxy1) const 02199 { 02200 btCollisionObject *colObj0, *colObj1; 02201 CcdPhysicsController *sensorCtrl, *objCtrl; 02202 bool collides; 02203 // first check the filters 02204 collides = (proxy0->m_collisionFilterGroup & proxy1->m_collisionFilterMask) != 0; 02205 collides = collides && (proxy1->m_collisionFilterGroup & proxy0->m_collisionFilterMask); 02206 if (!collides) 02207 return false; 02208 02209 // additional check for sensor object 02210 if (proxy0->m_collisionFilterGroup & btBroadphaseProxy::SensorTrigger) 02211 { 02212 // this is a sensor object, the other one can't be a sensor object because 02213 // they exclude each other in the above test 02214 assert(!(proxy1->m_collisionFilterGroup & btBroadphaseProxy::SensorTrigger)); 02215 colObj0 = (btCollisionObject*)proxy0->m_clientObject; 02216 colObj1 = (btCollisionObject*)proxy1->m_clientObject; 02217 } 02218 else if (proxy1->m_collisionFilterGroup & btBroadphaseProxy::SensorTrigger) 02219 { 02220 colObj0 = (btCollisionObject*)proxy1->m_clientObject; 02221 colObj1 = (btCollisionObject*)proxy0->m_clientObject; 02222 } 02223 else 02224 { 02225 return true; 02226 } 02227 if (!colObj0 || !colObj1) 02228 return false; 02229 sensorCtrl = static_cast<CcdPhysicsController*>(colObj0->getUserPointer()); 02230 objCtrl = static_cast<CcdPhysicsController*>(colObj1->getUserPointer()); 02231 if (m_physEnv->m_triggerCallbacks[PHY_BROADPH_RESPONSE]) 02232 { 02233 return m_physEnv->m_triggerCallbacks[PHY_BROADPH_RESPONSE](m_physEnv->m_triggerCallbacksUserPtrs[PHY_BROADPH_RESPONSE], sensorCtrl, objCtrl, 0); 02234 } 02235 return true; 02236 } 02237 02238 02239 #ifdef NEW_BULLET_VEHICLE_SUPPORT 02240 02241 //complex constraint for vehicles 02242 PHY_IVehicle* CcdPhysicsEnvironment::getVehicleConstraint(int constraintId) 02243 { 02244 int i; 02245 02246 int numVehicles = m_wrapperVehicles.size(); 02247 for (i=0;i<numVehicles;i++) 02248 { 02249 WrapperVehicle* wrapperVehicle = m_wrapperVehicles[i]; 02250 if (wrapperVehicle->GetVehicle()->getUserConstraintId() == constraintId) 02251 return wrapperVehicle; 02252 } 02253 02254 return 0; 02255 } 02256 02257 #endif //NEW_BULLET_VEHICLE_SUPPORT 02258 02259 02260 int currentController = 0; 02261 int numController = 0; 02262 02263 02264 02265 02266 PHY_IPhysicsController* CcdPhysicsEnvironment::CreateSphereController(float radius,const PHY__Vector3& position) 02267 { 02268 02269 CcdConstructionInfo cinfo; 02270 memset(&cinfo, 0, sizeof(cinfo)); /* avoid uninitialized values */ 02271 cinfo.m_collisionShape = new btSphereShape(radius); // memory leak! The shape is not deleted by Bullet and we cannot add it to the KX_Scene.m_shapes list 02272 cinfo.m_MotionState = 0; 02273 cinfo.m_physicsEnv = this; 02274 // declare this object as Dyamic rather than static!! 02275 // The reason as it is designed to detect all type of object, including static object 02276 // It would cause static-static message to be printed on the console otherwise 02277 cinfo.m_collisionFlags |= btCollisionObject::CF_NO_CONTACT_RESPONSE | btCollisionObject::CF_STATIC_OBJECT; 02278 DefaultMotionState* motionState = new DefaultMotionState(); 02279 cinfo.m_MotionState = motionState; 02280 // we will add later the possibility to select the filter from option 02281 cinfo.m_collisionFilterMask = CcdConstructionInfo::AllFilter ^ CcdConstructionInfo::SensorFilter; 02282 cinfo.m_collisionFilterGroup = CcdConstructionInfo::SensorFilter; 02283 cinfo.m_bSensor = true; 02284 motionState->m_worldTransform.setIdentity(); 02285 motionState->m_worldTransform.setOrigin(btVector3(position[0],position[1],position[2])); 02286 02287 CcdPhysicsController* sphereController = new CcdPhysicsController(cinfo); 02288 02289 return sphereController; 02290 } 02291 02292 int findClosestNode(btSoftBody* sb,const btVector3& worldPoint); 02293 int findClosestNode(btSoftBody* sb,const btVector3& worldPoint) 02294 { 02295 int node = -1; 02296 02297 btSoftBody::tNodeArray& nodes(sb->m_nodes); 02298 float maxDistSqr = 1e30f; 02299 02300 for (int n=0;n<nodes.size();n++) 02301 { 02302 btScalar distSqr = (nodes[n].m_x - worldPoint).length2(); 02303 if (distSqr<maxDistSqr) 02304 { 02305 maxDistSqr = distSqr; 02306 node = n; 02307 } 02308 } 02309 return node; 02310 } 02311 02312 int CcdPhysicsEnvironment::createConstraint(class PHY_IPhysicsController* ctrl0,class PHY_IPhysicsController* ctrl1,PHY_ConstraintType type, 02313 float pivotX,float pivotY,float pivotZ, 02314 float axisX,float axisY,float axisZ, 02315 float axis1X,float axis1Y,float axis1Z, 02316 float axis2X,float axis2Y,float axis2Z,int flags 02317 ) 02318 { 02319 02320 bool disableCollisionBetweenLinkedBodies = (0!=(flags & CCD_CONSTRAINT_DISABLE_LINKED_COLLISION)); 02321 02322 02323 02324 CcdPhysicsController* c0 = (CcdPhysicsController*)ctrl0; 02325 CcdPhysicsController* c1 = (CcdPhysicsController*)ctrl1; 02326 02327 btRigidBody* rb0 = c0 ? c0->GetRigidBody() : 0; 02328 btRigidBody* rb1 = c1 ? c1->GetRigidBody() : 0; 02329 02330 02331 02332 02333 bool rb0static = rb0 ? rb0->isStaticOrKinematicObject() : true; 02334 bool rb1static = rb1 ? rb1->isStaticOrKinematicObject() : true; 02335 02336 btCollisionObject* colObj0 = c0->GetCollisionObject(); 02337 if (!colObj0) 02338 { 02339 return 0; 02340 } 02341 02342 btVector3 pivotInA(pivotX,pivotY,pivotZ); 02343 02344 02345 02346 //it might be a soft body, let's try 02347 btSoftBody* sb0 = c0 ? c0->GetSoftBody() : 0; 02348 btSoftBody* sb1 = c1 ? c1->GetSoftBody() : 0; 02349 if (sb0 && sb1) 02350 { 02351 //not between two soft bodies? 02352 return 0; 02353 } 02354 02355 if (sb0) 02356 { 02357 //either cluster or node attach, let's find closest node first 02358 //the soft body doesn't have a 'real' world transform, so get its initial world transform for now 02359 btVector3 pivotPointSoftWorld = sb0->m_initialWorldTransform(pivotInA); 02360 int node=findClosestNode(sb0,pivotPointSoftWorld); 02361 if (node >=0) 02362 { 02363 bool clusterconstaint = false; 02364 /* 02365 switch (type) 02366 { 02367 case PHY_LINEHINGE_CONSTRAINT: 02368 { 02369 if (sb0->clusterCount() && rb1) 02370 { 02371 btSoftBody::LJoint::Specs ls; 02372 ls.erp=0.5f; 02373 ls.position=sb0->clusterCom(0); 02374 sb0->appendLinearJoint(ls,rb1); 02375 clusterconstaint = true; 02376 break; 02377 } 02378 } 02379 case PHY_GENERIC_6DOF_CONSTRAINT: 02380 { 02381 if (sb0->clusterCount() && rb1) 02382 { 02383 btSoftBody::AJoint::Specs as; 02384 as.erp = 1; 02385 as.cfm = 1; 02386 as.axis.setValue(axisX,axisY,axisZ); 02387 sb0->appendAngularJoint(as,rb1); 02388 clusterconstaint = true; 02389 break; 02390 } 02391 02392 break; 02393 } 02394 default: 02395 { 02396 02397 } 02398 }; 02399 */ 02400 02401 if (!clusterconstaint) 02402 { 02403 if (rb1) 02404 { 02405 sb0->appendAnchor(node,rb1,disableCollisionBetweenLinkedBodies); 02406 } else 02407 { 02408 sb0->setMass(node,0.f); 02409 } 02410 } 02411 02412 02413 } 02414 return 0;//can't remove soft body anchors yet 02415 } 02416 02417 if (sb1) 02418 { 02419 btVector3 pivotPointAWorld = colObj0->getWorldTransform()(pivotInA); 02420 int node=findClosestNode(sb1,pivotPointAWorld); 02421 if (node >=0) 02422 { 02423 bool clusterconstaint = false; 02424 02425 /* 02426 switch (type) 02427 { 02428 case PHY_LINEHINGE_CONSTRAINT: 02429 { 02430 if (sb1->clusterCount() && rb0) 02431 { 02432 btSoftBody::LJoint::Specs ls; 02433 ls.erp=0.5f; 02434 ls.position=sb1->clusterCom(0); 02435 sb1->appendLinearJoint(ls,rb0); 02436 clusterconstaint = true; 02437 break; 02438 } 02439 } 02440 case PHY_GENERIC_6DOF_CONSTRAINT: 02441 { 02442 if (sb1->clusterCount() && rb0) 02443 { 02444 btSoftBody::AJoint::Specs as; 02445 as.erp = 1; 02446 as.cfm = 1; 02447 as.axis.setValue(axisX,axisY,axisZ); 02448 sb1->appendAngularJoint(as,rb0); 02449 clusterconstaint = true; 02450 break; 02451 } 02452 02453 break; 02454 } 02455 default: 02456 { 02457 02458 02459 } 02460 };*/ 02461 02462 02463 if (!clusterconstaint) 02464 { 02465 if (rb0) 02466 { 02467 sb1->appendAnchor(node,rb0,disableCollisionBetweenLinkedBodies); 02468 } else 02469 { 02470 sb1->setMass(node,0.f); 02471 } 02472 } 02473 02474 02475 } 02476 return 0;//can't remove soft body anchors yet 02477 } 02478 02479 if (rb0static && rb1static) 02480 { 02481 02482 return 0; 02483 } 02484 02485 02486 if (!rb0) 02487 return 0; 02488 02489 02490 btVector3 pivotInB = rb1 ? rb1->getCenterOfMassTransform().inverse()(rb0->getCenterOfMassTransform()(pivotInA)) : 02491 rb0->getCenterOfMassTransform() * pivotInA; 02492 btVector3 axisInA(axisX,axisY,axisZ); 02493 02494 02495 bool angularOnly = false; 02496 02497 switch (type) 02498 { 02499 case PHY_POINT2POINT_CONSTRAINT: 02500 { 02501 02502 btPoint2PointConstraint* p2p = 0; 02503 02504 if (rb1) 02505 { 02506 p2p = new btPoint2PointConstraint(*rb0, 02507 *rb1,pivotInA,pivotInB); 02508 } else 02509 { 02510 p2p = new btPoint2PointConstraint(*rb0, 02511 pivotInA); 02512 } 02513 02514 m_dynamicsWorld->addConstraint(p2p,disableCollisionBetweenLinkedBodies); 02515 // m_constraints.push_back(p2p); 02516 02517 p2p->setUserConstraintId(gConstraintUid++); 02518 p2p->setUserConstraintType(type); 02519 //64 bit systems can't cast pointer to int. could use size_t instead. 02520 return p2p->getUserConstraintId(); 02521 02522 break; 02523 } 02524 02525 case PHY_GENERIC_6DOF_CONSTRAINT: 02526 { 02527 btGeneric6DofConstraint* genericConstraint = 0; 02528 02529 if (rb1) 02530 { 02531 btTransform frameInA; 02532 btTransform frameInB; 02533 02534 btVector3 axis1(axis1X,axis1Y,axis1Z), axis2(axis2X,axis2Y,axis2Z); 02535 if (axis1.length() == 0.0) 02536 { 02537 btPlaneSpace1( axisInA, axis1, axis2 ); 02538 } 02539 02540 frameInA.getBasis().setValue( axisInA.x(), axis1.x(), axis2.x(), 02541 axisInA.y(), axis1.y(), axis2.y(), 02542 axisInA.z(), axis1.z(), axis2.z() ); 02543 frameInA.setOrigin( pivotInA ); 02544 02545 btTransform inv = rb1->getCenterOfMassTransform().inverse(); 02546 02547 btTransform globalFrameA = rb0->getCenterOfMassTransform() * frameInA; 02548 02549 frameInB = inv * globalFrameA; 02550 bool useReferenceFrameA = true; 02551 02552 genericConstraint = new btGeneric6DofSpringConstraint( 02553 *rb0,*rb1, 02554 frameInA,frameInB,useReferenceFrameA); 02555 02556 02557 } else 02558 { 02559 static btRigidBody s_fixedObject2( 0,0,0); 02560 btTransform frameInA; 02561 btTransform frameInB; 02562 02563 btVector3 axis1, axis2; 02564 btPlaneSpace1( axisInA, axis1, axis2 ); 02565 02566 frameInA.getBasis().setValue( axisInA.x(), axis1.x(), axis2.x(), 02567 axisInA.y(), axis1.y(), axis2.y(), 02568 axisInA.z(), axis1.z(), axis2.z() ); 02569 02570 frameInA.setOrigin( pivotInA ); 02571 02573 frameInB = rb0->getCenterOfMassTransform() * frameInA; 02574 02575 bool useReferenceFrameA = true; 02576 genericConstraint = new btGeneric6DofSpringConstraint( 02577 *rb0,s_fixedObject2, 02578 frameInA,frameInB,useReferenceFrameA); 02579 } 02580 02581 if (genericConstraint) 02582 { 02583 //m_constraints.push_back(genericConstraint); 02584 m_dynamicsWorld->addConstraint(genericConstraint,disableCollisionBetweenLinkedBodies); 02585 genericConstraint->setUserConstraintId(gConstraintUid++); 02586 genericConstraint->setUserConstraintType(type); 02587 //64 bit systems can't cast pointer to int. could use size_t instead. 02588 return genericConstraint->getUserConstraintId(); 02589 } 02590 02591 break; 02592 } 02593 case PHY_CONE_TWIST_CONSTRAINT: 02594 { 02595 btConeTwistConstraint* coneTwistContraint = 0; 02596 02597 02598 if (rb1) 02599 { 02600 btTransform frameInA; 02601 btTransform frameInB; 02602 02603 btVector3 axis1(axis1X,axis1Y,axis1Z), axis2(axis2X,axis2Y,axis2Z); 02604 if (axis1.length() == 0.0) 02605 { 02606 btPlaneSpace1( axisInA, axis1, axis2 ); 02607 } 02608 02609 frameInA.getBasis().setValue( axisInA.x(), axis1.x(), axis2.x(), 02610 axisInA.y(), axis1.y(), axis2.y(), 02611 axisInA.z(), axis1.z(), axis2.z() ); 02612 frameInA.setOrigin( pivotInA ); 02613 02614 btTransform inv = rb1->getCenterOfMassTransform().inverse(); 02615 02616 btTransform globalFrameA = rb0->getCenterOfMassTransform() * frameInA; 02617 02618 frameInB = inv * globalFrameA; 02619 02620 coneTwistContraint = new btConeTwistConstraint( *rb0,*rb1, 02621 frameInA,frameInB); 02622 02623 02624 } else 02625 { 02626 static btRigidBody s_fixedObject2( 0,0,0); 02627 btTransform frameInA; 02628 btTransform frameInB; 02629 02630 btVector3 axis1, axis2; 02631 btPlaneSpace1( axisInA, axis1, axis2 ); 02632 02633 frameInA.getBasis().setValue( axisInA.x(), axis1.x(), axis2.x(), 02634 axisInA.y(), axis1.y(), axis2.y(), 02635 axisInA.z(), axis1.z(), axis2.z() ); 02636 02637 frameInA.setOrigin( pivotInA ); 02638 02640 frameInB = rb0->getCenterOfMassTransform() * frameInA; 02641 02642 coneTwistContraint = new btConeTwistConstraint( 02643 *rb0,s_fixedObject2, 02644 frameInA,frameInB); 02645 } 02646 02647 if (coneTwistContraint) 02648 { 02649 //m_constraints.push_back(genericConstraint); 02650 m_dynamicsWorld->addConstraint(coneTwistContraint,disableCollisionBetweenLinkedBodies); 02651 coneTwistContraint->setUserConstraintId(gConstraintUid++); 02652 coneTwistContraint->setUserConstraintType(type); 02653 //64 bit systems can't cast pointer to int. could use size_t instead. 02654 return coneTwistContraint->getUserConstraintId(); 02655 } 02656 02657 02658 02659 break; 02660 } 02661 case PHY_ANGULAR_CONSTRAINT: 02662 angularOnly = true; 02663 02664 02665 case PHY_LINEHINGE_CONSTRAINT: 02666 { 02667 btHingeConstraint* hinge = 0; 02668 02669 if (rb1) 02670 { 02671 // We know the orientations so we should use them instead of 02672 // having btHingeConstraint fill in the blanks any way it wants to. 02673 btTransform frameInA; 02674 btTransform frameInB; 02675 02676 btVector3 axis1(axis1X,axis1Y,axis1Z), axis2(axis2X,axis2Y,axis2Z); 02677 if (axis1.length() == 0.0) 02678 { 02679 btPlaneSpace1( axisInA, axis1, axis2 ); 02680 } 02681 02682 // Internally btHingeConstraint's hinge-axis is z 02683 frameInA.getBasis().setValue( axis1.x(), axis2.x(), axisInA.x(), 02684 axis1.y(), axis2.y(), axisInA.y(), 02685 axis1.z(), axis2.z(), axisInA.z() ); 02686 02687 frameInA.setOrigin( pivotInA ); 02688 02689 btTransform inv = rb1->getCenterOfMassTransform().inverse(); 02690 02691 btTransform globalFrameA = rb0->getCenterOfMassTransform() * frameInA; 02692 02693 frameInB = inv * globalFrameA; 02694 02695 hinge = new btHingeConstraint(*rb0,*rb1,frameInA,frameInB); 02696 02697 02698 } else 02699 { 02700 static btRigidBody s_fixedObject2( 0,0,0); 02701 02702 btTransform frameInA; 02703 btTransform frameInB; 02704 02705 btVector3 axis1(axis1X,axis1Y,axis1Z), axis2(axis2X,axis2Y,axis2Z); 02706 if (axis1.length() == 0.0) 02707 { 02708 btPlaneSpace1( axisInA, axis1, axis2 ); 02709 } 02710 02711 // Internally btHingeConstraint's hinge-axis is z 02712 frameInA.getBasis().setValue( axis1.x(), axis2.x(), axisInA.x(), 02713 axis1.y(), axis2.y(), axisInA.y(), 02714 axis1.z(), axis2.z(), axisInA.z() ); 02715 frameInA.setOrigin( pivotInA ); 02716 frameInB = rb0->getCenterOfMassTransform() * frameInA; 02717 02718 hinge = new btHingeConstraint(*rb0, s_fixedObject2, frameInA, frameInB); 02719 } 02720 hinge->setAngularOnly(angularOnly); 02721 02722 //m_constraints.push_back(hinge); 02723 m_dynamicsWorld->addConstraint(hinge,disableCollisionBetweenLinkedBodies); 02724 hinge->setUserConstraintId(gConstraintUid++); 02725 hinge->setUserConstraintType(type); 02726 //64 bit systems can't cast pointer to int. could use size_t instead. 02727 return hinge->getUserConstraintId(); 02728 break; 02729 } 02730 #ifdef NEW_BULLET_VEHICLE_SUPPORT 02731 02732 case PHY_VEHICLE_CONSTRAINT: 02733 { 02734 btRaycastVehicle::btVehicleTuning* tuning = new btRaycastVehicle::btVehicleTuning(); 02735 btRigidBody* chassis = rb0; 02736 btDefaultVehicleRaycaster* raycaster = new btDefaultVehicleRaycaster(m_dynamicsWorld); 02737 btRaycastVehicle* vehicle = new btRaycastVehicle(*tuning,chassis,raycaster); 02738 WrapperVehicle* wrapperVehicle = new WrapperVehicle(vehicle,ctrl0); 02739 m_wrapperVehicles.push_back(wrapperVehicle); 02740 m_dynamicsWorld->addVehicle(vehicle); 02741 vehicle->setUserConstraintId(gConstraintUid++); 02742 vehicle->setUserConstraintType(type); 02743 return vehicle->getUserConstraintId(); 02744 02745 break; 02746 }; 02747 #endif //NEW_BULLET_VEHICLE_SUPPORT 02748 02749 default: 02750 { 02751 } 02752 }; 02753 02754 //btRigidBody& rbA,btRigidBody& rbB, const btVector3& pivotInA,const btVector3& pivotInB 02755 02756 return 0; 02757 02758 } 02759 02760 02761 02762 PHY_IPhysicsController* CcdPhysicsEnvironment::CreateConeController(float coneradius,float coneheight) 02763 { 02764 CcdConstructionInfo cinfo; 02765 //don't memset cinfo: this is C++ and values should be set in the constructor! 02766 02767 // we don't need a CcdShapeConstructionInfo for this shape: 02768 // it is simple enough for the standard copy constructor (see CcdPhysicsController::GetReplica) 02769 cinfo.m_collisionShape = new btConeShape(coneradius,coneheight); 02770 cinfo.m_MotionState = 0; 02771 cinfo.m_physicsEnv = this; 02772 cinfo.m_collisionFlags |= btCollisionObject::CF_NO_CONTACT_RESPONSE | btCollisionObject::CF_STATIC_OBJECT; 02773 DefaultMotionState* motionState = new DefaultMotionState(); 02774 cinfo.m_MotionState = motionState; 02775 02776 // we will add later the possibility to select the filter from option 02777 cinfo.m_collisionFilterMask = CcdConstructionInfo::AllFilter ^ CcdConstructionInfo::SensorFilter; 02778 cinfo.m_collisionFilterGroup = CcdConstructionInfo::SensorFilter; 02779 cinfo.m_bSensor = true; 02780 motionState->m_worldTransform.setIdentity(); 02781 // motionState->m_worldTransform.setOrigin(btVector3(position[0],position[1],position[2])); 02782 02783 CcdPhysicsController* sphereController = new CcdPhysicsController(cinfo); 02784 02785 02786 return sphereController; 02787 } 02788 02789 float CcdPhysicsEnvironment::getAppliedImpulse(int constraintid) 02790 { 02791 int i; 02792 int numConstraints = m_dynamicsWorld->getNumConstraints(); 02793 for (i=0;i<numConstraints;i++) 02794 { 02795 btTypedConstraint* constraint = m_dynamicsWorld->getConstraint(i); 02796 if (constraint->getUserConstraintId() == constraintid) 02797 { 02798 return constraint->getAppliedImpulse(); 02799 } 02800 } 02801 02802 return 0.f; 02803 } 02804 02805 void CcdPhysicsEnvironment::exportFile(const char* filename) 02806 { 02807 btDefaultSerializer* serializer = new btDefaultSerializer(); 02808 02809 02810 for (int i=0;i<m_dynamicsWorld->getNumCollisionObjects();i++) 02811 { 02812 02813 btCollisionObject* colObj = m_dynamicsWorld->getCollisionObjectArray()[i]; 02814 02815 CcdPhysicsController* controller = static_cast<CcdPhysicsController*>(colObj->getUserPointer()); 02816 if (controller) 02817 { 02818 const char* name = controller->getName(); 02819 if (name) 02820 { 02821 serializer->registerNameForPointer(colObj,name); 02822 } 02823 } 02824 } 02825 02826 m_dynamicsWorld->serialize(serializer); 02827 02828 FILE* file = fopen(filename,"wb"); 02829 if (file) 02830 { 02831 fwrite(serializer->getBufferPointer(),serializer->getCurrentBufferSize(),1, file); 02832 fclose(file); 02833 } 02834 } 02835