btHfFluid.h
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 #ifndef __HFFLUID_H
00019 #define __HFFLUID_H
00020 
00021 #include "BulletCollision/CollisionDispatch/btCollisionObject.h"
00022 #include "BulletCollision/CollisionShapes/btTriangleCallback.h"
00023 
00024 class btPersistentManifold;
00025 class btManifoldResult;
00026 
00027 // FIX AABB calculation for whole btHfFluid shape
00028 // Fix flags and fill ratio
00029 // -> Figure out the constants used in flags and fill ratio code
00030 // Fix volume removal
00031 // add buoyant convex vs. convex / concave
00032 // add buoyant concave support (try bunny model)
00033 
00035 class btHfFluid : public btCollisionObject
00036 {
00037 public:
00038   btHfFluid(btScalar gridCellWidth, int numNodesWidth, int numNodesLength);
00039   btHfFluid(btScalar gridCellWidth, int minX, int maxX, int minY, int maxY, int depth, int height);
00040 
00041   ~btHfFluid();
00042 
00043   void predictMotion(btScalar dt);
00044 
00045   /* Prep does some initial setup of the height field fluid.
00046    * You should call this at initialization time.
00047    */
00048   void prep();
00049 
00050   static const btHfFluid* upcast(const btCollisionObject* colObj)
00051   {
00052     if (colObj->getInternalType() == CO_HF_FLUID)
00053       return (const btHfFluid*)colObj;
00054     return 0;
00055   }
00056   static btHfFluid* upcast(btCollisionObject* colObj)
00057   {
00058     if (colObj->getInternalType() == CO_HF_FLUID)
00059       return (btHfFluid*)colObj;
00060     return 0;
00061   }
00062 
00063   //
00064   // ::btCollisionObject
00065   //
00066 
00067   virtual void getAabb(btVector3& aabbMin, btVector3& aabbMax) const
00068   {
00069     aabbMin = m_aabbMin;
00070     aabbMax = m_aabbMax;
00071   }
00072 
00073   int getNumNodesWidth() const
00074   {
00075     return m_numNodesWidth;
00076   }
00077   int getNumNodesLength() const
00078   {
00079     return m_numNodesLength;
00080   }
00081 
00082   btScalar getGridCellWidth() const
00083   {
00084     return m_gridCellWidth;
00085   }
00086   btScalar widthPos(int i) const;
00087   btScalar lengthPos(int j) const;
00088 
00089   int arrayIndex(int i, int j) const;
00090   int arrayIndex(btScalar i, btScalar j) const;
00091   int arrayIndex(unsigned int i, unsigned int j) const;
00092   const btScalar* getHeightArray() const;
00093   const btScalar* getGroundArray() const;
00094   const btScalar* getEtaArray() const;
00095   const btScalar* getVelocityUArray() const;
00096   const btScalar* getVelocityVArray() const;
00097   const bool* getFlagsArray() const;
00098 
00099   void setFluidHeight(int x, int y, btScalar height);
00100   void setFluidHeight(int index, btScalar height);
00101 
00102   void addFluidHeight(int x, int y, btScalar height);
00103   void addDisplaced(int i, int j, btScalar r);
00104 
00105   void getAabbForColumn(int x, int y, btVector3& aabbMin, btVector3& aabbMax);
00106 
00107   btScalar* getHeightArray();
00108   btScalar* getGroundArray();
00109   btScalar* getEtaArray();
00110   btScalar* getVelocityUArray();
00111   btScalar* getVelocityVArray();
00112   bool* getFlagsArray();
00113 
00114   void foreachGroundTriangle(btTriangleCallback* callback, const btVector3& aabbMin, const btVector3& aabbMax);
00115   class btHfFluidColumnCallback
00116   {
00117   public:
00118     btHfFluidColumnCallback()
00119     {
00120     }
00121 
00122     virtual ~btHfFluidColumnCallback()
00123     {
00124     }
00125 
00126     virtual bool processColumn(btHfFluid* fluid, int w, int l)
00127     {
00128       return true; // keep going
00129     }
00130   };
00131 
00132   void foreachFluidColumn(btHfFluidColumnCallback* callback, const btVector3& aabbMin, const btVector3& aabbMax);
00133 
00134   void foreachSurfaceTriangle(btTriangleCallback* callback, const btVector3& aabbMin, const btVector3& aabbMax);
00135 protected:
00136   int m_numNodesWidth;
00137   int m_numNodesLength;
00138 
00139   btScalar m_gridCellWidth;
00140   btScalar m_gridWidth;
00141   btScalar m_gridLength;
00142 
00143   btScalar m_gridCellWidthInv;
00144 
00145   btVector3 m_aabbMin;
00146   btVector3 m_aabbMax;
00147 
00148   void setGridDimensions(btScalar gridCellWidth, int numNodesWidth, int numNodesLength);
00149 
00150   btScalar bilinearInterpolate(const btScalar* array, btScalar i, btScalar j);
00151 
00152   btScalar advect(const btScalar* array, btScalar i, btScalar j, btScalar di, btScalar dj, btScalar dt);
00153 
00154   void advectEta(btScalar dt);
00155   void updateHeight(btScalar dt);
00156 
00157   void advectVelocityU(btScalar dt);
00158   void advectVelocityV(btScalar dt);
00159   void updateVelocity(btScalar dt);
00160 
00161   void transferDisplaced(btScalar dt);
00162 
00163   void setReflectBoundaryLeft();
00164   void setReflectBoundaryRight();
00165   void setReflectBoundaryTop();
00166   void setReflectBoundaryBottom();
00167 
00168   void setAbsorbBoundaryLeft(btScalar dt);
00169   void setAbsorbBoundaryRight(btScalar dt);
00170   void setAbsorbBoundaryTop(btScalar dt);
00171   void setAbsorbBoundaryBottom(btScalar dt);
00172 
00173   void computeFlagsAndFillRatio();
00174   btScalar computeHmin(int i, int j);
00175   btScalar computeHmax(int i, int j);
00176   btScalar computeEtaMax(int i, int j);
00177 
00178   void allocateArrays();
00179 
00180   void debugTests();
00181 
00182   btScalar* m_temp; // temp
00183   int m_heightIndex;
00184   btScalar* m_height[2];
00185   btScalar* m_ground;
00186   btScalar* m_eta; // height - ground
00187   btScalar* m_u[2];
00188   btScalar* m_v[2];
00189   int m_rIndex;
00190   btScalar* m_r[2];
00191   int m_velocityIndex;
00192   bool* m_flags;
00193   btScalar* m_fillRatio;
00194 
00195   // tweakables
00196   btScalar m_globalVelocityU;
00197   btScalar m_globalVelocityV;
00198   btScalar m_gravity;
00199   btScalar m_volumeDisplacementScale;
00200   btScalar m_horizontalVelocityScale;
00201 
00202   btScalar m_epsHeight;
00203   btScalar m_epsEta;
00204 public:
00205   // You can enforce a global velocity at the surface of the fluid
00206   // default: 0.0 and 0.0
00207   void setGlobaVelocity(btScalar globalVelocityU, btScalar globalVelocityV);
00208   void getGlobalVelocity(btScalar& globalVelocityU, btScalar& globalVelocityV) const;
00209 
00210   // Control force of gravity, should match physics world
00211   // default: -10.0
00212   void setGravity(btScalar gravity);
00213   btScalar getGravity() const;
00214 
00215   // When a body is submerged into the fluid, the displaced fluid
00216   // is spread to adjacent cells. You can control the percentage of this
00217   // by setting this value between 0.0 and 1.0
00218   // default: 0.5
00219   void setVolumeDisplacementScale(btScalar volumeDisplacementScale);
00220   btScalar getVolumeDisplacementScale() const;
00221 
00222   // The horizontal velocity of the fluid can influence bodies submerged
00223   // in the fluid. You can control how much influence by setting this
00224   // between 0.0 and 1.0
00225   // default: 0.5
00226   void setHorizontalVelocityScale(btScalar horizontalVelocityScale);
00227   btScalar getHorizontalVelocityScale() const;
00228 };
00229 
00230 class btRigidBody;
00231 class btIDebugDraw;
00232 class btHfFluidBuoyantConvexShape;
00233 
00234 class btHfFluidColumnRigidBodyCallback : public btHfFluid::btHfFluidColumnCallback
00235 {
00236 protected:
00237   btRigidBody* m_rigidBody;
00238   btHfFluidBuoyantConvexShape* m_buoyantShape;
00239   btIDebugDraw* m_debugDraw;
00240   int m_numVoxels;
00241   btVector3* m_voxelPositionsXformed;
00242   bool* m_voxelSubmerged;
00243   btVector3 m_aabbMin;
00244   btVector3 m_aabbMax;
00245   btScalar m_volume;
00246   btScalar m_density;
00247   btScalar m_floatyness;
00248 public:
00249   btHfFluidColumnRigidBodyCallback(btRigidBody* rigidBody, btIDebugDraw* debugDraw, btScalar density,
00250                                    btScalar floatyness);
00251   ~btHfFluidColumnRigidBodyCallback();
00252   bool processColumn(btHfFluid* fluid, int w, int l);
00253   btScalar getVolume() const
00254   {
00255     return m_volume;
00256   }
00257 };
00258 
00259 #endif
00260 


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