mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-14 22:00:05 +00:00
Merge branch 'master' of https://github.com/erwincoumans/bullet3
This commit is contained in:
commit
bdf7e3f61f
@ -7,6 +7,7 @@
|
||||
#include "Bullet3Common/b3Scalar.h"
|
||||
#include "CollisionShape2TriangleMesh.h"
|
||||
|
||||
#include "../OpenGLWindow/ShapeData.h"
|
||||
|
||||
#include "../OpenGLWindow/SimpleCamera.h"
|
||||
#include "../OpenGLWindow/GLInstanceGraphicsShape.h"
|
||||
@ -35,6 +36,8 @@ ATTRIBUTE_ALIGNED16( class )MyDebugDrawer : public btIDebugDraw
|
||||
|
||||
btAlignedObjectArray<MyDebugVec3> m_linePoints;
|
||||
btAlignedObjectArray<unsigned int> m_lineIndices;
|
||||
|
||||
|
||||
btVector3 m_currentLineColor;
|
||||
DefaultColors m_ourColors;
|
||||
|
||||
@ -133,14 +136,67 @@ public:
|
||||
|
||||
static btVector4 sColors[4] =
|
||||
{
|
||||
btVector4(0.3,0.3,1,1),
|
||||
btVector4(0.6,0.6,1,1),
|
||||
btVector4(0,1,0,1),
|
||||
btVector4(0,1,1,1),
|
||||
btVector4(60./256.,186./256.,84./256.,1),
|
||||
btVector4(244./256.,194./256.,13./256.,1),
|
||||
btVector4(219./256.,50./256.,54./256.,1),
|
||||
btVector4(72./256.,133./256.,237./256.,1),
|
||||
|
||||
//btVector4(1,1,0,1),
|
||||
};
|
||||
|
||||
|
||||
|
||||
struct MyHashShape
|
||||
{
|
||||
|
||||
int m_shapeKey;
|
||||
int m_shapeType;
|
||||
btVector3 m_sphere0Pos;
|
||||
btVector3 m_sphere1Pos;
|
||||
btScalar m_radius0;
|
||||
btScalar m_radius1;
|
||||
btTransform m_childTransform;
|
||||
int m_deformFunc;
|
||||
int m_upAxis;
|
||||
btScalar m_halfHeight;
|
||||
|
||||
MyHashShape()
|
||||
:m_shapeKey(0),
|
||||
m_shapeType(0),
|
||||
m_sphere0Pos(btVector3(0,0,0)),
|
||||
m_sphere1Pos(btVector3(0,0,0)),
|
||||
m_radius0(0),
|
||||
m_radius1(0),
|
||||
m_deformFunc(0),
|
||||
m_upAxis(-1),
|
||||
m_halfHeight(0)
|
||||
{
|
||||
m_childTransform.setIdentity();
|
||||
}
|
||||
|
||||
bool equals(const MyHashShape& other) const
|
||||
{
|
||||
bool sameShapeType = m_shapeType==other.m_shapeType;
|
||||
bool sameSphere0= m_sphere0Pos == other.m_sphere0Pos;
|
||||
bool sameSphere1= m_sphere1Pos == other.m_sphere1Pos;
|
||||
bool sameRadius0 = m_radius0== other.m_radius0;
|
||||
bool sameRadius1 = m_radius1== other.m_radius1;
|
||||
bool sameTransform = m_childTransform== other.m_childTransform;
|
||||
bool sameUpAxis = m_upAxis == other.m_upAxis;
|
||||
bool sameHalfHeight = m_halfHeight == other.m_halfHeight;
|
||||
return sameShapeType && sameSphere0 && sameSphere1 && sameRadius0 && sameRadius1 && sameTransform && sameUpAxis && sameHalfHeight;
|
||||
}
|
||||
//to our success
|
||||
SIMD_FORCE_INLINE unsigned int getHash()const
|
||||
{
|
||||
unsigned int key = m_shapeKey;
|
||||
// Thomas Wang's hash
|
||||
key += ~(key << 15); key ^= (key >> 10); key += (key << 3); key ^= (key >> 6); key += ~(key << 11); key ^= (key >> 16);
|
||||
|
||||
return key;
|
||||
}
|
||||
};
|
||||
|
||||
struct OpenGLGuiHelperInternalData
|
||||
{
|
||||
struct CommonGraphicsApp* m_glApp;
|
||||
@ -150,12 +206,20 @@ struct OpenGLGuiHelperInternalData
|
||||
|
||||
btAlignedObjectArray<unsigned char> m_rgbaPixelBuffer1;
|
||||
btAlignedObjectArray<float> m_depthBuffer1;
|
||||
|
||||
btHashMap<MyHashShape, int> m_hashShapes;
|
||||
|
||||
|
||||
VisualizerFlagCallback m_visualizerFlagCallback;
|
||||
|
||||
int m_checkedTexture;
|
||||
int m_checkedTextureGrey;
|
||||
|
||||
OpenGLGuiHelperInternalData()
|
||||
:m_vrMode(false),
|
||||
m_vrSkipShadowPass(0),
|
||||
m_visualizerFlagCallback(0)
|
||||
m_visualizerFlagCallback(0),
|
||||
m_checkedTexture(-1),
|
||||
m_checkedTextureGrey(-1)
|
||||
{
|
||||
}
|
||||
|
||||
@ -238,6 +302,7 @@ int OpenGLGuiHelper::registerGraphicsInstance(int shapeIndex, const float* posit
|
||||
|
||||
void OpenGLGuiHelper::removeAllGraphicsInstances()
|
||||
{
|
||||
m_data->m_hashShapes.clear();
|
||||
m_data->m_glApp->m_renderer->removeAllInstances();
|
||||
}
|
||||
|
||||
@ -249,6 +314,45 @@ void OpenGLGuiHelper::removeGraphicsInstance(int graphicsUid)
|
||||
};
|
||||
}
|
||||
|
||||
int OpenGLGuiHelper::createCheckeredTexture(int red,int green, int blue)
|
||||
{
|
||||
int texWidth=1024;
|
||||
int texHeight=1024;
|
||||
btAlignedObjectArray<unsigned char> texels;
|
||||
texels.resize(texWidth*texHeight*3);
|
||||
for (int i=0;i<texWidth*texHeight*3;i++)
|
||||
texels[i]=255;
|
||||
|
||||
|
||||
for (int i=0;i<texWidth;i++)
|
||||
{
|
||||
for (int j=0;j<texHeight;j++)
|
||||
{
|
||||
int a = i<texWidth/2? 1 : 0;
|
||||
int b = j<texWidth/2? 1 : 0;
|
||||
|
||||
if (a==b)
|
||||
{
|
||||
texels[(i+j*texWidth)*3+0] = red;
|
||||
texels[(i+j*texWidth)*3+1] = green;
|
||||
texels[(i+j*texWidth)*3+2] = blue;
|
||||
// texels[(i+j*texWidth)*4+3] = 255;
|
||||
|
||||
}
|
||||
/*else
|
||||
{
|
||||
texels[i*3+0+j*texWidth] = 255;
|
||||
texels[i*3+1+j*texWidth] = 255;
|
||||
texels[i*3+2+j*texWidth] = 255;
|
||||
}
|
||||
*/
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
int texId = registerTexture(&texels[0],texWidth,texHeight);
|
||||
return texId;
|
||||
}
|
||||
|
||||
void OpenGLGuiHelper::createCollisionShapeGraphicsObject(btCollisionShape* collisionShape)
|
||||
{
|
||||
@ -256,10 +360,472 @@ void OpenGLGuiHelper::createCollisionShapeGraphicsObject(btCollisionShape* colli
|
||||
if (collisionShape->getUserIndex()>=0)
|
||||
return;
|
||||
|
||||
btAlignedObjectArray<GLInstanceVertex> gfxVertices;
|
||||
if (m_data->m_checkedTexture<0)
|
||||
{
|
||||
m_data->m_checkedTexture = createCheckeredTexture(192,192,255);
|
||||
}
|
||||
|
||||
if (m_data->m_checkedTextureGrey<0)
|
||||
{
|
||||
m_data->m_checkedTextureGrey = createCheckeredTexture(192,192,192);
|
||||
}
|
||||
|
||||
|
||||
btAlignedObjectArray<GLInstanceVertex> gfxVertices;
|
||||
btAlignedObjectArray<int> indices;
|
||||
int strideInBytes = 9*sizeof(float);
|
||||
//if (collisionShape->getShapeType()==BOX_SHAPE_PROXYTYPE)
|
||||
{
|
||||
}
|
||||
if (collisionShape->getShapeType()==MULTI_SPHERE_SHAPE_PROXYTYPE)
|
||||
{
|
||||
btMultiSphereShape* ms = (btMultiSphereShape*) collisionShape;
|
||||
if (ms->getSphereCount()==2)
|
||||
{
|
||||
btAlignedObjectArray<float> transformedVertices;
|
||||
int numVertices = sizeof(textured_detailed_sphere_vertices)/strideInBytes;
|
||||
transformedVertices.resize(numVertices*9);
|
||||
btVector3 sphere0Pos = ms->getSpherePosition(0);
|
||||
btVector3 sphere1Pos = ms->getSpherePosition(1);
|
||||
btVector3 fromTo = sphere1Pos-sphere0Pos;
|
||||
MyHashShape shape;
|
||||
shape.m_sphere0Pos = sphere0Pos;
|
||||
shape.m_sphere1Pos = sphere1Pos;
|
||||
shape.m_radius0 = 2.*ms->getSphereRadius(0);
|
||||
shape.m_radius1 = 2.*ms->getSphereRadius(1);
|
||||
shape.m_deformFunc = 1;//vert.dot(fromTo)
|
||||
int graphicsShapeIndex = -1;
|
||||
int* graphicsShapeIndexPtr = m_data->m_hashShapes[shape];
|
||||
|
||||
if (graphicsShapeIndexPtr)
|
||||
{
|
||||
//cache hit
|
||||
graphicsShapeIndex = *graphicsShapeIndexPtr;
|
||||
} else
|
||||
{
|
||||
//cache miss
|
||||
for (int i=0;i<numVertices;i++)
|
||||
{
|
||||
btVector3 vert;
|
||||
vert.setValue(textured_detailed_sphere_vertices[i*9+0],
|
||||
textured_detailed_sphere_vertices[i*9+1],
|
||||
textured_detailed_sphere_vertices[i*9+2]);
|
||||
|
||||
btVector3 trVer(0,0,0);
|
||||
|
||||
if (vert.dot(fromTo)>0)
|
||||
{
|
||||
btScalar radiusScale = 2.*ms->getSphereRadius(1);
|
||||
trVer = radiusScale*vert;
|
||||
trVer+=sphere1Pos;
|
||||
} else
|
||||
{
|
||||
btScalar radiusScale = 2.*ms->getSphereRadius(0);
|
||||
trVer = radiusScale*vert;
|
||||
trVer+=sphere0Pos;
|
||||
}
|
||||
|
||||
transformedVertices[i*9+0] = trVer[0];
|
||||
transformedVertices[i*9+1] = trVer[1];
|
||||
transformedVertices[i*9+2] = trVer[2];
|
||||
transformedVertices[i*9+3] =textured_detailed_sphere_vertices[i*9+3];
|
||||
transformedVertices[i*9+4] =textured_detailed_sphere_vertices[i*9+4];
|
||||
transformedVertices[i*9+5] =textured_detailed_sphere_vertices[i*9+5];
|
||||
transformedVertices[i*9+6] =textured_detailed_sphere_vertices[i*9+6];
|
||||
transformedVertices[i*9+7] =textured_detailed_sphere_vertices[i*9+7];
|
||||
transformedVertices[i*9+8] =textured_detailed_sphere_vertices[i*9+8];
|
||||
}
|
||||
|
||||
int numIndices = sizeof(textured_detailed_sphere_indices)/sizeof(int);
|
||||
graphicsShapeIndex = registerGraphicsShape(&transformedVertices[0],numVertices,textured_detailed_sphere_indices,numIndices,B3_GL_TRIANGLES,m_data->m_checkedTextureGrey);
|
||||
|
||||
m_data->m_hashShapes.insert(shape,graphicsShapeIndex);
|
||||
}
|
||||
collisionShape->setUserIndex(graphicsShapeIndex);
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
if (collisionShape->getShapeType()==SPHERE_SHAPE_PROXYTYPE)
|
||||
{
|
||||
btSphereShape* sphereShape = (btSphereShape*) collisionShape;
|
||||
btScalar radius = sphereShape->getRadius();
|
||||
btScalar sphereSize = 2.*radius;
|
||||
btVector3 radiusScale(sphereSize,sphereSize,sphereSize);
|
||||
btAlignedObjectArray<float> transformedVertices;
|
||||
|
||||
|
||||
MyHashShape shape;
|
||||
shape.m_radius0 = sphereSize;
|
||||
shape.m_deformFunc = 0;////no deform
|
||||
int graphicsShapeIndex = -1;
|
||||
int* graphicsShapeIndexPtr = m_data->m_hashShapes[shape];
|
||||
|
||||
if (graphicsShapeIndexPtr)
|
||||
{
|
||||
graphicsShapeIndex = *graphicsShapeIndexPtr;
|
||||
} else
|
||||
{
|
||||
int numVertices = sizeof(textured_detailed_sphere_vertices)/strideInBytes;
|
||||
transformedVertices.resize(numVertices*9);
|
||||
for (int i=0;i<numVertices;i++)
|
||||
{
|
||||
|
||||
btVector3 vert;
|
||||
vert.setValue(textured_detailed_sphere_vertices[i*9+0],
|
||||
textured_detailed_sphere_vertices[i*9+1],
|
||||
textured_detailed_sphere_vertices[i*9+2]);
|
||||
|
||||
btVector3 trVer = radiusScale*vert;
|
||||
transformedVertices[i*9+0] = trVer[0];
|
||||
transformedVertices[i*9+1] = trVer[1];
|
||||
transformedVertices[i*9+2] = trVer[2];
|
||||
transformedVertices[i*9+3] =textured_detailed_sphere_vertices[i*9+3];
|
||||
transformedVertices[i*9+4] =textured_detailed_sphere_vertices[i*9+4];
|
||||
transformedVertices[i*9+5] =textured_detailed_sphere_vertices[i*9+5];
|
||||
transformedVertices[i*9+6] =textured_detailed_sphere_vertices[i*9+6];
|
||||
transformedVertices[i*9+7] =textured_detailed_sphere_vertices[i*9+7];
|
||||
transformedVertices[i*9+8] =textured_detailed_sphere_vertices[i*9+8];
|
||||
}
|
||||
|
||||
int numIndices = sizeof(textured_detailed_sphere_indices)/sizeof(int);
|
||||
graphicsShapeIndex = registerGraphicsShape(&transformedVertices[0],numVertices,textured_detailed_sphere_indices,numIndices,B3_GL_TRIANGLES,m_data->m_checkedTextureGrey);
|
||||
m_data->m_hashShapes.insert(shape,graphicsShapeIndex);
|
||||
}
|
||||
|
||||
collisionShape->setUserIndex(graphicsShapeIndex);
|
||||
return;
|
||||
}
|
||||
if (collisionShape->getShapeType()==COMPOUND_SHAPE_PROXYTYPE)
|
||||
{
|
||||
btCompoundShape* compound = (btCompoundShape*)collisionShape;
|
||||
if (compound->getNumChildShapes()==1)
|
||||
{
|
||||
if (compound->getChildShape(0)->getShapeType()==SPHERE_SHAPE_PROXYTYPE)
|
||||
{
|
||||
btSphereShape* sphereShape = (btSphereShape*) compound->getChildShape(0);
|
||||
btScalar radius = sphereShape->getRadius();
|
||||
btScalar sphereSize = 2.*radius;
|
||||
btVector3 radiusScale(sphereSize,sphereSize,sphereSize);
|
||||
|
||||
MyHashShape shape;
|
||||
shape.m_radius0 = sphereSize;
|
||||
shape.m_deformFunc = 0;//no deform
|
||||
shape.m_childTransform = compound->getChildTransform(0);
|
||||
|
||||
int graphicsShapeIndex = -1;
|
||||
int* graphicsShapeIndexPtr = m_data->m_hashShapes[shape];
|
||||
|
||||
if (graphicsShapeIndexPtr)
|
||||
{
|
||||
graphicsShapeIndex = *graphicsShapeIndexPtr;
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
btAlignedObjectArray<float> transformedVertices;
|
||||
int numVertices = sizeof(textured_detailed_sphere_vertices)/strideInBytes;
|
||||
transformedVertices.resize(numVertices*9);
|
||||
for (int i=0;i<numVertices;i++)
|
||||
{
|
||||
|
||||
btVector3 vert;
|
||||
vert.setValue(textured_detailed_sphere_vertices[i*9+0],
|
||||
textured_detailed_sphere_vertices[i*9+1],
|
||||
textured_detailed_sphere_vertices[i*9+2]);
|
||||
|
||||
btVector3 trVer = compound->getChildTransform(0)*(radiusScale*vert);
|
||||
transformedVertices[i*9+0] = trVer[0];
|
||||
transformedVertices[i*9+1] = trVer[1];
|
||||
transformedVertices[i*9+2] = trVer[2];
|
||||
transformedVertices[i*9+3] =textured_detailed_sphere_vertices[i*9+3];
|
||||
transformedVertices[i*9+4] =textured_detailed_sphere_vertices[i*9+4];
|
||||
transformedVertices[i*9+5] =textured_detailed_sphere_vertices[i*9+5];
|
||||
transformedVertices[i*9+6] =textured_detailed_sphere_vertices[i*9+6];
|
||||
transformedVertices[i*9+7] =textured_detailed_sphere_vertices[i*9+7];
|
||||
transformedVertices[i*9+8] =textured_detailed_sphere_vertices[i*9+8];
|
||||
}
|
||||
|
||||
int numIndices = sizeof(textured_detailed_sphere_indices)/sizeof(int);
|
||||
graphicsShapeIndex = registerGraphicsShape(&transformedVertices[0],numVertices,textured_detailed_sphere_indices,numIndices,B3_GL_TRIANGLES,m_data->m_checkedTextureGrey);
|
||||
m_data->m_hashShapes.insert(shape,graphicsShapeIndex);
|
||||
}
|
||||
|
||||
collisionShape->setUserIndex(graphicsShapeIndex);
|
||||
return;
|
||||
}
|
||||
if (compound->getChildShape(0)->getShapeType()==CAPSULE_SHAPE_PROXYTYPE)
|
||||
{
|
||||
btCapsuleShape* sphereShape = (btCapsuleShape*) compound->getChildShape(0);
|
||||
int up = sphereShape->getUpAxis();
|
||||
btScalar halfHeight = sphereShape->getHalfHeight();
|
||||
|
||||
btScalar radius = sphereShape->getRadius();
|
||||
btScalar sphereSize = 2.*radius;
|
||||
|
||||
btVector3 radiusScale = btVector3(sphereSize,sphereSize,sphereSize);
|
||||
|
||||
|
||||
MyHashShape shape;
|
||||
shape.m_radius0 = sphereSize;
|
||||
shape.m_deformFunc = 2;//no deform
|
||||
shape.m_childTransform = compound->getChildTransform(0);
|
||||
shape.m_upAxis = up;
|
||||
|
||||
int graphicsShapeIndex = -1;
|
||||
int* graphicsShapeIndexPtr = m_data->m_hashShapes[shape];
|
||||
|
||||
if (graphicsShapeIndexPtr)
|
||||
{
|
||||
graphicsShapeIndex = *graphicsShapeIndexPtr;
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
btAlignedObjectArray<float> transformedVertices;
|
||||
int numVertices = sizeof(textured_detailed_sphere_vertices)/strideInBytes;
|
||||
transformedVertices.resize(numVertices*9);
|
||||
for (int i=0;i<numVertices;i++)
|
||||
{
|
||||
|
||||
btVector3 vert;
|
||||
vert.setValue(textured_detailed_sphere_vertices[i*9+0],
|
||||
textured_detailed_sphere_vertices[i*9+1],
|
||||
textured_detailed_sphere_vertices[i*9+2]);
|
||||
|
||||
btVector3 trVer = compound->getChildTransform(0)*(radiusScale*vert);
|
||||
if (trVer[up]>0)
|
||||
trVer[up]+=halfHeight;
|
||||
else
|
||||
trVer[up]-=halfHeight;
|
||||
|
||||
|
||||
transformedVertices[i*9+0] = trVer[0];
|
||||
transformedVertices[i*9+1] = trVer[1];
|
||||
transformedVertices[i*9+2] = trVer[2];
|
||||
transformedVertices[i*9+3] =textured_detailed_sphere_vertices[i*9+3];
|
||||
transformedVertices[i*9+4] =textured_detailed_sphere_vertices[i*9+4];
|
||||
transformedVertices[i*9+5] =textured_detailed_sphere_vertices[i*9+5];
|
||||
transformedVertices[i*9+6] =textured_detailed_sphere_vertices[i*9+6];
|
||||
transformedVertices[i*9+7] =textured_detailed_sphere_vertices[i*9+7];
|
||||
transformedVertices[i*9+8] =textured_detailed_sphere_vertices[i*9+8];
|
||||
}
|
||||
|
||||
int numIndices = sizeof(textured_detailed_sphere_indices)/sizeof(int);
|
||||
graphicsShapeIndex = registerGraphicsShape(&transformedVertices[0],numVertices,textured_detailed_sphere_indices,numIndices,B3_GL_TRIANGLES,m_data->m_checkedTextureGrey);
|
||||
m_data->m_hashShapes.insert(shape,graphicsShapeIndex);
|
||||
}
|
||||
|
||||
collisionShape->setUserIndex(graphicsShapeIndex);
|
||||
return;
|
||||
|
||||
}
|
||||
|
||||
if (compound->getChildShape(0)->getShapeType()==MULTI_SPHERE_SHAPE_PROXYTYPE)
|
||||
{
|
||||
btMultiSphereShape* ms = (btMultiSphereShape*) compound->getChildShape(0);
|
||||
if (ms->getSphereCount()==2)
|
||||
{
|
||||
btAlignedObjectArray<float> transformedVertices;
|
||||
int numVertices = sizeof(textured_detailed_sphere_vertices)/strideInBytes;
|
||||
transformedVertices.resize(numVertices*9);
|
||||
btVector3 sphere0Pos = ms->getSpherePosition(0);
|
||||
btVector3 sphere1Pos = ms->getSpherePosition(1);
|
||||
btVector3 fromTo = sphere1Pos-sphere0Pos;
|
||||
btScalar radiusScale1 = 2.0*ms->getSphereRadius(1);
|
||||
btScalar radiusScale0 = 2.0*ms->getSphereRadius(0);
|
||||
|
||||
MyHashShape shape;
|
||||
shape.m_radius0 = radiusScale0;
|
||||
shape.m_radius1 = radiusScale1;
|
||||
shape.m_deformFunc = 4;
|
||||
shape.m_sphere0Pos = sphere0Pos;
|
||||
shape.m_sphere1Pos = sphere1Pos;
|
||||
shape.m_childTransform = compound->getChildTransform(0);
|
||||
|
||||
int graphicsShapeIndex = -1;
|
||||
int* graphicsShapeIndexPtr = m_data->m_hashShapes[shape];
|
||||
|
||||
if (graphicsShapeIndexPtr)
|
||||
{
|
||||
graphicsShapeIndex = *graphicsShapeIndexPtr;
|
||||
}
|
||||
else
|
||||
{
|
||||
for (int i=0;i<numVertices;i++)
|
||||
{
|
||||
|
||||
btVector3 vert;
|
||||
vert.setValue(textured_detailed_sphere_vertices[i*9+0],
|
||||
textured_detailed_sphere_vertices[i*9+1],
|
||||
textured_detailed_sphere_vertices[i*9+2]);
|
||||
|
||||
btVector3 trVer(0,0,0);
|
||||
if (vert.dot(fromTo)>0)
|
||||
{
|
||||
|
||||
trVer = vert*radiusScale1;
|
||||
trVer+=sphere1Pos;
|
||||
trVer = compound->getChildTransform(0)*trVer;
|
||||
} else
|
||||
{
|
||||
trVer = vert*radiusScale0;
|
||||
trVer+=sphere0Pos;
|
||||
trVer=compound->getChildTransform(0)*trVer;
|
||||
}
|
||||
|
||||
|
||||
|
||||
transformedVertices[i*9+0] = trVer[0];
|
||||
transformedVertices[i*9+1] = trVer[1];
|
||||
transformedVertices[i*9+2] = trVer[2];
|
||||
transformedVertices[i*9+3] =textured_detailed_sphere_vertices[i*9+3];
|
||||
transformedVertices[i*9+4] =textured_detailed_sphere_vertices[i*9+4];
|
||||
transformedVertices[i*9+5] =textured_detailed_sphere_vertices[i*9+5];
|
||||
transformedVertices[i*9+6] =textured_detailed_sphere_vertices[i*9+6];
|
||||
transformedVertices[i*9+7] =textured_detailed_sphere_vertices[i*9+7];
|
||||
transformedVertices[i*9+8] =textured_detailed_sphere_vertices[i*9+8];
|
||||
}
|
||||
|
||||
int numIndices = sizeof(textured_detailed_sphere_indices)/sizeof(int);
|
||||
graphicsShapeIndex = registerGraphicsShape(&transformedVertices[0],numVertices,textured_detailed_sphere_indices,numIndices,B3_GL_TRIANGLES,m_data->m_checkedTextureGrey);
|
||||
m_data->m_hashShapes.insert(shape,graphicsShapeIndex);
|
||||
}
|
||||
collisionShape->setUserIndex(graphicsShapeIndex);
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
if (collisionShape->getShapeType()==CAPSULE_SHAPE_PROXYTYPE)
|
||||
{
|
||||
btCapsuleShape* sphereShape = (btCapsuleShape*) collisionShape;//Y up
|
||||
int up = sphereShape->getUpAxis();
|
||||
btScalar halfHeight = sphereShape->getHalfHeight();
|
||||
|
||||
btScalar radius = sphereShape->getRadius();
|
||||
btScalar sphereSize = 2.*radius;
|
||||
btVector3 radiusScale(sphereSize,sphereSize,sphereSize);
|
||||
|
||||
|
||||
MyHashShape shape;
|
||||
shape.m_radius0 = sphereSize;
|
||||
shape.m_deformFunc = 3;
|
||||
shape.m_upAxis = up;
|
||||
shape.m_halfHeight = halfHeight;
|
||||
int graphicsShapeIndex = -1;
|
||||
int* graphicsShapeIndexPtr = m_data->m_hashShapes[shape];
|
||||
|
||||
if (graphicsShapeIndexPtr)
|
||||
{
|
||||
graphicsShapeIndex = *graphicsShapeIndexPtr;
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
btAlignedObjectArray<float> transformedVertices;
|
||||
int numVertices = sizeof(textured_detailed_sphere_vertices)/strideInBytes;
|
||||
transformedVertices.resize(numVertices*9);
|
||||
for (int i=0;i<numVertices;i++)
|
||||
{
|
||||
|
||||
btVector3 vert;
|
||||
vert.setValue(textured_detailed_sphere_vertices[i*9+0],
|
||||
textured_detailed_sphere_vertices[i*9+1],
|
||||
textured_detailed_sphere_vertices[i*9+2]);
|
||||
|
||||
btVector3 trVer = radiusScale*vert;
|
||||
if (trVer[up]>0)
|
||||
trVer[up]+=halfHeight;
|
||||
else
|
||||
trVer[up]-=halfHeight;
|
||||
|
||||
|
||||
|
||||
transformedVertices[i*9+0] = trVer[0];
|
||||
transformedVertices[i*9+1] = trVer[1];
|
||||
transformedVertices[i*9+2] = trVer[2];
|
||||
transformedVertices[i*9+3] =textured_detailed_sphere_vertices[i*9+3];
|
||||
transformedVertices[i*9+4] =textured_detailed_sphere_vertices[i*9+4];
|
||||
transformedVertices[i*9+5] =textured_detailed_sphere_vertices[i*9+5];
|
||||
transformedVertices[i*9+6] =textured_detailed_sphere_vertices[i*9+6];
|
||||
transformedVertices[i*9+7] =textured_detailed_sphere_vertices[i*9+7];
|
||||
transformedVertices[i*9+8] =textured_detailed_sphere_vertices[i*9+8];
|
||||
}
|
||||
|
||||
int numIndices = sizeof(textured_detailed_sphere_indices)/sizeof(int);
|
||||
graphicsShapeIndex = registerGraphicsShape(&transformedVertices[0],numVertices,textured_detailed_sphere_indices,numIndices,B3_GL_TRIANGLES,m_data->m_checkedTextureGrey);
|
||||
m_data->m_hashShapes.insert(shape,graphicsShapeIndex);
|
||||
}
|
||||
collisionShape->setUserIndex(graphicsShapeIndex);
|
||||
return;
|
||||
|
||||
}
|
||||
if (collisionShape->getShapeType()==STATIC_PLANE_PROXYTYPE)
|
||||
{
|
||||
const btStaticPlaneShape* staticPlaneShape = static_cast<const btStaticPlaneShape*>(collisionShape);
|
||||
btScalar planeConst = staticPlaneShape->getPlaneConstant();
|
||||
const btVector3& planeNormal = staticPlaneShape->getPlaneNormal();
|
||||
btVector3 planeOrigin = planeNormal * planeConst;
|
||||
btVector3 vec0,vec1;
|
||||
btPlaneSpace1(planeNormal,vec0,vec1);
|
||||
|
||||
btScalar vecLen = 128;
|
||||
btVector3 verts[4];
|
||||
|
||||
verts[0] = planeOrigin + vec0*vecLen + vec1*vecLen;
|
||||
verts[1] = planeOrigin - vec0*vecLen + vec1*vecLen;
|
||||
verts[2] = planeOrigin - vec0*vecLen - vec1*vecLen;
|
||||
verts[3] = planeOrigin + vec0*vecLen - vec1*vecLen;
|
||||
|
||||
int startIndex = 0;
|
||||
indices.push_back(startIndex+0);
|
||||
indices.push_back(startIndex+1);
|
||||
indices.push_back(startIndex+2);
|
||||
indices.push_back(startIndex+0);
|
||||
indices.push_back(startIndex+2);
|
||||
indices.push_back(startIndex+3);
|
||||
btTransform parentTransform;
|
||||
parentTransform.setIdentity();
|
||||
btVector3 triNormal = parentTransform.getBasis()*planeNormal;
|
||||
|
||||
gfxVertices.resize(4);
|
||||
|
||||
for (int i=0;i<4;i++)
|
||||
{
|
||||
btVector3 vtxPos;
|
||||
btVector3 pos =parentTransform*verts[i];
|
||||
|
||||
gfxVertices[i].xyzw[0] = pos[0];
|
||||
gfxVertices[i].xyzw[1] = pos[1];
|
||||
gfxVertices[i].xyzw[2] = pos[2];
|
||||
gfxVertices[i].xyzw[3] = 1;
|
||||
gfxVertices[i].normal[0] = triNormal[0];
|
||||
gfxVertices[i].normal[1] = triNormal[1];
|
||||
gfxVertices[i].normal[2] = triNormal[2];
|
||||
}
|
||||
|
||||
//verts[0] = planeOrigin + vec0*vecLen + vec1*vecLen;
|
||||
//verts[1] = planeOrigin - vec0*vecLen + vec1*vecLen;
|
||||
//verts[2] = planeOrigin - vec0*vecLen - vec1*vecLen;
|
||||
//verts[3] = planeOrigin + vec0*vecLen - vec1*vecLen;
|
||||
|
||||
gfxVertices[0].uv[0] = vecLen/2;
|
||||
gfxVertices[0].uv[1] = vecLen/2;
|
||||
gfxVertices[1].uv[0] = -vecLen/2;
|
||||
gfxVertices[1].uv[1] = vecLen/2;
|
||||
gfxVertices[2].uv[0] = -vecLen/2;
|
||||
gfxVertices[2].uv[1] = -vecLen/2;
|
||||
gfxVertices[3].uv[0] = vecLen/2;
|
||||
gfxVertices[3].uv[1] = -vecLen/2;
|
||||
|
||||
int shapeId = registerGraphicsShape(&gfxVertices[0].xyzw[0],gfxVertices.size(),&indices[0],indices.size(),B3_GL_TRIANGLES,m_data->m_checkedTexture);
|
||||
collisionShape->setUserIndex(shapeId);
|
||||
return;
|
||||
}
|
||||
|
||||
btTransform startTrans;startTrans.setIdentity();
|
||||
//todo: create some textured objects for popular objects, like plane, cube, sphere, capsule
|
||||
|
||||
{
|
||||
btAlignedObjectArray<btVector3> vertexPositions;
|
||||
@ -605,7 +1171,12 @@ void OpenGLGuiHelper::autogenerateGraphicsObjects(btDiscreteDynamicsWorld* rbWor
|
||||
createCollisionShapeGraphicsObject(colObj->getCollisionShape());
|
||||
int colorIndex = colObj->getBroadphaseHandle()->getUid() & 3;
|
||||
|
||||
btVector3 color= sColors[colorIndex];
|
||||
btVector3 color;
|
||||
color = sColors[colorIndex];
|
||||
if (colObj->getCollisionShape()->getShapeType()==STATIC_PLANE_PROXYTYPE)
|
||||
{
|
||||
color.setValue(1,1,1);
|
||||
}
|
||||
createCollisionObjectGraphicsObject(colObj,color);
|
||||
|
||||
}
|
||||
|
@ -90,6 +90,7 @@ struct OpenGLGuiHelper : public GUIHelperInterface
|
||||
|
||||
virtual void dumpFramesToVideo(const char* mp4FileName);
|
||||
|
||||
int createCheckeredTexture(int r,int g, int b);
|
||||
};
|
||||
|
||||
#endif //OPENGL_GUI_HELPER_H
|
||||
|
@ -36,6 +36,9 @@ static btScalar gBoxRestitution = 0; // set box restitution to 0
|
||||
static btScalar gSphereFriction = 1; // set sphere friction to 1
|
||||
|
||||
static btScalar gSphereRollingFriction = 1; // set sphere rolling friction to 1
|
||||
static btScalar gSphereSpinningFriction = 0.3; // set sphere spinning friction to 0.3
|
||||
|
||||
|
||||
|
||||
static btScalar gSphereRestitution = 0; // set sphere restitution to 0
|
||||
|
||||
@ -149,6 +152,16 @@ void InclinedPlaneExample::initPhysics()
|
||||
m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
|
||||
}
|
||||
|
||||
{ // create slider to change the sphere rolling friction
|
||||
SliderParams slider("Sphere Spinning",&gSphereSpinningFriction);
|
||||
slider.m_minVal=0;
|
||||
slider.m_maxVal=2;
|
||||
slider.m_clampToNotches = false;
|
||||
slider.m_callback = onSphereRestitutionChanged;
|
||||
m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
|
||||
}
|
||||
|
||||
|
||||
{ // create slider to change the sphere restitution
|
||||
SliderParams slider("Sphere Restitution",&gSphereRestitution);
|
||||
slider.m_minVal=0;
|
||||
@ -240,6 +253,8 @@ void InclinedPlaneExample::initPhysics()
|
||||
gSphere->setFriction(gSphereFriction);
|
||||
gSphere->setRestitution(gSphereRestitution);
|
||||
gSphere->setRollingFriction(gSphereRollingFriction);
|
||||
gSphere->setSpinningFriction(gSphereSpinningFriction);
|
||||
|
||||
}
|
||||
|
||||
m_guiHelper->autogenerateGraphicsObjects(m_dynamicsWorld);
|
||||
|
@ -192,7 +192,7 @@ struct InternalDataRenderer : public GLInstanceRendererInternalData
|
||||
m_shadowTexture(0),
|
||||
m_renderFrameBuffer(0)
|
||||
{
|
||||
m_lightPos=b3MakeVector3(-50,30,100);
|
||||
m_lightPos=b3MakeVector3(-50,50,50);
|
||||
|
||||
//clear to zero to make it obvious if the matrix is used uninitialized
|
||||
for (int i=0;i<16;i++)
|
||||
|
File diff suppressed because it is too large
Load Diff
@ -4536,7 +4536,6 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
int linkIndexB = -1;
|
||||
|
||||
int objectIndexB = -1;
|
||||
|
||||
const btRigidBody* bodyB = btRigidBody::upcast(manifold->getBody1());
|
||||
if (bodyB)
|
||||
{
|
||||
@ -4547,12 +4546,6 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
linkIndexB = mblB->m_link;
|
||||
objectIndexB = mblB->m_multiBody->getUserIndex2();
|
||||
if (
|
||||
(clientCmd.m_updateFlags & CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_B_FILTER) &&
|
||||
clientCmd.m_requestContactPointArguments.m_linkIndexBIndexFilter != linkIndexB)
|
||||
{
|
||||
continue;
|
||||
}
|
||||
}
|
||||
|
||||
int objectIndexA = -1;
|
||||
@ -4566,30 +4559,55 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
linkIndexA = mblA->m_link;
|
||||
objectIndexA = mblA->m_multiBody->getUserIndex2();
|
||||
if (
|
||||
(clientCmd.m_updateFlags & CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_A_FILTER) &&
|
||||
clientCmd.m_requestContactPointArguments.m_linkIndexAIndexFilter != linkIndexA)
|
||||
}
|
||||
btAssert(bodyA || mblA);
|
||||
|
||||
//apply the filter, if the user provides it
|
||||
bool swap = false;
|
||||
if (clientCmd.m_requestContactPointArguments.m_objectAIndexFilter >= 0)
|
||||
{
|
||||
if (clientCmd.m_requestContactPointArguments.m_objectAIndexFilter == objectIndexA)
|
||||
{
|
||||
swap = false;
|
||||
}
|
||||
else if (clientCmd.m_requestContactPointArguments.m_objectAIndexFilter == objectIndexB)
|
||||
{
|
||||
swap = true;
|
||||
}
|
||||
else
|
||||
{
|
||||
continue;
|
||||
}
|
||||
}
|
||||
|
||||
btAssert(bodyA || mblA);
|
||||
|
||||
//apply the filter, if the user provides it
|
||||
if (clientCmd.m_requestContactPointArguments.m_objectAIndexFilter >= 0)
|
||||
if (swap)
|
||||
{
|
||||
if ((clientCmd.m_requestContactPointArguments.m_objectAIndexFilter != objectIndexA) &&
|
||||
(clientCmd.m_requestContactPointArguments.m_objectAIndexFilter != objectIndexB))
|
||||
continue;
|
||||
std::swap(objectIndexA, objectIndexB);
|
||||
std::swap(linkIndexA, linkIndexB);
|
||||
std::swap(bodyA, bodyB);
|
||||
}
|
||||
|
||||
//apply the second object filter, if the user provides it
|
||||
if (clientCmd.m_requestContactPointArguments.m_objectBIndexFilter >= 0)
|
||||
{
|
||||
if ((clientCmd.m_requestContactPointArguments.m_objectBIndexFilter != objectIndexA) &&
|
||||
(clientCmd.m_requestContactPointArguments.m_objectBIndexFilter != objectIndexB))
|
||||
if (clientCmd.m_requestContactPointArguments.m_objectBIndexFilter != objectIndexB)
|
||||
{
|
||||
continue;
|
||||
}
|
||||
}
|
||||
|
||||
if (
|
||||
(clientCmd.m_updateFlags & CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_A_FILTER) &&
|
||||
clientCmd.m_requestContactPointArguments.m_linkIndexAIndexFilter != linkIndexA)
|
||||
{
|
||||
continue;
|
||||
}
|
||||
|
||||
if (
|
||||
(clientCmd.m_updateFlags & CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_B_FILTER) &&
|
||||
clientCmd.m_requestContactPointArguments.m_linkIndexBIndexFilter != linkIndexB)
|
||||
{
|
||||
continue;
|
||||
}
|
||||
|
||||
for (int p = 0; p < manifold->getNumContacts(); p++)
|
||||
|
@ -5520,8 +5520,8 @@ static PyObject* pybullet_calculateInverseKinematics(PyObject* self,
|
||||
PyObject* restPosesObj = 0;
|
||||
PyObject* jointDampingObj = 0;
|
||||
|
||||
static char* kwlist[] = {"bodyIndex", "endEffectorLinkIndex", "targetPosition", "targetOrientation", "lowerLimits", "upperLimits", "jointRanges", "restPoses", "physicsClientId", "jointDamping", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iiO|OOOOOiO", kwlist, &bodyIndex, &endEffectorLinkIndex, &targetPosObj, &targetOrnObj, &lowerLimitsObj, &upperLimitsObj, &jointRangesObj, &restPosesObj, &physicsClientId, &jointDampingObj))
|
||||
static char* kwlist[] = {"bodyIndex", "endEffectorLinkIndex", "targetPosition", "targetOrientation", "lowerLimits", "upperLimits", "jointRanges", "restPoses", "jointDamping", "physicsClientId", NULL};
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iiO|OOOOOOi", kwlist, &bodyIndex, &endEffectorLinkIndex, &targetPosObj, &targetOrnObj, &lowerLimitsObj, &upperLimitsObj, &jointRangesObj, &restPosesObj, &jointDampingObj, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
|
@ -4,15 +4,11 @@ import numpy as np
|
||||
|
||||
import pybullet as p
|
||||
import time
|
||||
p.connect(p.SHARED_MEMORY) #GUI is slower, but shows the running gait
|
||||
p.connect(p.GUI) #GUI is slower, but shows the running gait
|
||||
p.setGravity(0,0,-9.8)
|
||||
p.setPhysicsEngineParameter(fixedTimeStep=1.0/60., numSolverIterations=5, numSubSteps=2)
|
||||
#this mp4 recording requires ffmpeg installed
|
||||
#mp4log = p.startStateLogging(p.STATE_LOGGING_VIDEO_MP4,"humanoid.mp4")
|
||||
# numSubSteps:
|
||||
# 1 falls often at 300 fps
|
||||
# 2 works fine at 300 fps
|
||||
# 11 not that slower at 180 fps
|
||||
|
||||
|
||||
plane, human1 = p.loadMJCF("mjcf/humanoid_symmetric.xml",flags = p.URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS)
|
||||
@ -65,7 +61,9 @@ dummy.initial_z = None
|
||||
def current_relative_position(human, j, lower, upper):
|
||||
#print("j")
|
||||
#print(j)
|
||||
pos, vel, *other = p.getJointState(human, j)
|
||||
temp = p.getJointState(human, j)
|
||||
pos = temp[0]
|
||||
vel = temp[1]
|
||||
#print("pos")
|
||||
#print(pos)
|
||||
#print("vel")
|
||||
@ -186,7 +184,7 @@ def demo_run():
|
||||
p.setJointMotorControlArray(human2, motors,controlMode=p.TORQUE_CONTROL, forces=forces)
|
||||
|
||||
p.stepSimulation()
|
||||
time.sleep(0.01)
|
||||
#time.sleep(0.01)
|
||||
distance=5
|
||||
yaw = 0
|
||||
humanPos, humanOrn = p.getBasePositionAndOrientation(human)
|
||||
|
2
setup.py
2
setup.py
@ -417,7 +417,7 @@ else:
|
||||
|
||||
setup(
|
||||
name = 'pybullet',
|
||||
version='1.0.2',
|
||||
version='1.0.3',
|
||||
description='Official Python Interface for the Bullet Physics SDK Robotics Simulator',
|
||||
long_description='pybullet is an easy to use Python module for physics simulation, robotics and machine learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.',
|
||||
url='https://github.com/bulletphysics/bullet3',
|
||||
|
@ -4,8 +4,8 @@ Copyright (c) 2013 Erwin Coumans http://bulletphysics.org
|
||||
|
||||
This software is provided 'as-is', without any express or implied warranty.
|
||||
In no event will the authors be held liable for any damages arising from the use of this software.
|
||||
Permission is granted to anyone to use this software for any purpose,
|
||||
including commercial applications, and to alter it and redistribute it freely,
|
||||
Permission is granted to anyone to use this software for any purpose,
|
||||
including commercial applications, and to alter it and redistribute it freely,
|
||||
subject to the following restrictions:
|
||||
|
||||
1. The origin of this software must not be misrepresented; you must not claim that you wrote the original software. If you use this software in a product, an acknowledgment in the product documentation would be appreciated but is not required.
|
||||
@ -74,17 +74,12 @@ public:
|
||||
if (m_link>=0)
|
||||
{
|
||||
const btMultibodyLink& link = m_multiBody->getLink(this->m_link);
|
||||
if (link.m_flags&BT_MULTIBODYLINKFLAGS_DISABLE_PARENT_COLLISION)
|
||||
{
|
||||
if ( link.m_parent == other->m_link)
|
||||
return false;
|
||||
}
|
||||
if (link.m_flags&BT_MULTIBODYLINKFLAGS_DISABLE_ALL_PARENT_COLLISION)
|
||||
{
|
||||
int parent_of_this = m_link;
|
||||
while (1)
|
||||
while (1)
|
||||
{
|
||||
if (parent_of_this==-1)
|
||||
if (parent_of_this==-1)
|
||||
break;
|
||||
parent_of_this = m_multiBody->getLink(parent_of_this).m_parent;
|
||||
if (parent_of_this==other->m_link)
|
||||
@ -93,28 +88,34 @@ public:
|
||||
}
|
||||
}
|
||||
}
|
||||
else if (link.m_flags&BT_MULTIBODYLINKFLAGS_DISABLE_PARENT_COLLISION)
|
||||
{
|
||||
if ( link.m_parent == other->m_link)
|
||||
return false;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
||||
if (other->m_link>=0)
|
||||
{
|
||||
const btMultibodyLink& otherLink = other->m_multiBody->getLink(other->m_link);
|
||||
if (otherLink.m_flags& BT_MULTIBODYLINKFLAGS_DISABLE_PARENT_COLLISION)
|
||||
{
|
||||
if (otherLink.m_parent == this->m_link)
|
||||
return false;
|
||||
}
|
||||
if (otherLink.m_flags& BT_MULTIBODYLINKFLAGS_DISABLE_ALL_PARENT_COLLISION)
|
||||
{
|
||||
int parent_of_other = other->m_link;
|
||||
while (1)
|
||||
while (1)
|
||||
{
|
||||
if (parent_of_other==-1)
|
||||
if (parent_of_other==-1)
|
||||
break;
|
||||
parent_of_other = m_multiBody->getLink(parent_of_other).m_parent;
|
||||
if (parent_of_other==this->m_link)
|
||||
return false;
|
||||
}
|
||||
}
|
||||
else if (otherLink.m_flags& BT_MULTIBODYLINKFLAGS_DISABLE_PARENT_COLLISION)
|
||||
{
|
||||
if (otherLink.m_parent == this->m_link)
|
||||
return false;
|
||||
}
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
@ -355,7 +355,15 @@ public:
|
||||
{
|
||||
return btSqrt(length2());
|
||||
}
|
||||
|
||||
btQuaternion& safeNormalize()
|
||||
{
|
||||
btScalar l2 = length2();
|
||||
if (l2>SIMD_EPSILON)
|
||||
{
|
||||
normalize();
|
||||
}
|
||||
return *this;
|
||||
}
|
||||
/**@brief Normalize the quaternion
|
||||
* Such that x^2 + y^2 + z^2 +w^2 = 1 */
|
||||
btQuaternion& normalize()
|
||||
|
@ -47,13 +47,19 @@ public:
|
||||
#ifdef QUATERNION_DERIVATIVE
|
||||
btQuaternion predictedOrn = curTrans.getRotation();
|
||||
predictedOrn += (angvel * predictedOrn) * (timeStep * btScalar(0.5));
|
||||
predictedOrn.normalize();
|
||||
predictedOrn.safeNormalize();
|
||||
#else
|
||||
//Exponential map
|
||||
//google for "Practical Parameterization of Rotations Using the Exponential Map", F. Sebastian Grassia
|
||||
|
||||
btVector3 axis;
|
||||
btScalar fAngle = angvel.length();
|
||||
btScalar fAngle2 = angvel.length2();
|
||||
btScalar fAngle = 0;
|
||||
if (fAngle2>SIMD_EPSILON)
|
||||
{
|
||||
fAngle = btSqrt(fAngle2);
|
||||
}
|
||||
|
||||
//limit the angular motion
|
||||
if (fAngle*timeStep > ANGULAR_MOTION_THRESHOLD)
|
||||
{
|
||||
@ -74,9 +80,16 @@ public:
|
||||
btQuaternion orn0 = curTrans.getRotation();
|
||||
|
||||
btQuaternion predictedOrn = dorn * orn0;
|
||||
predictedOrn.normalize();
|
||||
predictedOrn.safeNormalize();
|
||||
#endif
|
||||
predictedTransform.setRotation(predictedOrn);
|
||||
if (predictedOrn.length2()>SIMD_EPSILON)
|
||||
{
|
||||
predictedTransform.setRotation(predictedOrn);
|
||||
}
|
||||
else
|
||||
{
|
||||
predictedTransform.setBasis(curTrans.getBasis());
|
||||
}
|
||||
}
|
||||
|
||||
static void calculateVelocityQuaternion(const btVector3& pos0,const btVector3& pos1,const btQuaternion& orn0,const btQuaternion& orn1,btScalar timeStep,btVector3& linVel,btVector3& angVel)
|
||||
|
Loading…
Reference in New Issue
Block a user