Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include <stdio.h>
00018
00019 #include <LinearMath/btAabbUtil2.h>
00020 #include <BulletCollision/CollisionShapes/btConvexShape.h>
00021 #include <BulletCollision/CollisionShapes/btSphereShape.h>
00022 #include <BulletCollision/NarrowPhaseCollision/btGjkPairDetector.h>
00023 #include <BulletCollision/NarrowPhaseCollision/btVoronoiSimplexSolver.h>
00024 #include <BulletCollision/NarrowPhaseCollision/btMinkowskiPenetrationDepthSolver.h>
00025 #include <BulletCollision/NarrowPhaseCollision/btDiscreteCollisionDetectorInterface.h>
00026
00027 #include <uwsim/BulletHfFluid/btHfFluidBuoyantConvexShape.h>
00028
00029 btHfFluidBuoyantConvexShape::btHfFluidBuoyantConvexShape(btConvexShape* convexShape)
00030 {
00031 m_convexShape = convexShape;
00032 m_shapeType = HFFLUID_BUOYANT_CONVEX_SHAPE_PROXYTYPE;
00033 m_radius = btScalar(0.f);
00034 m_numVoxels = 0;
00035 m_voxelPositions = NULL;
00036 m_totalVolume = btScalar(0.0f);
00037 m_floatyness = btScalar(1.5f);
00038 }
00039
00040 btHfFluidBuoyantConvexShape::~btHfFluidBuoyantConvexShape()
00041 {
00042 if (m_voxelPositions)
00043 btAlignedFree (m_voxelPositions);
00044 }
00045
00046 void btHfFluidBuoyantConvexShape::getAabb(const btTransform& t, btVector3& aabbMin, btVector3& aabbMax) const
00047 {
00048 return m_convexShape->getAabb(t, aabbMin, aabbMax);
00049 }
00050
00051 void btHfFluidBuoyantConvexShape::setMargin(btScalar margin)
00052 {
00053 m_convexShape->setMargin(margin);
00054 }
00055
00056 void btHfFluidBuoyantConvexShape::setLocalScaling(const btVector3& scaling)
00057 {
00058 m_convexShape->setLocalScaling(scaling);
00059 }
00060
00061 const char* btHfFluidBuoyantConvexShape::getName() const
00062 {
00063 return "HF_FLUID_BUOYANT_CONVEX_SHAPE";
00064 }
00065
00066 const btVector3& btHfFluidBuoyantConvexShape::getLocalScaling() const
00067 {
00068 return m_convexShape->getLocalScaling();
00069 }
00070
00071 void btHfFluidBuoyantConvexShape::calculateLocalInertia(btScalar mass, btVector3& inertia) const
00072 {
00073 m_convexShape->calculateLocalInertia(mass, inertia);
00074 }
00075
00076 btScalar btHfFluidBuoyantConvexShape::getMargin() const
00077 {
00078 return m_convexShape->getMargin();
00079 }
00080
00081
00082 #define REL_ERROR2 btScalar(1.0e-6)
00083 static bool intersect(btVoronoiSimplexSolver* simplexSolver, const btTransform& transformA,
00084 const btTransform& transformB, btConvexShape* a, btConvexShape* b)
00085 {
00086
00087 btScalar squaredDistance = SIMD_INFINITY;
00088 btTransform localTransA = transformA;
00089 btTransform localTransB = transformB;
00090 btVector3 positionOffset = (localTransA.getOrigin() + localTransB.getOrigin()) * btScalar(0.5);
00091 localTransA.getOrigin() -= positionOffset;
00092 localTransB.getOrigin() -= positionOffset;
00093 btScalar delta = btScalar(0.);
00094 btVector3 v = btVector3(1.0f, 0.0f, 0.0f);
00095 simplexSolver->reset();
00096 do
00097 {
00098 btVector3 seperatingAxisInA = (-v) * transformA.getBasis();
00099 btVector3 seperatingAxisInB = v * transformB.getBasis();
00100
00101 btVector3 pInA = a->localGetSupportVertexNonVirtual(seperatingAxisInA);
00102 btVector3 qInB = b->localGetSupportVertexNonVirtual(seperatingAxisInB);
00103
00104 btVector3 pWorld = localTransA(pInA);
00105 btVector3 qWorld = localTransB(qInB);
00106
00107 btVector3 w = pWorld - qWorld;
00108 delta = v.dot(w);
00109
00110
00111 if ((delta > btScalar(0.0)))
00112 {
00113 return false;
00114 }
00115
00116 if (simplexSolver->inSimplex(w))
00117 {
00118 return false;
00119 }
00120
00121 simplexSolver->addVertex(w, pWorld, qWorld);
00122
00123 if (!simplexSolver->closest(v))
00124 {
00125 return false;
00126 }
00127
00128 btScalar previousSquaredDistance = squaredDistance;
00129 squaredDistance = v.length2();
00130
00131 if (previousSquaredDistance - squaredDistance <= SIMD_EPSILON * previousSquaredDistance)
00132 {
00133 return false;
00134 }
00135 } while (!simplexSolver->fullSimplex() && squaredDistance > REL_ERROR2 * simplexSolver->maxVertex());
00136
00137 return true;
00138 }
00139
00140 void btHfFluidBuoyantConvexShape::generateShape(btScalar radius, btScalar gap)
00141 {
00142 btTransform T;
00143 T.setIdentity();
00144 btVector3 aabbMin, aabbMax;
00145 getAabb(T, aabbMin, aabbMax);
00146
00147 m_radius = radius;
00148 m_numVoxels = 0;
00149
00150 btVoronoiSimplexSolver simplexSolver;
00151 btSphereShape sphereShape(radius);
00152 btVector3* voxelPositions = (btVector3*)btAlignedAlloc(
00153 sizeof(btVector3) * MAX_VOXEL_DIMENSION * MAX_VOXEL_DIMENSION * MAX_VOXEL_DIMENSION, 16);
00154 for (int i = 0; i < MAX_VOXEL_DIMENSION; i++)
00155 {
00156 for (int j = 0; j < MAX_VOXEL_DIMENSION; j++)
00157 {
00158 for (int k = 0; k < MAX_VOXEL_DIMENSION; k++)
00159 {
00160 btVector3 point;
00161 btTransform sT;
00162 sT.setIdentity();
00163
00164 point.setX(aabbMin.getX() + (i * btScalar(2.0f) * radius) + (i * gap));
00165 point.setY(aabbMin.getY() + (j * btScalar(2.0f) * radius) + (j * gap));
00166 point.setZ(aabbMin.getZ() + (k * btScalar(2.0f) * radius) + (k * gap));
00167
00168 if (TestPointAgainstAabb2(aabbMin, aabbMax, point))
00169 {
00170 btTransform sT;
00171 sT.setIdentity();
00172 sT.setOrigin(point);
00173
00174 if (intersect(&simplexSolver, T, sT, m_convexShape, &sphereShape))
00175 {
00176 voxelPositions[m_numVoxels] = point;
00177 m_numVoxels++;
00178 }
00179 }
00180 }
00181 }
00182 }
00183 m_voxelPositions = (btVector3*)btAlignedAlloc(sizeof(btVector3) * m_numVoxels, 16);
00184 for (int i = 0; i < m_numVoxels; i++)
00185 {
00186 m_voxelPositions[i] = voxelPositions[i];
00187 }
00188 btAlignedFree(voxelPositions);
00189 m_volumePerVoxel = btScalar(4.0f) / btScalar(3.0f) * SIMD_PI * radius * radius * radius;
00190 m_totalVolume = m_numVoxels * m_volumePerVoxel;
00191 m_radius = radius;
00192 }
00193