btHfFluidRigidCollisionAlgorithm.cpp
Go to the documentation of this file.
00001 /*
00002  Bullet Continuous Collision Detection and Physics Library
00003  Copyright (c) 2003-2009 Erwin Coumans  http://bulletphysics.com
00004 
00005  This software is provided 'as-is', without any express or implied warranty.
00006  In no event will the authors be held liable for any damages arising from the use of this software.
00007  Permission is granted to anyone to use this software for any purpose,
00008  including commercial applications, and to alter it and redistribute it freely,
00009  subject to the following restrictions:
00010 
00011  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.
00012  2. Altered source versions must be plainly marked as such, and must not be misrepresented as being the original software.
00013  3. This notice may not be removed or altered from any source distribution.
00014 
00015  Experimental Buoyancy fluid demo written by John McCutchan
00016  */
00017 
00018 #include <stdio.h>
00019 #include <iostream>
00020 
00021 #include <uwsim/BulletHfFluid/btHfFluidRigidCollisionAlgorithm.h>
00022 #include <uwsim/BulletHfFluid/btHfFluidBuoyantConvexShape.h>
00023 #include <BulletCollision/CollisionDispatch/btCollisionDispatcher.h>
00024 #include <BulletCollision/CollisionShapes/btSphereShape.h>
00025 #include <BulletCollision/CollisionShapes/btBoxShape.h>
00026 #include <BulletCollision/CollisionDispatch/btCollisionObject.h>
00027 #include <BulletDynamics/Dynamics/btRigidBody.h>
00028 #include <uwsim/BulletHfFluid/btHfFluid.h>
00029 
00030 btHfFluidRigidCollisionAlgorithm::~btHfFluidRigidCollisionAlgorithm()
00031 {
00032 }
00033 
00034 btHfFluidRigidCollisionAlgorithm::btHfFluidRigidCollisionAlgorithm(const btCollisionAlgorithmConstructionInfo& ci,
00035                                                                    btCollisionObject* col0, btCollisionObject* col1,
00036                                                                    bool isSwapped) :
00037     btCollisionAlgorithm(ci), m_isSwapped(isSwapped), m_convexTrianglecallback(ci.m_dispatcher1, col0, col1, !isSwapped) // we flip the isSwapped because we are hf fluid vs. convex and callback expects convex vs. concave
00038 {
00039   m_manifoldPtr = m_convexTrianglecallback.m_manifoldPtr;
00040   if (m_isSwapped)
00041   {
00042     m_hfFluid = static_cast<btHfFluid*>(col1);
00043     m_rigidCollisionObject = static_cast<btCollisionObject*>(col0);
00044     m_manifoldPtr->setBodies(m_hfFluid, m_rigidCollisionObject);
00045   }
00046   else
00047   {
00048     m_hfFluid = static_cast<btHfFluid*>(col0);
00049     m_rigidCollisionObject = static_cast<btCollisionObject*>(col1);
00050     m_manifoldPtr->setBodies(m_rigidCollisionObject, m_hfFluid);
00051   }
00052 }
00053 
00054 void btHfFluidRigidCollisionAlgorithm::processGround(const btDispatcherInfo& dispatchInfo, btManifoldResult* resultOut)
00055 {
00056   btScalar triangleMargin = m_rigidCollisionObject->getCollisionShape()->getMargin();
00057   resultOut->setPersistentManifold(m_manifoldPtr);
00058   // to perform the convex shape vs. ground terrain:
00059   // we pull the convex shape out of the buoyant shape and replace it temporarily
00060   btHfFluidBuoyantConvexShape* tmpShape = (btHfFluidBuoyantConvexShape*)m_rigidCollisionObject->getCollisionShape();
00061   btConvexShape* convexShape = ((btHfFluidBuoyantConvexShape*)tmpShape)->getConvexShape();
00062   m_rigidCollisionObject->setCollisionShape(convexShape);
00063   m_convexTrianglecallback.setTimeStepAndCounters(triangleMargin, dispatchInfo, resultOut);
00064   m_hfFluid->foreachGroundTriangle(&m_convexTrianglecallback, m_convexTrianglecallback.getAabbMin(),
00065                                    m_convexTrianglecallback.getAabbMax());
00066   resultOut->refreshContactPoints();
00067   // restore the buoyant shape
00068   m_rigidCollisionObject->setCollisionShape(tmpShape);
00069 }
00070 
00071 btScalar btHfFluidRigidCollisionAlgorithm::processFluid(const btDispatcherInfo& dispatchInfo, btScalar density,
00072                                                         btScalar floatyness)
00073 {
00074   btRigidBody* rb = btRigidBody::upcast(m_rigidCollisionObject);
00075   btHfFluidColumnRigidBodyCallback columnCallback(rb, dispatchInfo.m_debugDraw, density, floatyness);
00076   m_hfFluid->foreachFluidColumn(&columnCallback, m_convexTrianglecallback.getAabbMin(),
00077                                 m_convexTrianglecallback.getAabbMax());
00078   return columnCallback.getVolume();
00079 }
00080 
00081 void btHfFluidRigidCollisionAlgorithm::applyFluidFriction(btScalar mu, btScalar submerged_percentage)
00082 {
00083   btRigidBody* rb = btRigidBody::upcast(m_rigidCollisionObject);
00084   btScalar dt = btScalar(1.0f / 60.0f);
00085 
00086 //#define OLD_WAY
00087 #ifdef OLD_WAY
00088   btScalar radius = btScalar(0.0f);
00089   {
00090     btVector3 aabbMin, aabbMax;
00091     btTransform T;
00092     T.setIdentity();
00093     rb->getCollisionShape()->getAabb (T, aabbMin, aabbMax);
00094     radius = (aabbMax-aabbMin).length()*btScalar(0.5);
00095   }
00096   btScalar viscosity = btScalar(0.05);
00097   btVector3 force = btScalar(6.0f) * SIMD_PI * viscosity * radius * -rb->getLinearVelocity();
00098 
00099   btVector3 impulse = force * dt;
00100   rb->applyCentralImpulse (impulse);
00101 
00102   if (true)
00103   {
00104     btVector3 av = rb->getAngularVelocity();
00105     av *= btScalar(0.99);
00106     rb->setAngularVelocity (av);
00107   }
00108 #else
00109   btScalar scaled_mu = mu * submerged_percentage * btScalar(0.4f);
00110 
00111   /*std::cout<<dt<<" "<<scaled_mu<<" "<<rb->getLinearVelocity().x()<<" "<<rb->getLinearVelocity().y()<<" "<<rb->getLinearVelocity().z()<<std::endl;
00112    std::cout<<dt<<" "<<scaled_mu<<" "<<rb->getAngularVelocity().x()<<" "<<rb->getAngularVelocity().y()<<" "<<rb->getAngularVelocity().z()<<std::endl;
00113    std::cout<<"COLLISIOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOON"<<std::endl;*/
00114   rb->applyCentralImpulse(dt * scaled_mu * -rb->getLinearVelocity());
00115   rb->applyTorqueImpulse(dt * scaled_mu * -rb->getAngularVelocity());
00116 #endif
00117 }
00118 
00119 void btHfFluidRigidCollisionAlgorithm::processCollision(btCollisionObject* body0, btCollisionObject* body1,
00120                                                         const btDispatcherInfo& dispatchInfo,
00121                                                         btManifoldResult* resultOut)
00122 {
00123   processGround(dispatchInfo, resultOut);
00124   btHfFluidBuoyantConvexShape* buoyantShape = (btHfFluidBuoyantConvexShape*)m_rigidCollisionObject->getCollisionShape();
00125   btRigidBody* rb = btRigidBody::upcast(m_rigidCollisionObject);
00126   if (rb)
00127   {
00128 
00129     btScalar mass = btScalar(1.0f) / rb->getInvMass();
00130     btScalar volume = buoyantShape->getTotalVolume();
00131     btScalar density = mass / volume;
00132     btScalar floatyness = buoyantShape->getFloatyness();
00133     btScalar submerged_volume = processFluid(dispatchInfo, density, floatyness);
00134     if (submerged_volume > btScalar(0.0))
00135     {
00136       btScalar submerged_percentage = submerged_volume / buoyantShape->getTotalVolume();
00137       //printf("%f\n", submerged_percentage);
00138       btScalar mu = btScalar(6.0f);
00139       applyFluidFriction(mu, submerged_percentage);
00140     }
00141   }
00142 }
00143 
00144 btScalar btHfFluidRigidCollisionAlgorithm::calculateTimeOfImpact(btCollisionObject* body0, btCollisionObject* body1,
00145                                                                  const btDispatcherInfo& dispatchInfo,
00146                                                                  btManifoldResult* resultOut)
00147 {
00148   return btScalar(1.0);
00149 }


uwsim
Author(s): Mario Prats
autogenerated on Mon Oct 6 2014 08:24:07