Merge pull request #917 from erwincoumans/master
add --disable_desktop_gl for Virtual Reality server (App_SharedMemory…
This commit is contained in:
@@ -705,6 +705,7 @@ float computeConcavity(unsigned int vcount,
|
||||
}
|
||||
}
|
||||
|
||||
#if 0
|
||||
if ( ftris.size() && 0 )
|
||||
{
|
||||
|
||||
@@ -725,17 +726,17 @@ float computeConcavity(unsigned int vcount,
|
||||
|
||||
do
|
||||
{
|
||||
found = false;
|
||||
CTriVector::iterator i;
|
||||
for (i=ftris.begin(); i!=ftris.end(); ++i)
|
||||
{
|
||||
CTri &t = (*i);
|
||||
if ( isFeatureTri(t,flist,maxc,callback,color) )
|
||||
{
|
||||
found = true;
|
||||
totalarea+=t.area();
|
||||
}
|
||||
}
|
||||
found = false;
|
||||
CTriVector::iterator i;
|
||||
for (i=ftris.begin(); i!=ftris.end(); ++i)
|
||||
{
|
||||
CTri &t = (*i);
|
||||
if ( isFeatureTri(t,flist,maxc,callback,color) )
|
||||
{
|
||||
found = true;
|
||||
totalarea+=t.area();
|
||||
}
|
||||
}
|
||||
} while ( found );
|
||||
|
||||
|
||||
@@ -759,6 +760,7 @@ float computeConcavity(unsigned int vcount,
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
unsigned int color = getDebugColor();
|
||||
@@ -786,7 +788,7 @@ float computeConcavity(unsigned int vcount,
|
||||
|
||||
hl.ReleaseResult(result);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
return cret;
|
||||
}
|
||||
|
||||
@@ -349,7 +349,8 @@ static int name_is_array(char* name, int* dim1, int* dim2) {
|
||||
void bDNA::init(char *data, int len, bool swap)
|
||||
{
|
||||
int *intPtr=0;short *shtPtr=0;
|
||||
char *cp = 0;int dataLen =0;long nr=0;
|
||||
char *cp = 0;int dataLen =0;
|
||||
//long nr=0;
|
||||
intPtr = (int*)data;
|
||||
|
||||
/*
|
||||
|
||||
@@ -411,7 +411,7 @@ void bFile::swapDNA(char* ptr)
|
||||
|
||||
// void bDNA::init(char *data, int len, bool swap)
|
||||
int *intPtr=0;short *shtPtr=0;
|
||||
char *cp = 0;int dataLen =0;long nr=0;
|
||||
char *cp = 0;int dataLen =0;
|
||||
intPtr = (int*)data;
|
||||
|
||||
/*
|
||||
@@ -573,7 +573,7 @@ void bFile::writeFile(const char* fileName)
|
||||
void bFile::preSwap()
|
||||
{
|
||||
|
||||
const bool brokenDNA = (mFlags&FD_BROKEN_DNA)!=0;
|
||||
//const bool brokenDNA = (mFlags&FD_BROKEN_DNA)!=0;
|
||||
//FD_ENDIAN_SWAP
|
||||
//byte 8 determines the endianness of the file, little (v) versus big (V)
|
||||
int littleEndian= 1;
|
||||
@@ -1285,7 +1285,7 @@ int bFile::resolvePointersStructRecursive(char *strcPtr, int dna_nr, int verbose
|
||||
}
|
||||
//skip the *
|
||||
printf("<%s type=\"pointer\"> ",&memName[1]);
|
||||
printf("%d ", array[a]);
|
||||
printf("%p ", array[a]);
|
||||
printf("</%s>\n",&memName[1]);
|
||||
}
|
||||
|
||||
@@ -1303,7 +1303,7 @@ int bFile::resolvePointersStructRecursive(char *strcPtr, int dna_nr, int verbose
|
||||
printf(" ");
|
||||
}
|
||||
printf("<%s type=\"pointer\"> ",&memName[1]);
|
||||
printf("%d ", ptr);
|
||||
printf("%p ", ptr);
|
||||
printf("</%s>\n",&memName[1]);
|
||||
}
|
||||
ptr = findLibPointer(ptr);
|
||||
@@ -1484,7 +1484,7 @@ void bFile::resolvePointers(int verboseMode)
|
||||
char* oldType = fileDna->getType(oldStruct[0]);
|
||||
|
||||
if (verboseMode & FD_VERBOSE_EXPORT_XML)
|
||||
printf(" <%s pointer=%d>\n",oldType,dataChunk.oldPtr);
|
||||
printf(" <%s pointer=%p>\n",oldType,dataChunk.oldPtr);
|
||||
|
||||
resolvePointersChunk(dataChunk, verboseMode);
|
||||
|
||||
|
||||
@@ -307,8 +307,6 @@ bool btBulletWorldImporter::convertAllObjects( bParse::btBulletFile* bulletFile
|
||||
for (i=0;i<bulletFile2->m_constraints.size();i++)
|
||||
{
|
||||
btTypedConstraintData2* constraintData = (btTypedConstraintData2*)bulletFile2->m_constraints[i];
|
||||
btTypedConstraintFloatData* singleC = (btTypedConstraintFloatData*)bulletFile2->m_constraints[i];
|
||||
btTypedConstraintDoubleData* doubleC = (btTypedConstraintDoubleData*)bulletFile2->m_constraints[i];
|
||||
|
||||
btCollisionObject** colAptr = m_bodyMap.find(constraintData->m_rbA);
|
||||
btCollisionObject** colBptr = m_bodyMap.find(constraintData->m_rbB);
|
||||
|
||||
@@ -468,14 +468,11 @@ btCollisionShape* btWorldImporter::convertCollisionShape( btCollisionShapeData*
|
||||
btCompoundShapeData* compoundData = (btCompoundShapeData*)shapeData;
|
||||
btCompoundShape* compoundShape = createCompoundShape();
|
||||
|
||||
btCompoundShapeChildData* childShapeDataArray = &compoundData->m_childShapePtr[0];
|
||||
|
||||
|
||||
|
||||
btAlignedObjectArray<btCollisionShape*> childShapes;
|
||||
for (int i=0;i<compoundData->m_numChildShapes;i++)
|
||||
{
|
||||
btCompoundShapeChildData* ptr = &compoundData->m_childShapePtr[i];
|
||||
|
||||
|
||||
btCollisionShapeData* cd = compoundData->m_childShapePtr[i].m_childShape;
|
||||
|
||||
btCollisionShape* childShape = convertCollisionShape(cd);
|
||||
@@ -997,11 +994,11 @@ void btWorldImporter::convertConstraintFloat(btTypedConstraintFloatData* constra
|
||||
dof->setStiffness(i,dofData->m_linearSpringStiffness.m_floats[i],dofData->m_linearSpringStiffnessLimited[i]!=0);
|
||||
dof->setEquilibriumPoint(i,dofData->m_linearEquilibriumPoint.m_floats[i]);
|
||||
dof->enableSpring(i,dofData->m_linearEnableSpring[i]!=0);
|
||||
dof->setDamping(i,dofData->m_linearSpringDamping.m_floats[i],dofData->m_linearSpringDampingLimited[i]);
|
||||
dof->setDamping(i,dofData->m_linearSpringDamping.m_floats[i],(dofData->m_linearSpringDampingLimited[i]!=0));
|
||||
}
|
||||
for (i=0;i<3;i++)
|
||||
{
|
||||
dof->setStiffness(i+3,dofData->m_angularSpringStiffness.m_floats[i],dofData->m_angularSpringStiffnessLimited[i]);
|
||||
dof->setStiffness(i+3,dofData->m_angularSpringStiffness.m_floats[i],(dofData->m_angularSpringStiffnessLimited[i]!=0));
|
||||
dof->setEquilibriumPoint(i+3,dofData->m_angularEquilibriumPoint.m_floats[i]);
|
||||
dof->enableSpring(i+3,dofData->m_angularEnableSpring[i]!=0);
|
||||
dof->setDamping(i+3,dofData->m_angularSpringDamping.m_floats[i],dofData->m_angularSpringDampingLimited[i]);
|
||||
@@ -1327,14 +1324,14 @@ void btWorldImporter::convertConstraintDouble(btTypedConstraintDoubleData* const
|
||||
dof->setStiffness(i,dofData->m_linearSpringStiffness.m_floats[i],dofData->m_linearSpringStiffnessLimited[i]);
|
||||
dof->setEquilibriumPoint(i,dofData->m_linearEquilibriumPoint.m_floats[i]);
|
||||
dof->enableSpring(i,dofData->m_linearEnableSpring[i]!=0);
|
||||
dof->setDamping(i,dofData->m_linearSpringDamping.m_floats[i],dofData->m_linearSpringDampingLimited[i]);
|
||||
dof->setDamping(i,dofData->m_linearSpringDamping.m_floats[i],(dofData->m_linearSpringDampingLimited[i]!=0));
|
||||
}
|
||||
for (i=0;i<3;i++)
|
||||
{
|
||||
dof->setStiffness(i+3,dofData->m_angularSpringStiffness.m_floats[i],dofData->m_angularSpringStiffnessLimited[i]);
|
||||
dof->setStiffness(i+3,dofData->m_angularSpringStiffness.m_floats[i],(dofData->m_angularSpringStiffnessLimited[i]!=0));
|
||||
dof->setEquilibriumPoint(i+3,dofData->m_angularEquilibriumPoint.m_floats[i]);
|
||||
dof->enableSpring(i+3,dofData->m_angularEnableSpring[i]!=0);
|
||||
dof->setDamping(i+3,dofData->m_angularSpringDamping.m_floats[i],dofData->m_angularSpringDampingLimited[i]);
|
||||
dof->setDamping(i+3,dofData->m_angularSpringDamping.m_floats[i],(dofData->m_angularSpringDampingLimited[i]!=0));
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
@@ -18,6 +18,16 @@ subject to the following restrictions:
|
||||
#include "btBulletDynamicsCommon.h"
|
||||
#include "string_split.h"
|
||||
|
||||
struct MyLocalCaster
|
||||
{
|
||||
void* m_ptr;
|
||||
int m_int;
|
||||
MyLocalCaster()
|
||||
:m_ptr(0)
|
||||
{
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
btBulletXmlWorldImporter::btBulletXmlWorldImporter(btDynamicsWorld* world)
|
||||
:btWorldImporter(world),
|
||||
@@ -32,7 +42,7 @@ btBulletXmlWorldImporter::~btBulletXmlWorldImporter()
|
||||
|
||||
}
|
||||
|
||||
|
||||
#if 0
|
||||
static int get_double_attribute_by_name(const TiXmlElement* pElement, const char* attribName,double* value)
|
||||
{
|
||||
if ( !pElement )
|
||||
@@ -48,7 +58,7 @@ static int get_double_attribute_by_name(const TiXmlElement* pElement, const char
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
static int get_int_attribute_by_name(const TiXmlElement* pElement, const char* attribName,int* value)
|
||||
{
|
||||
@@ -130,7 +140,9 @@ void btBulletXmlWorldImporter::deSerializeVector3FloatData(TiXmlNode* pParent,bt
|
||||
if (node)\
|
||||
{\
|
||||
const char* txt = (node)->ToElement()->GetText();\
|
||||
(targetdata).argname= (pointertype) (int) atof(txt);\
|
||||
MyLocalCaster cast;\
|
||||
cast.m_int = (int) atof(txt);\
|
||||
(targetdata).argname= (pointertype)cast.m_ptr;\
|
||||
}\
|
||||
}
|
||||
|
||||
@@ -216,8 +228,8 @@ void btBulletXmlWorldImporter::deSerializeCollisionShapeData(TiXmlNode* pParent,
|
||||
|
||||
void btBulletXmlWorldImporter::deSerializeConvexHullShapeData(TiXmlNode* pParent)
|
||||
{
|
||||
int ptr;
|
||||
get_int_attribute_by_name(pParent->ToElement(),"pointer",&ptr);
|
||||
MyLocalCaster cast;
|
||||
get_int_attribute_by_name(pParent->ToElement(),"pointer",&cast.m_int);
|
||||
|
||||
btConvexHullShapeData* convexHullData = (btConvexHullShapeData*)btAlignedAlloc(sizeof(btConvexHullShapeData), 16);
|
||||
|
||||
@@ -233,18 +245,33 @@ void btBulletXmlWorldImporter::deSerializeConvexHullShapeData(TiXmlNode* pParent
|
||||
SET_VECTOR4_VALUE(xmlConvexInt,&convexHullData->m_convexInternalShapeData,m_localScaling)
|
||||
SET_VECTOR4_VALUE(xmlConvexInt,&convexHullData->m_convexInternalShapeData,m_implicitShapeDimensions)
|
||||
|
||||
//convexHullData->m_unscaledPointsFloatPtr
|
||||
//#define SET_POINTER_VALUE(xmlnode, targetdata, argname, pointertype)
|
||||
|
||||
{
|
||||
TiXmlNode* node = pParent->FirstChild("m_unscaledPointsFloatPtr");
|
||||
btAssert(node);
|
||||
if (node)
|
||||
{
|
||||
const char* txt = (node)->ToElement()->GetText();
|
||||
MyLocalCaster cast;
|
||||
cast.m_int = (int) atof(txt);
|
||||
(*convexHullData).m_unscaledPointsFloatPtr= (btVector3FloatData*) cast.m_ptr;
|
||||
}
|
||||
}
|
||||
|
||||
SET_POINTER_VALUE(pParent,*convexHullData,m_unscaledPointsFloatPtr,btVector3FloatData*);
|
||||
SET_POINTER_VALUE(pParent,*convexHullData,m_unscaledPointsDoublePtr,btVector3DoubleData*);
|
||||
SET_INT_VALUE(pParent,convexHullData,m_numUnscaledPoints);
|
||||
|
||||
m_collisionShapeData.push_back((btCollisionShapeData*)convexHullData);
|
||||
m_pointerLookup.insert((void*)ptr,convexHullData);
|
||||
m_pointerLookup.insert(cast.m_ptr,convexHullData);
|
||||
}
|
||||
|
||||
void btBulletXmlWorldImporter::deSerializeCompoundShapeChildData(TiXmlNode* pParent)
|
||||
{
|
||||
int ptr;
|
||||
get_int_attribute_by_name(pParent->ToElement(),"pointer",&ptr);
|
||||
MyLocalCaster cast;
|
||||
get_int_attribute_by_name(pParent->ToElement(),"pointer",&cast.m_int);
|
||||
|
||||
int numChildren = 0;
|
||||
btAlignedObjectArray<btCompoundShapeChildData>* compoundChildArrayPtr = new btAlignedObjectArray<btCompoundShapeChildData>;
|
||||
@@ -262,7 +289,9 @@ void btBulletXmlWorldImporter::deSerializeCompoundShapeChildData(TiXmlNode* pPar
|
||||
SET_MATRIX33_VALUE(transNode,&compoundChildArrayPtr->at(i).m_transform,m_basis)
|
||||
|
||||
const char* txt = (colShapeNode)->ToElement()->GetText();
|
||||
compoundChildArrayPtr->at(i).m_childShape = (btCollisionShapeData*) (int) atof(txt);
|
||||
MyLocalCaster cast;
|
||||
cast.m_int = (int) atof(txt);
|
||||
compoundChildArrayPtr->at(i).m_childShape = (btCollisionShapeData*) cast.m_ptr;
|
||||
|
||||
btAssert(childTypeNode->ToElement());
|
||||
if (childTypeNode->ToElement())
|
||||
@@ -292,15 +321,15 @@ void btBulletXmlWorldImporter::deSerializeCompoundShapeChildData(TiXmlNode* pPar
|
||||
{
|
||||
m_compoundShapeChildDataArrays.push_back(compoundChildArrayPtr);
|
||||
btCompoundShapeChildData* cd = &compoundChildArrayPtr->at(0);
|
||||
m_pointerLookup.insert((void*)ptr,cd);
|
||||
m_pointerLookup.insert(cast.m_ptr,cd);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void btBulletXmlWorldImporter::deSerializeCompoundShapeData(TiXmlNode* pParent)
|
||||
{
|
||||
int ptr;
|
||||
get_int_attribute_by_name(pParent->ToElement(),"pointer",&ptr);
|
||||
MyLocalCaster cast;
|
||||
get_int_attribute_by_name(pParent->ToElement(),"pointer",&cast.m_int);
|
||||
|
||||
btCompoundShapeData* compoundData = (btCompoundShapeData*) btAlignedAlloc(sizeof(btCompoundShapeData),16);
|
||||
|
||||
@@ -319,7 +348,9 @@ void btBulletXmlWorldImporter::deSerializeCompoundShapeData(TiXmlNode* pParent)
|
||||
while (node)
|
||||
{
|
||||
const char* txt = (node)->ToElement()->GetText();
|
||||
compoundData->m_childShapePtr = (btCompoundShapeChildData*) (int) atof(txt);
|
||||
MyLocalCaster cast;
|
||||
cast.m_int = (int) atof(txt);
|
||||
compoundData->m_childShapePtr = (btCompoundShapeChildData*) cast.m_ptr;
|
||||
node = node->NextSibling("m_childShapePtr");
|
||||
}
|
||||
//SET_POINTER_VALUE(xmlColShape, *compoundData,m_childShapePtr,btCompoundShapeChildData*);
|
||||
@@ -328,14 +359,14 @@ void btBulletXmlWorldImporter::deSerializeCompoundShapeData(TiXmlNode* pParent)
|
||||
SET_FLOAT_VALUE(pParent, compoundData,m_collisionMargin);
|
||||
|
||||
m_collisionShapeData.push_back((btCollisionShapeData*)compoundData);
|
||||
m_pointerLookup.insert((void*)ptr,compoundData);
|
||||
m_pointerLookup.insert(cast.m_ptr,compoundData);
|
||||
|
||||
}
|
||||
|
||||
void btBulletXmlWorldImporter::deSerializeStaticPlaneShapeData(TiXmlNode* pParent)
|
||||
{
|
||||
int ptr;
|
||||
get_int_attribute_by_name(pParent->ToElement(),"pointer",&ptr);
|
||||
MyLocalCaster cast;
|
||||
get_int_attribute_by_name(pParent->ToElement(),"pointer",&cast.m_int);
|
||||
|
||||
btStaticPlaneShapeData* planeData = (btStaticPlaneShapeData*) btAlignedAlloc(sizeof(btStaticPlaneShapeData),16);
|
||||
|
||||
@@ -348,7 +379,7 @@ void btBulletXmlWorldImporter::deSerializeStaticPlaneShapeData(TiXmlNode* pParen
|
||||
SET_FLOAT_VALUE(pParent, planeData,m_planeConstant);
|
||||
|
||||
m_collisionShapeData.push_back((btCollisionShapeData*)planeData);
|
||||
m_pointerLookup.insert((void*)ptr,planeData);
|
||||
m_pointerLookup.insert(cast.m_ptr,planeData);
|
||||
|
||||
}
|
||||
|
||||
@@ -364,8 +395,8 @@ void btBulletXmlWorldImporter::deSerializeDynamicsWorldData(TiXmlNode* pParent)
|
||||
|
||||
void btBulletXmlWorldImporter::deSerializeConvexInternalShapeData(TiXmlNode* pParent)
|
||||
{
|
||||
int ptr=0;
|
||||
get_int_attribute_by_name(pParent->ToElement(),"pointer",&ptr);
|
||||
MyLocalCaster cast;
|
||||
get_int_attribute_by_name(pParent->ToElement(),"pointer",&cast.m_int);
|
||||
|
||||
|
||||
btConvexInternalShapeData* convexShape = (btConvexInternalShapeData*) btAlignedAlloc(sizeof(btConvexInternalShapeData),16);
|
||||
@@ -382,7 +413,7 @@ void btBulletXmlWorldImporter::deSerializeConvexInternalShapeData(TiXmlNode* pPa
|
||||
SET_VECTOR4_VALUE(pParent,convexShape,m_implicitShapeDimensions)
|
||||
|
||||
m_collisionShapeData.push_back((btCollisionShapeData*)convexShape);
|
||||
m_pointerLookup.insert((void*)ptr,convexShape);
|
||||
m_pointerLookup.insert(cast.m_ptr,convexShape);
|
||||
|
||||
}
|
||||
|
||||
@@ -404,8 +435,8 @@ enum btTypedConstraintType
|
||||
|
||||
void btBulletXmlWorldImporter::deSerializeGeneric6DofConstraintData(TiXmlNode* pParent)
|
||||
{
|
||||
int ptr=0;
|
||||
get_int_attribute_by_name(pParent->ToElement(),"pointer",&ptr);
|
||||
MyLocalCaster cast;
|
||||
get_int_attribute_by_name(pParent->ToElement(),"pointer",&cast.m_int);
|
||||
|
||||
btGeneric6DofConstraintData2* dof6Data = (btGeneric6DofConstraintData2*)btAlignedAlloc(sizeof(btGeneric6DofConstraintData2),16);
|
||||
|
||||
@@ -439,13 +470,14 @@ void btBulletXmlWorldImporter::deSerializeGeneric6DofConstraintData(TiXmlNode* p
|
||||
SET_INT_VALUE(pParent, dof6Data,m_useOffsetForConstraintFrame);
|
||||
|
||||
m_constraintData.push_back((btTypedConstraintData2*)dof6Data);
|
||||
m_pointerLookup.insert((void*)ptr,dof6Data);
|
||||
m_pointerLookup.insert(cast.m_ptr,dof6Data);
|
||||
}
|
||||
|
||||
void btBulletXmlWorldImporter::deSerializeRigidBodyFloatData(TiXmlNode* pParent)
|
||||
{
|
||||
int ptr=0;
|
||||
if (!get_int_attribute_by_name(pParent->ToElement(),"pointer",&ptr))
|
||||
MyLocalCaster cast;
|
||||
|
||||
if (!get_int_attribute_by_name(pParent->ToElement(),"pointer",&cast.m_int))
|
||||
{
|
||||
m_fileOk = false;
|
||||
return;
|
||||
@@ -506,7 +538,7 @@ void btBulletXmlWorldImporter::deSerializeRigidBodyFloatData(TiXmlNode* pParent)
|
||||
|
||||
|
||||
m_rigidBodyData.push_back(rbData);
|
||||
m_pointerLookup.insert((void*)ptr,rbData);
|
||||
m_pointerLookup.insert(cast.m_ptr,rbData);
|
||||
|
||||
// rbData->m_collisionObjectData.m_collisionShape = (void*) (int)atof(txt);
|
||||
}
|
||||
@@ -641,8 +673,8 @@ void btBulletXmlWorldImporter::auto_serialize_root_level_children(TiXmlNode* pPa
|
||||
// printf("child Name=%s\n", pChild->Value());
|
||||
if (!strcmp(pChild->Value(),"btVector3FloatData"))
|
||||
{
|
||||
int ptr;
|
||||
get_int_attribute_by_name(pChild->ToElement(),"pointer",&ptr);
|
||||
MyLocalCaster cast;
|
||||
get_int_attribute_by_name(pChild->ToElement(),"pointer",&cast.m_int);
|
||||
|
||||
btAlignedObjectArray<btVector3FloatData> v;
|
||||
deSerializeVector3FloatData(pChild,v);
|
||||
@@ -651,7 +683,7 @@ void btBulletXmlWorldImporter::auto_serialize_root_level_children(TiXmlNode* pPa
|
||||
for (int i=0;i<numVectors;i++)
|
||||
vectors[i] = v[i];
|
||||
m_floatVertexArrays.push_back(vectors);
|
||||
m_pointerLookup.insert((void*)ptr,vectors);
|
||||
m_pointerLookup.insert(cast.m_ptr,vectors);
|
||||
continue;
|
||||
}
|
||||
|
||||
@@ -790,7 +822,7 @@ void btBulletXmlWorldImporter::auto_serialize_root_level_children(TiXmlNode* pPa
|
||||
for (int i=0;i<m_constraintData.size();i++)
|
||||
{
|
||||
btTypedConstraintData2* tcd = m_constraintData[i];
|
||||
bool isDoublePrecision = false;
|
||||
// bool isDoublePrecision = false;
|
||||
btRigidBody* rbA = 0;
|
||||
btRigidBody* rbB = 0;
|
||||
{
|
||||
|
||||
@@ -2,5 +2,9 @@
|
||||
rm CMakeCache.txt
|
||||
mkdir build_cmake
|
||||
cd build_cmake
|
||||
cmake -DBUILD_PYBULLET=ON -DBUILD_PYBULLET_NUMPY=ON -DUSE_DOUBLE_PRECISION=ON -DCMAKE_BUILD_TYPE=Release ..
|
||||
cmake -DBUILD_PYBULLET=ON -DBUILD_PYBULLET_NUMPY=OFF -DUSE_DOUBLE_PRECISION=ON -DCMAKE_BUILD_TYPE=Release ..
|
||||
make -j12
|
||||
cd examples
|
||||
cd pybullet
|
||||
ln -s pybullet.dylib pybullet.so
|
||||
|
||||
|
||||
@@ -21,7 +21,7 @@
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_0.stl</uri>
|
||||
<uri>meshes/link_0.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
@@ -60,7 +60,7 @@
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_1.stl</uri>
|
||||
<uri>meshes/link_1.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
@@ -119,7 +119,7 @@
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_2.stl</uri>
|
||||
<uri>meshes/link_2.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
@@ -178,7 +178,7 @@
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_3.stl</uri>
|
||||
<uri>meshes/link_3.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
@@ -237,7 +237,7 @@
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_4.stl</uri>
|
||||
<uri>meshes/link_4.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
@@ -296,7 +296,7 @@
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_5.stl</uri>
|
||||
<uri>meshes/link_5.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
@@ -355,7 +355,7 @@
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_6.stl</uri>
|
||||
<uri>meshes/link_6.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
@@ -414,7 +414,7 @@
|
||||
<geometry>
|
||||
<mesh>
|
||||
<scale>1 1 1</scale>
|
||||
<uri>meshes/coarse/link_7.stl</uri>
|
||||
<uri>meshes/link_7.stl</uri>
|
||||
</mesh>
|
||||
</geometry>
|
||||
</collision>
|
||||
|
||||
47
data/mjcf/inverted_double_pendulum.xml
Normal file
47
data/mjcf/inverted_double_pendulum.xml
Normal file
@@ -0,0 +1,47 @@
|
||||
<!-- Cartpole Model
|
||||
|
||||
The state space is populated with joints in the order that they are
|
||||
defined in this file. The actuators also operate on joints.
|
||||
|
||||
State-Space (name/joint/parameter):
|
||||
- cart slider position (m)
|
||||
- pole hinge angle (rad)
|
||||
- cart slider velocity (m/s)
|
||||
- pole hinge angular velocity (rad/s)
|
||||
|
||||
Actuators (name/actuator/parameter):
|
||||
- cart motor force x (N)
|
||||
|
||||
-->
|
||||
<mujoco model="cartpole">
|
||||
<compiler coordinate="local" inertiafromgeom="true"/>
|
||||
<custom>
|
||||
<numeric data="2" name="frame_skip"/>
|
||||
</custom>
|
||||
<default>
|
||||
<joint damping="0.05"/>
|
||||
<geom contype="0" friction="1 0.1 0.1" rgba="0.7 0.7 0 1"/>
|
||||
</default>
|
||||
<option gravity="1e-5 0 -9.81" integrator="RK4" timestep="0.01"/>
|
||||
<size nstack="3000"/>
|
||||
<worldbody>
|
||||
<geom name="floor" pos="0 0 -3.0" rgba="0.8 0.9 0.8 1" size="40 40 40" type="plane"/>
|
||||
<geom name="rail" pos="0 0 0" quat="0.707 0 0.707 0" rgba="0.3 0.3 0.7 1" size="0.02 1" type="capsule"/>
|
||||
<body name="cart" pos="0 0 0">
|
||||
<joint axis="1 0 0" limited="true" margin="0.01" name="slider" pos="0 0 0" range="-1 1" type="slide"/>
|
||||
<geom name="cart" pos="0 0 0" quat="0.707 0 0.707 0" size="0.1 0.1" type="capsule"/>
|
||||
<body name="pole" pos="0 0 0">
|
||||
<joint axis="0 1 0" name="hinge" pos="0 0 0" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 0 0.6" name="cpole" rgba="0 0.7 0.7 1" size="0.045 0.3" type="capsule"/>
|
||||
<body name="pole2" pos="0 0 0.6">
|
||||
<joint axis="0 1 0" name="hinge2" pos="0 0 0" type="hinge"/>
|
||||
<geom fromto="0 0 0 0 0 0.6" name="cpole2" rgba="0 0.7 0.7 1" size="0.045 0.3" type="capsule"/>
|
||||
<site name="tip" pos="0 0 .6" size="0.01 0.01"/>
|
||||
</body>
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
<motor ctrllimited="true" ctrlrange="-1 1" gear="500" joint="slider" name="slide"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
27
data/mjcf/inverted_pendulum.xml
Normal file
27
data/mjcf/inverted_pendulum.xml
Normal file
@@ -0,0 +1,27 @@
|
||||
<mujoco model="inverted pendulum">
|
||||
<compiler inertiafromgeom="true"/>
|
||||
<default>
|
||||
<joint armature="0" damping="1" limited="true"/>
|
||||
<geom contype="0" friction="1 0.1 0.1" rgba="0.7 0.7 0 1"/>
|
||||
<tendon/>
|
||||
<motor ctrlrange="-3 3"/>
|
||||
</default>
|
||||
<option gravity="0 0 -9.81" integrator="RK4" timestep="0.02"/>
|
||||
<size nstack="3000"/>
|
||||
<worldbody>
|
||||
<!--geom name="ground" type="plane" pos="0 0 0" /-->
|
||||
<!-- <geom name="rail" pos="0 0 0" quat="0.707 0 0.707 0" rgba="0.3 0.3 0.7 1" size="0.02 1" type="capsule"/> /-->
|
||||
<body name="cart1" pos="0 0 0">
|
||||
<joint axis="1 0 0" limited="true" name="slider" pos="0 0 0" range="-1 1" type="slide"/>
|
||||
<geom name="cart" pos="0 0 0" quat="0.707 0 0.707 0" size="0.1 0.1" type="capsule"/>
|
||||
<body name="pole" pos="0 0 0">
|
||||
<joint axis="0 1 0" name="hinge" pos="0 0 0" range="-90 90" type="hinge"/>
|
||||
<geom fromto="0 0 0 0.001 0 0.6" name="cpole" rgba="0 0.7 0.7 1" size="0.049 0.3" type="capsule"/>
|
||||
<!-- <body name="pole2" pos="0.001 0 0.6"><joint name="hinge2" type="hinge" pos="0 0 0" axis="0 1 0"/><geom name="cpole2" type="capsule" fromto="0 0 0 0 0 0.6" size="0.05 0.3" rgba="0.7 0 0.7 1"/><site name="tip2" pos="0 0 .6"/></body>-->
|
||||
</body>
|
||||
</body>
|
||||
</worldbody>
|
||||
<actuator>
|
||||
<motor gear="100" joint="slider" name="slide"/>
|
||||
</actuator>
|
||||
</mujoco>
|
||||
Binary file not shown.
@@ -74,7 +74,7 @@ ELSE(WIN32)
|
||||
IF(APPLE)
|
||||
find_library(COCOA NAMES Cocoa)
|
||||
MESSAGE(${COCOA})
|
||||
link_libraries(${COCOA})
|
||||
link_libraries(${COCOA} ${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY})
|
||||
|
||||
ELSE(APPLE)
|
||||
INCLUDE_DIRECTORIES(
|
||||
|
||||
@@ -228,9 +228,10 @@ public:
|
||||
|
||||
struct CastRaysLoopBody
|
||||
{
|
||||
btRaycastBar2* mRaycasts;
|
||||
btCollisionWorld* mWorld;
|
||||
CastRaysLoopBody(btCollisionWorld* cw, btRaycastBar2* rb) : mWorld(cw), mRaycasts(rb) {}
|
||||
btRaycastBar2* mRaycasts;
|
||||
|
||||
CastRaysLoopBody(btCollisionWorld* cw, btRaycastBar2* rb) : mWorld(cw), mRaycasts(rb) {}
|
||||
|
||||
void forLoop( int iBegin, int iEnd ) const
|
||||
{
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
SUBDIRS( HelloWorld BasicDemo )
|
||||
IF(BUILD_BULLET3)
|
||||
SUBDIRS( ExampleBrowser ThirdPartyLibs/Gwen ThirdPartyLibs/BussIK OpenGLWindow )
|
||||
SUBDIRS( ExampleBrowser SharedMemory ThirdPartyLibs/Gwen ThirdPartyLibs/BussIK OpenGLWindow )
|
||||
ENDIF()
|
||||
IF(BUILD_PYBULLET)
|
||||
SUBDIRS(pybullet)
|
||||
|
||||
@@ -61,8 +61,8 @@ class CollisionTutorialBullet2 : public CommonExampleInterface
|
||||
plCollisionSdkHandle m_collisionSdkHandle;
|
||||
plCollisionWorldHandle m_collisionWorldHandle;
|
||||
|
||||
int m_stage;
|
||||
int m_counter;
|
||||
// int m_stage;
|
||||
// int m_counter;
|
||||
|
||||
public:
|
||||
|
||||
@@ -70,11 +70,11 @@ public:
|
||||
:m_app(guiHelper->getAppInterface()),
|
||||
m_guiHelper(guiHelper),
|
||||
m_tutorialIndex(tutorialIndex),
|
||||
m_timeSeriesCanvas0(0),
|
||||
m_collisionSdkHandle(0),
|
||||
m_collisionWorldHandle(0),
|
||||
m_stage(0),
|
||||
m_counter(0),
|
||||
m_timeSeriesCanvas0(0)
|
||||
m_collisionWorldHandle(0)
|
||||
// m_stage(0),
|
||||
// m_counter(0)
|
||||
{
|
||||
|
||||
gTotalPoints = 0;
|
||||
|
||||
@@ -6,13 +6,14 @@ struct Bullet2CollisionSdkInternalData
|
||||
btCollisionConfiguration* m_collisionConfig;
|
||||
btCollisionDispatcher* m_dispatcher;
|
||||
btBroadphaseInterface* m_aabbBroadphase;
|
||||
|
||||
btCollisionWorld* m_collisionWorld;
|
||||
|
||||
Bullet2CollisionSdkInternalData()
|
||||
:m_aabbBroadphase(0),
|
||||
m_dispatcher(0),
|
||||
m_collisionWorld(0)
|
||||
:
|
||||
m_collisionConfig(0),
|
||||
m_dispatcher(0),
|
||||
m_aabbBroadphase(0),
|
||||
m_collisionWorld(0)
|
||||
{
|
||||
}
|
||||
};
|
||||
|
||||
@@ -53,13 +53,19 @@ struct RTB3CollisionWorld
|
||||
b3AlignedObjectArray<b3Aabb> m_worldSpaceAabbs;
|
||||
b3AlignedObjectArray<b3GpuFace> m_planeFaces;
|
||||
b3AlignedObjectArray<b3CompoundOverlappingPair> m_compoundOverlappingPairs;
|
||||
int m_nextFreeShapeIndex;
|
||||
|
||||
union
|
||||
{
|
||||
int m_nextFreeShapeIndex;
|
||||
void* m_nextFreeShapePtr;
|
||||
};
|
||||
int m_nextFreeCollidableIndex;
|
||||
int m_nextFreePlaneFaceIndex;
|
||||
|
||||
RTB3CollisionWorld()
|
||||
:m_nextFreeCollidableIndex(START_COLLIDABLE_INDEX),
|
||||
:
|
||||
m_nextFreeShapeIndex(START_SHAPE_INDEX),
|
||||
m_nextFreeCollidableIndex(START_COLLIDABLE_INDEX),
|
||||
m_nextFreePlaneFaceIndex(0)//this value is never exposed to the user, so we can start from 0
|
||||
{
|
||||
}
|
||||
@@ -125,7 +131,8 @@ plCollisionShapeHandle RealTimeBullet3CollisionSdk::createSphereShape(plCollisio
|
||||
shape.m_childOrientation.setValue(0,0,0,1);
|
||||
shape.m_radius = radius;
|
||||
shape.m_shapeType = RTB3_SHAPE_SPHERE;
|
||||
return (plCollisionShapeHandle) world->m_nextFreeShapeIndex++;
|
||||
world->m_nextFreeShapeIndex++;
|
||||
return (plCollisionShapeHandle) world->m_nextFreeShapePtr;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
@@ -147,7 +154,8 @@ plCollisionShapeHandle RealTimeBullet3CollisionSdk::createPlaneShape(plCollision
|
||||
world->m_planeFaces[world->m_nextFreePlaneFaceIndex].m_plane = b3MakeVector4(planeNormalX,planeNormalY,planeNormalZ,planeConstant);
|
||||
shape.m_shapeIndex = world->m_nextFreePlaneFaceIndex++;
|
||||
shape.m_shapeType = RTB3_SHAPE_PLANE;
|
||||
return (plCollisionShapeHandle) world->m_nextFreeShapeIndex++;
|
||||
world->m_nextFreeShapeIndex++;
|
||||
return (plCollisionShapeHandle)world->m_nextFreeShapePtr ;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
@@ -169,7 +177,8 @@ plCollisionShapeHandle RealTimeBullet3CollisionSdk::createCapsuleShape(plCollisi
|
||||
shape.m_height = height;
|
||||
shape.m_shapeIndex = capsuleAxis;
|
||||
shape.m_shapeType = RTB3_SHAPE_CAPSULE;
|
||||
return (plCollisionShapeHandle) world->m_nextFreeShapeIndex++;
|
||||
world->m_nextFreeShapeIndex++;
|
||||
return (plCollisionShapeHandle) world->m_nextFreeShapePtr;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
@@ -186,7 +195,8 @@ plCollisionShapeHandle RealTimeBullet3CollisionSdk::createCompoundShape(plCollis
|
||||
shape.m_childOrientation.setValue(0,0,0,1);
|
||||
shape.m_numChildShapes = 0;
|
||||
shape.m_shapeType = RTB3_SHAPE_COMPOUND_INTERNAL;
|
||||
return (plCollisionShapeHandle) world->m_nextFreeShapeIndex++;
|
||||
world->m_nextFreeShapeIndex++;
|
||||
return (plCollisionShapeHandle) world->m_nextFreeShapePtr;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
@@ -265,7 +275,8 @@ plCollisionObjectHandle RealTimeBullet3CollisionSdk::createCollisionObject( plC
|
||||
collidable.m_shapeIndex = shape.m_shapeIndex;
|
||||
break;
|
||||
*/
|
||||
return (plCollisionObjectHandle)world->m_nextFreeCollidableIndex++;
|
||||
world->m_nextFreeCollidableIndex++;
|
||||
return (plCollisionObjectHandle)world->m_nextFreeShapePtr;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -18,10 +18,49 @@
|
||||
#include "CommonWindowInterface.h"
|
||||
#include "CommonCameraInterface.h"
|
||||
|
||||
enum MyFilterModes
|
||||
{
|
||||
FILTER_GROUPAMASKB_AND_GROUPBMASKA2=0,
|
||||
FILTER_GROUPAMASKB_OR_GROUPBMASKA2
|
||||
};
|
||||
|
||||
struct MyOverlapFilterCallback2 : public btOverlapFilterCallback
|
||||
{
|
||||
int m_filterMode;
|
||||
|
||||
MyOverlapFilterCallback2()
|
||||
:m_filterMode(FILTER_GROUPAMASKB_AND_GROUPBMASKA2)
|
||||
{
|
||||
}
|
||||
|
||||
virtual ~MyOverlapFilterCallback2()
|
||||
{}
|
||||
// return true when pairs need collision
|
||||
virtual bool needBroadphaseCollision(btBroadphaseProxy* proxy0,btBroadphaseProxy* proxy1) const
|
||||
{
|
||||
if (m_filterMode==FILTER_GROUPAMASKB_AND_GROUPBMASKA2)
|
||||
{
|
||||
bool collides = (proxy0->m_collisionFilterGroup & proxy1->m_collisionFilterMask) != 0;
|
||||
collides = collides && (proxy1->m_collisionFilterGroup & proxy0->m_collisionFilterMask);
|
||||
return collides;
|
||||
}
|
||||
|
||||
if (m_filterMode==FILTER_GROUPAMASKB_OR_GROUPBMASKA2)
|
||||
{
|
||||
bool collides = (proxy0->m_collisionFilterGroup & proxy1->m_collisionFilterMask) != 0;
|
||||
collides = collides || (proxy1->m_collisionFilterGroup & proxy0->m_collisionFilterMask);
|
||||
return collides;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
};
|
||||
|
||||
struct CommonMultiBodyBase : public CommonExampleInterface
|
||||
{
|
||||
//keep the collision shapes, for deletion/cleanup
|
||||
btAlignedObjectArray<btCollisionShape*> m_collisionShapes;
|
||||
MyOverlapFilterCallback2* m_filterCallback;
|
||||
btOverlappingPairCache* m_pairCache;
|
||||
btBroadphaseInterface* m_broadphase;
|
||||
btCollisionDispatcher* m_dispatcher;
|
||||
btMultiBodyConstraintSolver* m_solver;
|
||||
@@ -41,7 +80,9 @@ struct CommonMultiBodyBase : public CommonExampleInterface
|
||||
struct GUIHelperInterface* m_guiHelper;
|
||||
|
||||
CommonMultiBodyBase(GUIHelperInterface* helper)
|
||||
:m_broadphase(0),
|
||||
:m_filterCallback(0),
|
||||
m_pairCache(0),
|
||||
m_broadphase(0),
|
||||
m_dispatcher(0),
|
||||
m_solver(0),
|
||||
m_collisionConfiguration(0),
|
||||
@@ -59,11 +100,16 @@ struct CommonMultiBodyBase : public CommonExampleInterface
|
||||
///collision configuration contains default setup for memory, collision setup
|
||||
m_collisionConfiguration = new btDefaultCollisionConfiguration();
|
||||
//m_collisionConfiguration->setConvexConvexMultipointIterations();
|
||||
|
||||
m_filterCallback = new MyOverlapFilterCallback2();
|
||||
|
||||
///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
|
||||
m_dispatcher = new btCollisionDispatcher(m_collisionConfiguration);
|
||||
|
||||
m_broadphase = new btDbvtBroadphase();//btSimpleBroadphase();
|
||||
m_pairCache = new btHashedOverlappingPairCache();
|
||||
|
||||
m_pairCache->setOverlapFilterCallback(m_filterCallback);
|
||||
|
||||
m_broadphase = new btDbvtBroadphase(m_pairCache);//btSimpleBroadphase();
|
||||
|
||||
m_solver = new btMultiBodyConstraintSolver;
|
||||
|
||||
@@ -142,7 +188,13 @@ struct CommonMultiBodyBase : public CommonExampleInterface
|
||||
|
||||
delete m_dispatcher;
|
||||
m_dispatcher=0;
|
||||
|
||||
delete m_pairCache;
|
||||
m_pairCache = 0;
|
||||
|
||||
delete m_filterCallback;
|
||||
m_filterCallback = 0;
|
||||
|
||||
delete m_collisionConfiguration;
|
||||
m_collisionConfiguration=0;
|
||||
}
|
||||
|
||||
@@ -56,7 +56,7 @@ class AllConstraintDemo : public CommonRigidBodyBase
|
||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
||||
}
|
||||
|
||||
virtual void keyboardCallback(unsigned char key, int x, int y);
|
||||
virtual bool keyboardCallback(int key, int state);
|
||||
|
||||
// for cone-twist motor driving
|
||||
float m_Time;
|
||||
@@ -66,7 +66,6 @@ class AllConstraintDemo : public CommonRigidBodyBase
|
||||
|
||||
|
||||
|
||||
const int numObjects = 3;
|
||||
|
||||
#define ENABLE_ALL_DEMOS 1
|
||||
|
||||
@@ -839,10 +838,11 @@ void AllConstraintDemo::displayCallback(void) {
|
||||
}
|
||||
#endif
|
||||
|
||||
void AllConstraintDemo::keyboardCallback(unsigned char key, int x, int y)
|
||||
bool AllConstraintDemo::keyboardCallback(int key, int state)
|
||||
{
|
||||
(void)x;
|
||||
(void)y;
|
||||
|
||||
bool handled = false;
|
||||
|
||||
switch (key)
|
||||
{
|
||||
case 'O' :
|
||||
@@ -870,6 +870,7 @@ void AllConstraintDemo::keyboardCallback(unsigned char key, int x, int y)
|
||||
printf("Slider6Dof %s frame offset\n", offectOnOff ? "uses" : "does not use");
|
||||
}
|
||||
}
|
||||
handled = true;
|
||||
break;
|
||||
default :
|
||||
{
|
||||
@@ -877,6 +878,8 @@ void AllConstraintDemo::keyboardCallback(unsigned char key, int x, int y)
|
||||
}
|
||||
break;
|
||||
}
|
||||
return handled;
|
||||
|
||||
}
|
||||
|
||||
class CommonExampleInterface* AllConstraintCreateFunc(struct CommonExampleOptions& options)
|
||||
|
||||
@@ -443,8 +443,6 @@ void Dof6Spring2Setup::animate()
|
||||
/////// servo motor: flip its target periodically
|
||||
#ifdef USE_6DOF2
|
||||
static float servoNextFrame = -1;
|
||||
btScalar pos = m_data->m_ServoMotorConstraint->getRotationalLimitMotor(2)->m_currentPosition;
|
||||
btScalar target = m_data->m_ServoMotorConstraint->getRotationalLimitMotor(2)->m_servoTarget;
|
||||
if(servoNextFrame < 0)
|
||||
{
|
||||
m_data->m_ServoMotorConstraint->getRotationalLimitMotor(2)->m_servoTarget *= -1;
|
||||
|
||||
@@ -4,8 +4,8 @@
|
||||
#include "../CommonInterfaces/CommonRigidBodyBase.h"
|
||||
#include "../CommonInterfaces/CommonParameterInterface.h"
|
||||
|
||||
short collisionFilterGroup = short(btBroadphaseProxy::CharacterFilter);
|
||||
short collisionFilterMask = short(btBroadphaseProxy::AllFilter ^ (btBroadphaseProxy::CharacterFilter));
|
||||
int collisionFilterGroup = int(btBroadphaseProxy::CharacterFilter);
|
||||
int collisionFilterMask = int(btBroadphaseProxy::AllFilter ^ (btBroadphaseProxy::CharacterFilter));
|
||||
static btScalar radius(0.2);
|
||||
|
||||
struct TestHingeTorque : public CommonRigidBodyBase
|
||||
@@ -123,9 +123,7 @@ void TestHingeTorque::initPhysics()
|
||||
{ // create a door using hinge constraint attached to the world
|
||||
|
||||
int numLinks = 2;
|
||||
bool spherical = false; //set it ot false -to use 1DoF hinges instead of 3DoF sphericals
|
||||
bool canSleep = false;
|
||||
bool selfCollide = false;
|
||||
// bool selfCollide = false;
|
||||
btVector3 linkHalfExtents(0.05, 0.37, 0.1);
|
||||
btVector3 baseHalfExtents(0.05, 0.37, 0.1);
|
||||
|
||||
@@ -223,7 +221,7 @@ void TestHingeTorque::initPhysics()
|
||||
|
||||
btTransform start; start.setIdentity();
|
||||
btVector3 groundOrigin(-0.4f, 3.f, 0.f);
|
||||
btVector3 basePosition = btVector3(-0.4f, 3.f, 0.f);
|
||||
// btVector3 basePosition = btVector3(-0.4f, 3.f, 0.f);
|
||||
btQuaternion groundOrn(btVector3(0,1,0),0.25*SIMD_PI);
|
||||
|
||||
groundOrigin[upAxis] -=.5;
|
||||
|
||||
@@ -118,10 +118,10 @@ public:
|
||||
:NN3DWalkersTimeWarpBase(helper),
|
||||
m_Time(0),
|
||||
m_SpeedupTimestamp(0),
|
||||
m_motorStrength(0.5f),
|
||||
m_targetFrequency(3),
|
||||
m_targetAccumulator(0),
|
||||
m_evaluationsQty(0),
|
||||
m_targetFrequency(3),
|
||||
m_motorStrength(0.5f),
|
||||
m_evaluationsQty(0),
|
||||
m_nextReaped(0),
|
||||
m_timeSeriesCanvas(0)
|
||||
{
|
||||
@@ -729,9 +729,9 @@ bool NN3DWalkersExample::detectCollisions()
|
||||
btManifoldPoint& pt = contactManifold->getContactPoint(j);
|
||||
if (pt.getDistance()<0.f)
|
||||
{
|
||||
const btVector3& ptA = pt.getPositionWorldOnA();
|
||||
const btVector3& ptB = pt.getPositionWorldOnB();
|
||||
const btVector3& normalOnB = pt.m_normalWorldOnB;
|
||||
//const btVector3& ptA = pt.getPositionWorldOnA();
|
||||
//const btVector3& ptB = pt.getPositionWorldOnB();
|
||||
//const btVector3& normalOnB = pt.m_normalWorldOnB;
|
||||
|
||||
if(!DRAW_INTERPENETRATIONS){
|
||||
return collisionDetected;
|
||||
|
||||
@@ -593,7 +593,7 @@ struct NN3DWalkersTimeWarpBase: public CommonRigidBodyBase {
|
||||
timeWarpSimulation(deltaTime);
|
||||
if(mLoopTimer.getTimeSeconds() - speedUpPrintTimeStamp > 1){
|
||||
// on reset, we calculate the performed speed up
|
||||
double speedUp = ((double)performedTime*1000.0)/((double)(mLoopTimer.getTimeMilliseconds()-performanceTimestamp));
|
||||
//double speedUp = ((double)performedTime*1000.0)/((double)(mLoopTimer.getTimeMilliseconds()-performanceTimestamp));
|
||||
// b3Printf("Avg Effective speedup: %f",speedUp);
|
||||
performedTime = 0;
|
||||
performanceTimestamp = mLoopTimer.getTimeMilliseconds();
|
||||
|
||||
@@ -36,12 +36,13 @@ struct MySliderEventHandler : public Gwen::Event::Handler
|
||||
bool m_showValue;
|
||||
|
||||
MySliderEventHandler(const char* varName, Gwen::Controls::TextBox* label, Gwen::Controls::Slider* pSlider,T* target, SliderParamChangedCallback callback, void* userPtr)
|
||||
:m_label(label),
|
||||
: m_callback(callback),
|
||||
m_userPointer(userPtr),
|
||||
m_label(label),
|
||||
m_pSlider(pSlider),
|
||||
m_targetValue(target),
|
||||
m_showValue(true),
|
||||
m_callback(callback),
|
||||
m_userPointer(userPtr)
|
||||
m_targetValue(target),
|
||||
m_showValue(true)
|
||||
|
||||
{
|
||||
memcpy(m_variableName,varName,strlen(varName)+1);
|
||||
}
|
||||
|
||||
@@ -233,7 +233,7 @@ void ExampleBrowserThreadFunc(void* userPtr,void* lsMemory)
|
||||
ExampleBrowserThreadLocalStorage* localStorage = (ExampleBrowserThreadLocalStorage*) lsMemory;
|
||||
|
||||
ExampleBrowserArgs* args = (ExampleBrowserArgs*) userPtr;
|
||||
int workLeft = true;
|
||||
//int workLeft = true;
|
||||
b3CommandLineArgs args2(args->m_argc,args->m_argv);
|
||||
b3Clock clock;
|
||||
|
||||
@@ -411,7 +411,8 @@ btInProcessExampleBrowserMainThreadInternalData* btCreateInProcessExampleBrowser
|
||||
data->m_exampleBrowser = new DefaultBrowser(&data->m_examples);
|
||||
data->m_sharedMem = new InProcessMemory;
|
||||
data->m_exampleBrowser->setSharedMemoryInterface(data->m_sharedMem );
|
||||
bool init = data->m_exampleBrowser->init(argc,argv);
|
||||
bool init;
|
||||
init = data->m_exampleBrowser->init(argc,argv);
|
||||
data->m_clock.reset();
|
||||
return data;
|
||||
}
|
||||
|
||||
@@ -721,7 +721,7 @@ static void saveCurrentSettings(int currentEntry,const char* startFileName)
|
||||
|
||||
static void loadCurrentSettings(const char* startFileName, b3CommandLineArgs& args)
|
||||
{
|
||||
int currentEntry= 0;
|
||||
//int currentEntry= 0;
|
||||
FILE* f = fopen(startFileName,"r");
|
||||
if (f)
|
||||
{
|
||||
|
||||
@@ -29,7 +29,8 @@ struct MyDebugVec3
|
||||
float y;
|
||||
float z;
|
||||
};
|
||||
class MyDebugDrawer : public btIDebugDraw
|
||||
|
||||
ATTRIBUTE_ALIGNED16( class )MyDebugDrawer : public btIDebugDraw
|
||||
{
|
||||
CommonGraphicsApp* m_glApp;
|
||||
int m_debugMode;
|
||||
@@ -40,6 +41,7 @@ class MyDebugDrawer : public btIDebugDraw
|
||||
DefaultColors m_ourColors;
|
||||
|
||||
public:
|
||||
BT_DECLARE_ALIGNED_ALLOCATOR();
|
||||
|
||||
MyDebugDrawer(CommonGraphicsApp* app)
|
||||
: m_glApp(app)
|
||||
|
||||
@@ -46,6 +46,7 @@ class btCollisionShape;
|
||||
class ForkLiftDemo : public CommonExampleInterface
|
||||
{
|
||||
public:
|
||||
GUIHelperInterface* m_guiHelper;
|
||||
|
||||
/* extra stuff*/
|
||||
btVector3 m_cameraPosition;
|
||||
@@ -57,7 +58,6 @@ class ForkLiftDemo : public CommonExampleInterface
|
||||
btRigidBody* m_carChassis;
|
||||
btRigidBody* localCreateRigidBody(btScalar mass, const btTransform& worldTransform, btCollisionShape* colSape);
|
||||
|
||||
GUIHelperInterface* m_guiHelper;
|
||||
int m_wheelInstances[4];
|
||||
|
||||
//----------------------------
|
||||
@@ -195,8 +195,6 @@ bool useMCLPSolver = true;
|
||||
#include "ForkLiftDemo.h"
|
||||
|
||||
|
||||
const int maxProxies = 32766;
|
||||
const int maxOverlap = 65535;
|
||||
|
||||
///btRaycastVehicle is the interface for the constraint that implements the raycast vehicle
|
||||
///notice that for higher-quality slow-moving vehicles, another approach might be better
|
||||
|
||||
@@ -529,7 +529,7 @@ void btFractureDynamicsWorld::fractureCallback( )
|
||||
{
|
||||
int j=f0;
|
||||
|
||||
btCollisionObject* colOb = (btCollisionObject*)manifold->getBody1();
|
||||
// btCollisionObject* colOb = (btCollisionObject*)manifold->getBody1();
|
||||
// btRigidBody* otherOb = btRigidBody::upcast(colOb);
|
||||
// if (!otherOb->getInvMass())
|
||||
// continue;
|
||||
@@ -562,8 +562,8 @@ void btFractureDynamicsWorld::fractureCallback( )
|
||||
{
|
||||
int j=f1;
|
||||
{
|
||||
btCollisionObject* colOb = (btCollisionObject*)manifold->getBody0();
|
||||
btRigidBody* otherOb = btRigidBody::upcast(colOb);
|
||||
//btCollisionObject* colOb = (btCollisionObject*)manifold->getBody0();
|
||||
//btRigidBody* otherOb = btRigidBody::upcast(colOb);
|
||||
// if (!otherOb->getInvMass())
|
||||
// continue;
|
||||
|
||||
|
||||
@@ -336,7 +336,7 @@ void readLibraryGeometries(TiXmlDocument& doc, btAlignedObjectArray<GLInstanceGr
|
||||
|
||||
void readNodeHierarchy(TiXmlElement* node,btHashMap<btHashString,int>& name2Shape, btAlignedObjectArray<ColladaGraphicsInstance>& visualShapeInstances, const btMatrix4x4& parentTransMat)
|
||||
{
|
||||
const char* nodeName = node->Attribute("id");
|
||||
//const char* nodeName = node->Attribute("id");
|
||||
//printf("processing node %s\n", nodeName);
|
||||
|
||||
|
||||
|
||||
@@ -21,10 +21,12 @@
|
||||
|
||||
enum ePARENT_LINK_ENUMS
|
||||
{
|
||||
BASE_LINK_INDEX=-1,
|
||||
|
||||
INVALID_LINK_INDEX=-2
|
||||
};
|
||||
|
||||
|
||||
static int gUid=0;
|
||||
|
||||
static bool parseVector4(btVector4& vec4, const std::string& vector_str)
|
||||
{
|
||||
@@ -120,12 +122,17 @@ struct BulletMJCFImporterInternalData
|
||||
|
||||
btAlignedObjectArray<UrdfModel*> m_models;
|
||||
int m_activeModel;
|
||||
//todo: for full MJCF compatibility, we would need a stack of default values
|
||||
int m_defaultCollisionGroup;
|
||||
int m_defaultCollisionMask;
|
||||
|
||||
//those collision shapes are deleted by caller (todo: make sure this happens!)
|
||||
btAlignedObjectArray<btCollisionShape*> m_allocatedCollisionShapes;
|
||||
|
||||
BulletMJCFImporterInternalData()
|
||||
:m_activeModel(-1)
|
||||
:m_activeModel(-1),
|
||||
m_defaultCollisionGroup(1),
|
||||
m_defaultCollisionMask(1)
|
||||
{
|
||||
m_pathPrefix[0] = 0;
|
||||
}
|
||||
@@ -144,18 +151,48 @@ struct BulletMJCFImporterInternalData
|
||||
return 0;
|
||||
}
|
||||
|
||||
bool parseDefaults(TiXmlElement* root_xml, MJCFErrorLogger* logger)
|
||||
{
|
||||
bool handled= false;
|
||||
//rudimentary 'default' support, would need more work for better feature coverage
|
||||
for (TiXmlElement* child_xml = root_xml->FirstChildElement() ; child_xml ; child_xml = child_xml->NextSiblingElement())
|
||||
{
|
||||
std::string n = child_xml->Value();
|
||||
if (n=="inertial")
|
||||
{
|
||||
}
|
||||
if (n=="geom")
|
||||
{
|
||||
//contype, conaffinity
|
||||
const char* conTypeStr = child_xml->Attribute("contype");
|
||||
if (conTypeStr)
|
||||
{
|
||||
m_defaultCollisionGroup = urdfLexicalCast<int>(conTypeStr);
|
||||
}
|
||||
const char* conAffinityStr = child_xml->Attribute("conaffinity");
|
||||
if (conAffinityStr)
|
||||
{
|
||||
m_defaultCollisionMask = urdfLexicalCast<int>(conAffinityStr);
|
||||
}
|
||||
}
|
||||
}
|
||||
handled=true;
|
||||
return handled;
|
||||
}
|
||||
bool parseRootLevel(TiXmlElement* root_xml,MJCFErrorLogger* logger)
|
||||
{
|
||||
for (TiXmlElement* xml = root_xml->FirstChildElement() ; xml ; xml = xml->NextSiblingElement())
|
||||
for (TiXmlElement* rootxml = root_xml->FirstChildElement() ; rootxml ; rootxml = rootxml->NextSiblingElement())
|
||||
{
|
||||
bool handled = false;
|
||||
std::string n = xml->Value();
|
||||
std::string n = rootxml->Value();
|
||||
|
||||
|
||||
if (n=="body")
|
||||
{
|
||||
int modelIndex = m_models.size();
|
||||
UrdfModel* model = new UrdfModel();
|
||||
m_models.push_back(model);
|
||||
parseBody(xml,modelIndex, INVALID_LINK_INDEX,logger);
|
||||
parseBody(rootxml,modelIndex, INVALID_LINK_INDEX,logger);
|
||||
initTreeAndRoot(*model,logger);
|
||||
handled = true;
|
||||
}
|
||||
@@ -168,7 +205,7 @@ struct BulletMJCFImporterInternalData
|
||||
|
||||
UrdfLink* linkPtr = new UrdfLink();
|
||||
linkPtr->m_name = "anonymous";
|
||||
const char* namePtr = xml->Attribute("name");
|
||||
const char* namePtr = rootxml->Attribute("name");
|
||||
if (namePtr)
|
||||
{
|
||||
linkPtr->m_name = namePtr;
|
||||
@@ -177,12 +214,12 @@ struct BulletMJCFImporterInternalData
|
||||
linkPtr->m_linkIndex = linkIndex;
|
||||
modelPtr->m_links.insert(linkPtr->m_name.c_str(),linkPtr);
|
||||
|
||||
btTransform linkTransform = parseTransform(xml,logger);
|
||||
linkPtr->m_linkTransformInWorld = linkTransform;
|
||||
|
||||
//don't parse geom transform here, it will be inside 'parseGeom'
|
||||
linkPtr->m_linkTransformInWorld.setIdentity();
|
||||
|
||||
// modelPtr->m_rootLinks.push_back(linkPtr);
|
||||
|
||||
parseGeom(xml,modelIndex, linkIndex,logger);
|
||||
parseGeom(rootxml,modelIndex, linkIndex,logger);
|
||||
initTreeAndRoot(*modelPtr,logger);
|
||||
|
||||
handled = true;
|
||||
@@ -202,7 +239,7 @@ struct BulletMJCFImporterInternalData
|
||||
return true;
|
||||
}
|
||||
|
||||
bool parseJoint(TiXmlElement* link_xml, int modelIndex, int parentLinkIndex, int linkIndex, MJCFErrorLogger* logger, btTransform& jointTransOut)
|
||||
bool parseJoint(TiXmlElement* link_xml, int modelIndex, int parentLinkIndex, int linkIndex, MJCFErrorLogger* logger, const btTransform& parentToLinkTrans, btTransform& jointTransOut)
|
||||
{
|
||||
const char* jType = link_xml->Attribute("type");
|
||||
const char* limitedStr = link_xml->Attribute("limited");
|
||||
@@ -210,6 +247,8 @@ struct BulletMJCFImporterInternalData
|
||||
const char* posStr = link_xml->Attribute("pos");
|
||||
const char* ornStr = link_xml->Attribute("quat");
|
||||
const char* nameStr = link_xml->Attribute("name");
|
||||
const char* rangeStr = link_xml->Attribute("range");
|
||||
|
||||
btTransform jointTrans;
|
||||
jointTrans.setIdentity();
|
||||
if (posStr)
|
||||
@@ -242,12 +281,36 @@ struct BulletMJCFImporterInternalData
|
||||
logger->reportWarning("joint without axis attribute");
|
||||
}
|
||||
bool isLimited = false;
|
||||
double range[2] = {1,0};
|
||||
|
||||
if (limitedStr)
|
||||
{
|
||||
std::string lim = limitedStr;
|
||||
if (lim=="true")
|
||||
{
|
||||
isLimited = true;
|
||||
//parse the 'range' field
|
||||
btArray<std::string> pieces;
|
||||
btArray<float> sizes;
|
||||
btAlignedObjectArray<std::string> strArray;
|
||||
urdfIsAnyOf(" ", strArray);
|
||||
urdfStringSplit(pieces, rangeStr, strArray);
|
||||
for (int i = 0; i < pieces.size(); ++i)
|
||||
{
|
||||
if (!pieces[i].empty())
|
||||
{
|
||||
sizes.push_back(urdfLexicalCast<double>(pieces[i].c_str()));
|
||||
}
|
||||
}
|
||||
if (sizes.size()==2)
|
||||
{
|
||||
range[0] = sizes[0];
|
||||
range[1] = sizes[1];
|
||||
} else
|
||||
{
|
||||
logger->reportWarning("Expected range[2] in joint with limits");
|
||||
}
|
||||
|
||||
}
|
||||
} else
|
||||
{
|
||||
@@ -259,7 +322,8 @@ struct BulletMJCFImporterInternalData
|
||||
|
||||
btTransform parentLinkToJointTransform;
|
||||
parentLinkToJointTransform.setIdentity();
|
||||
parentLinkToJointTransform = jointTrans*linkPtr->m_linkTransformInWorld;
|
||||
parentLinkToJointTransform = parentToLinkTrans*jointTrans;
|
||||
|
||||
jointTransOut = jointTrans;
|
||||
UrdfJointTypes ejtype;
|
||||
if (jType)
|
||||
@@ -270,6 +334,11 @@ struct BulletMJCFImporterInternalData
|
||||
ejtype = URDFFixedJoint;
|
||||
jointHandled = true;
|
||||
}
|
||||
if (jointType == "slide")
|
||||
{
|
||||
ejtype = URDFPrismaticJoint;
|
||||
jointHandled = true;
|
||||
}
|
||||
if (jointType == "hinge")
|
||||
{
|
||||
if (isLimited)
|
||||
@@ -288,7 +357,6 @@ struct BulletMJCFImporterInternalData
|
||||
|
||||
if (jointHandled)
|
||||
{
|
||||
//default to 'fixed' joint
|
||||
UrdfJoint* jointPtr = new UrdfJoint();
|
||||
jointPtr->m_childLinkName=linkPtr->m_name;
|
||||
const UrdfLink* parentLink = getLink(modelIndex,parentLinkIndex);
|
||||
@@ -297,13 +365,18 @@ struct BulletMJCFImporterInternalData
|
||||
jointPtr->m_parentLinkToJointTransform = parentLinkToJointTransform;
|
||||
jointPtr->m_type = ejtype;
|
||||
int numJoints = m_models[modelIndex]->m_joints.size();
|
||||
|
||||
//range
|
||||
jointPtr->m_lowerLimit = range[0];
|
||||
jointPtr->m_upperLimit = range[1];
|
||||
|
||||
if (nameStr)
|
||||
{
|
||||
jointPtr->m_name =nameStr;
|
||||
} else
|
||||
{
|
||||
char jointName[1024];
|
||||
sprintf(jointName,"joint%d_%d",linkIndex,numJoints);
|
||||
sprintf(jointName,"joint%d_%d_%d",gUid++,linkIndex,numJoints);
|
||||
jointPtr->m_name =jointName;
|
||||
}
|
||||
m_models[modelIndex]->m_joints.insert(jointPtr->m_name.c_str(),jointPtr);
|
||||
@@ -335,7 +408,10 @@ struct BulletMJCFImporterInternalData
|
||||
|
||||
bool handledGeomType = false;
|
||||
UrdfGeometry geom;
|
||||
const char* rgba = link_xml->Attribute("rgba");
|
||||
|
||||
|
||||
|
||||
// const char* rgba = link_xml->Attribute("rgba");
|
||||
const char* gType = link_xml->Attribute("type");
|
||||
const char* sz = link_xml->Attribute("size");
|
||||
const char* posS = link_xml->Attribute("pos");
|
||||
@@ -356,7 +432,7 @@ struct BulletMJCFImporterInternalData
|
||||
btVector4 o4;
|
||||
if (parseVector4(o4,ornStr))
|
||||
{
|
||||
orn.setValue(o4[3],o4[0],o4[1],o4[2]);
|
||||
orn.setValue(o4[1],o4[2],o4[3],o4[0]);
|
||||
linkLocalFrame.setRotation(orn);
|
||||
}
|
||||
}
|
||||
@@ -410,16 +486,52 @@ struct BulletMJCFImporterInternalData
|
||||
if (geomType == "capsule")
|
||||
{
|
||||
geom.m_type = URDF_GEOM_CAPSULE;
|
||||
geom.m_capsuleRadius = urdfLexicalCast<double>(sz);
|
||||
|
||||
btArray<std::string> pieces;
|
||||
btArray<float> sizes;
|
||||
btAlignedObjectArray<std::string> strArray;
|
||||
urdfIsAnyOf(" ", strArray);
|
||||
urdfStringSplit(pieces, sz, strArray);
|
||||
for (int i = 0; i < pieces.size(); ++i)
|
||||
{
|
||||
if (!pieces[i].empty())
|
||||
{
|
||||
sizes.push_back(urdfLexicalCast<double>(pieces[i].c_str()));
|
||||
}
|
||||
}
|
||||
|
||||
geom.m_capsuleRadius = 0;
|
||||
geom.m_capsuleHalfHeight = 0.f;
|
||||
|
||||
if (sizes.size()>0)
|
||||
{
|
||||
geom.m_capsuleRadius = sizes[0];
|
||||
if (sizes.size()>1)
|
||||
{
|
||||
geom.m_capsuleHalfHeight = sizes[1];
|
||||
}
|
||||
} else
|
||||
{
|
||||
logger->reportWarning("couldn't convert 'size' attribute of capsule geom");
|
||||
}
|
||||
const char* fromtoStr = link_xml->Attribute("fromto");
|
||||
geom.m_hasFromTo = false;
|
||||
|
||||
if (fromtoStr)
|
||||
{
|
||||
geom.m_hasFromTo = true;
|
||||
std::string fromto = fromtoStr;
|
||||
parseVector6(geom.m_capsuleFrom,geom.m_capsuleTo,fromto,logger);
|
||||
handledGeomType = true;
|
||||
} else
|
||||
{
|
||||
logger->reportWarning("capsule without fromto attribute");
|
||||
if (sizes.size()<2)
|
||||
{
|
||||
logger->reportWarning("capsule without fromto attribute requires 2 sizes (radius and halfheight)");
|
||||
} else
|
||||
{
|
||||
handledGeomType = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
#if 0
|
||||
@@ -433,6 +545,26 @@ struct BulletMJCFImporterInternalData
|
||||
{
|
||||
|
||||
UrdfCollision col;
|
||||
col.m_flags |= URDF_HAS_COLLISION_GROUP;
|
||||
col.m_collisionGroup = m_defaultCollisionGroup;
|
||||
|
||||
col.m_flags |= URDF_HAS_COLLISION_MASK;
|
||||
col.m_collisionMask = m_defaultCollisionMask;
|
||||
|
||||
//contype, conaffinity
|
||||
const char* conTypeStr = link_xml->Attribute("contype");
|
||||
if (conTypeStr)
|
||||
{
|
||||
col.m_flags |= URDF_HAS_COLLISION_GROUP;
|
||||
col.m_collisionGroup = urdfLexicalCast<int>(conTypeStr);
|
||||
}
|
||||
const char* conAffinityStr = link_xml->Attribute("conaffinity");
|
||||
if (conAffinityStr)
|
||||
{
|
||||
col.m_flags |= URDF_HAS_COLLISION_MASK;
|
||||
col.m_collisionMask = urdfLexicalCast<int>(conAffinityStr);
|
||||
}
|
||||
|
||||
col.m_geometry = geom;
|
||||
col.m_linkLocalFrame = linkLocalFrame;
|
||||
linkPtr->m_collisionArray.push_back(col);
|
||||
@@ -478,7 +610,7 @@ struct BulletMJCFImporterInternalData
|
||||
btQuaternion orn(0,0,0,1);
|
||||
if (parseVector4(o4,ornstr))
|
||||
{
|
||||
orn.setValue(o4[3],o4[0],o4[1],o4[2]);//MuJoCo quats are [w,x,y,z], Bullet uses [x,y,z,w]
|
||||
orn.setValue(o4[1],o4[2],o4[3],o4[0]);//MuJoCo quats are [w,x,y,z], Bullet uses [x,y,z,w]
|
||||
tr.setRotation(orn);
|
||||
}
|
||||
} else
|
||||
@@ -545,43 +677,72 @@ struct BulletMJCFImporterInternalData
|
||||
|
||||
return totalVolume;
|
||||
}
|
||||
UrdfLink* getLink(int modelIndex, int linkIndex)
|
||||
{
|
||||
UrdfLink** linkPtrPtr = m_models[modelIndex]->m_links.getAtIndex(linkIndex);
|
||||
if (linkPtrPtr && *linkPtrPtr)
|
||||
{
|
||||
return *linkPtrPtr;
|
||||
}
|
||||
btAssert(0);
|
||||
return 0;
|
||||
}
|
||||
|
||||
bool parseBody(TiXmlElement* link_xml, int modelIndex, int parentLinkIndex, MJCFErrorLogger* logger)
|
||||
int createBody(int modelIndex, const char* namePtr)
|
||||
{
|
||||
UrdfModel* modelPtr = m_models[modelIndex];
|
||||
int linkIndex = modelPtr->m_links.size();
|
||||
int orgChildLinkIndex = modelPtr->m_links.size();
|
||||
UrdfLink* linkPtr = new UrdfLink();
|
||||
char uniqueLinkName[1024];
|
||||
sprintf(uniqueLinkName,"link%d",linkIndex);
|
||||
sprintf(uniqueLinkName,"link%d",orgChildLinkIndex );
|
||||
linkPtr->m_name = uniqueLinkName;
|
||||
const char* namePtr = link_xml->Attribute("name");
|
||||
if (namePtr)
|
||||
{
|
||||
linkPtr->m_name = namePtr;
|
||||
}
|
||||
|
||||
linkPtr->m_linkIndex = linkIndex;
|
||||
linkPtr->m_linkIndex = orgChildLinkIndex ;
|
||||
modelPtr->m_links.insert(linkPtr->m_name.c_str(),linkPtr);
|
||||
|
||||
|
||||
btTransform linkTransform = parseTransform(link_xml,logger);
|
||||
return orgChildLinkIndex;
|
||||
}
|
||||
bool parseBody(TiXmlElement* link_xml, int modelIndex, int orgParentLinkIndex, MJCFErrorLogger* logger)
|
||||
{
|
||||
int newParentLinkIndex = orgParentLinkIndex;
|
||||
|
||||
linkPtr->m_linkTransformInWorld = linkTransform;
|
||||
//body/geom links with no parent are root links
|
||||
if (parentLinkIndex==INVALID_LINK_INDEX)
|
||||
const char* bodyName = link_xml->Attribute("name");
|
||||
int orgChildLinkIndex = createBody(modelIndex,bodyName);
|
||||
|
||||
// int curChildLinkIndex = orgChildLinkIndex;
|
||||
std::string bodyN;
|
||||
|
||||
if (bodyName)
|
||||
{
|
||||
// modelPtr->m_rootLinks.push_back(linkPtr);
|
||||
bodyN = bodyName;
|
||||
} else
|
||||
{
|
||||
char anon[1024];
|
||||
sprintf(anon,"anon%d",gUid++);
|
||||
bodyN = anon;
|
||||
}
|
||||
|
||||
|
||||
// btTransform orgLinkTransform = parseTransform(link_xml,logger);
|
||||
|
||||
btTransform linkTransform = parseTransform(link_xml,logger);
|
||||
UrdfLink* linkPtr = getLink(modelIndex,orgChildLinkIndex);
|
||||
|
||||
|
||||
|
||||
bool massDefined = false;
|
||||
btVector3 inertialPos(0,0,0);
|
||||
btQuaternion inertialOrn(0,0,0,1);
|
||||
btScalar mass = 0.f;
|
||||
btVector3 localInertiaDiag(0,0,0);
|
||||
int thisLinkIndex = -2;
|
||||
// int thisLinkIndex = -2;
|
||||
bool hasJoint = false;
|
||||
btTransform jointTrans;
|
||||
jointTrans.setIdentity();
|
||||
bool skipFixedJoint = false;
|
||||
|
||||
for (TiXmlElement* xml = link_xml->FirstChildElement() ; xml ; xml = xml->NextSiblingElement())
|
||||
{
|
||||
@@ -616,31 +777,56 @@ struct BulletMJCFImporterInternalData
|
||||
|
||||
if (n=="joint")
|
||||
{
|
||||
//skip joints at the root for now
|
||||
//MuJoCo supports more than just 'free' or 'fixed',
|
||||
//so we will need to emulate this with extra root links+joints
|
||||
|
||||
//for now, only convert 1st joint
|
||||
if (!hasJoint)
|
||||
{
|
||||
if (parentLinkIndex!=INVALID_LINK_INDEX)
|
||||
const char* jType = xml->Attribute("type");
|
||||
std::string jointType = jType? jType:"";
|
||||
|
||||
if (newParentLinkIndex!=INVALID_LINK_INDEX || jointType!="free")
|
||||
{
|
||||
parseJoint(xml,modelIndex,parentLinkIndex, linkIndex,logger,jointTrans);
|
||||
if (newParentLinkIndex==INVALID_LINK_INDEX)
|
||||
{
|
||||
int newRootLinkIndex = createBody(modelIndex,0);
|
||||
UrdfLink* rootLink = getLink(modelIndex,newRootLinkIndex);
|
||||
rootLink->m_inertia.m_mass = 0;
|
||||
rootLink->m_linkTransformInWorld.setIdentity();
|
||||
newParentLinkIndex = newRootLinkIndex;
|
||||
}
|
||||
|
||||
int newLinkIndex = createBody(modelIndex,0);
|
||||
parseJoint(xml,modelIndex,newParentLinkIndex, newLinkIndex,logger,linkTransform,jointTrans);
|
||||
|
||||
//getLink(modelIndex,newLinkIndex)->m_linkTransformInWorld = jointTrans*linkTransform;
|
||||
|
||||
linkTransform = jointTrans.inverse();
|
||||
newParentLinkIndex = newLinkIndex;
|
||||
//newParentLinkIndex, curChildLinkIndex
|
||||
hasJoint = true;
|
||||
handled = true;
|
||||
}
|
||||
} else
|
||||
{
|
||||
int newLinkIndex = createBody(modelIndex,0);
|
||||
btTransform joint2nextjoint = jointTrans.inverse();
|
||||
btTransform unused;
|
||||
parseJoint(xml,modelIndex,newParentLinkIndex, newLinkIndex,logger,joint2nextjoint,unused);
|
||||
newParentLinkIndex = newLinkIndex;
|
||||
//todo: compute relative joint transforms (if any) and append to linkTransform
|
||||
hasJoint = true;
|
||||
handled = true;
|
||||
}
|
||||
hasJoint = true;
|
||||
handled = true;
|
||||
|
||||
}
|
||||
if (n == "geom")
|
||||
{
|
||||
parseGeom(xml,modelIndex, linkIndex, logger);
|
||||
parseGeom(xml,modelIndex, orgChildLinkIndex , logger);
|
||||
handled = true;
|
||||
}
|
||||
|
||||
//recursive
|
||||
if (n=="body")
|
||||
{
|
||||
parseBody(xml,modelIndex,linkIndex,logger);
|
||||
parseBody(xml,modelIndex,orgChildLinkIndex,logger);
|
||||
handled = true;
|
||||
}
|
||||
|
||||
@@ -657,18 +843,24 @@ struct BulletMJCFImporterInternalData
|
||||
}
|
||||
}
|
||||
|
||||
if ((!hasJoint) && (parentLinkIndex != INVALID_LINK_INDEX))
|
||||
linkPtr->m_linkTransformInWorld = linkTransform;
|
||||
if (bodyN == "cart1")//front_left_leg")
|
||||
{
|
||||
printf("found!\n");
|
||||
}
|
||||
if ((newParentLinkIndex != INVALID_LINK_INDEX) && !skipFixedJoint)
|
||||
{
|
||||
//linkPtr->m_linkTransformInWorld.setIdentity();
|
||||
//default to 'fixed' joint
|
||||
UrdfJoint* jointPtr = new UrdfJoint();
|
||||
jointPtr->m_childLinkName=linkPtr->m_name;
|
||||
const UrdfLink* parentLink = getLink(modelIndex,parentLinkIndex);
|
||||
const UrdfLink* parentLink = getLink(modelIndex,newParentLinkIndex);
|
||||
jointPtr->m_parentLinkName =parentLink->m_name;
|
||||
jointPtr->m_localJointAxis.setValue(1,0,0);
|
||||
jointPtr->m_parentLinkToJointTransform = linkTransform;
|
||||
jointPtr->m_type = URDFFixedJoint;
|
||||
char jointName[1024];
|
||||
sprintf(jointName,"joint%d",linkIndex);
|
||||
sprintf(jointName,"jointfix_%d_%d",gUid++,newParentLinkIndex);
|
||||
jointPtr->m_name =jointName;
|
||||
m_models[modelIndex]->m_joints.insert(jointPtr->m_name.c_str(),jointPtr);
|
||||
}
|
||||
@@ -680,11 +872,26 @@ struct BulletMJCFImporterInternalData
|
||||
double volume = computeVolume(linkPtr,logger);
|
||||
mass = density * volume;
|
||||
}
|
||||
linkPtr->m_inertia.m_linkLocalFrame = jointTrans.inverse();
|
||||
linkPtr->m_inertia.m_linkLocalFrame.setIdentity();// = jointTrans.inverse();
|
||||
linkPtr->m_inertia.m_mass = mass;
|
||||
return true;
|
||||
}
|
||||
|
||||
void recurseAddChildLinks(UrdfModel* model, UrdfLink* link)
|
||||
{
|
||||
for (int i=0;i<link->m_childLinks.size();i++)
|
||||
{
|
||||
int linkIndex = model->m_links.size();
|
||||
link->m_childLinks[i]->m_linkIndex = linkIndex;
|
||||
const char* linkName = link->m_childLinks[i]->m_name.c_str();
|
||||
model->m_links.insert(linkName,link->m_childLinks[i]);
|
||||
}
|
||||
for (int i=0;i<link->m_childLinks.size();i++)
|
||||
{
|
||||
recurseAddChildLinks(model,link->m_childLinks[i]);
|
||||
}
|
||||
}
|
||||
|
||||
bool initTreeAndRoot(UrdfModel& model, MJCFErrorLogger* logger)
|
||||
{
|
||||
// every link has children links and joints, but no parents, so we create a
|
||||
@@ -763,6 +970,23 @@ struct BulletMJCFImporterInternalData
|
||||
logger->reportError("URDF without root link found");
|
||||
return false;
|
||||
}
|
||||
|
||||
//re-index the link indices so parent indices are always smaller than child indices
|
||||
btAlignedObjectArray<UrdfLink*> links;
|
||||
links.resize(model.m_links.size());
|
||||
for (int i=0;i<model.m_links.size();i++)
|
||||
{
|
||||
links[i] = *model.m_links.getAtIndex(i);
|
||||
}
|
||||
model.m_links.clear();
|
||||
for (int i=0;i<model.m_rootLinks.size();i++)
|
||||
{
|
||||
UrdfLink* rootLink = model.m_rootLinks[i];
|
||||
int linkIndex = model.m_links.size();
|
||||
rootLink->m_linkIndex = linkIndex;
|
||||
model.m_links.insert(rootLink->m_name.c_str(),rootLink);
|
||||
recurseAddChildLinks(&model, rootLink);
|
||||
}
|
||||
return true;
|
||||
|
||||
}
|
||||
@@ -791,7 +1015,7 @@ bool BulletMJCFImporter::loadMJCF(const char* fileName, MJCFErrorLogger* logger,
|
||||
b3FileUtils fu;
|
||||
|
||||
//bool fileFound = fu.findFile(fileName, relativeFileName, 1024);
|
||||
bool fileFound = b3ResourcePath::findResourcePath(fileName,relativeFileName,1024);
|
||||
bool fileFound = (b3ResourcePath::findResourcePath(fileName,relativeFileName,1024)>0);
|
||||
|
||||
std::string xml_string;
|
||||
m_data->m_pathPrefix[0] = 0;
|
||||
@@ -850,6 +1074,13 @@ bool BulletMJCFImporter::parseMJCFString(const char* xmlText, MJCFErrorLogger* l
|
||||
m_data->m_fileModelName = modelName;
|
||||
}
|
||||
|
||||
//<compiler>,<option>,<size>,<default>,<body>,<keyframe>,<contactpair>,
|
||||
//<light>, <camera>,<constraint>,<tendon>,<actuator>,<customfield>,<textfield>
|
||||
|
||||
for (TiXmlElement* link_xml = mujoco_xml->FirstChildElement("default"); link_xml; link_xml = link_xml->NextSiblingElement("default"))
|
||||
{
|
||||
m_data->parseDefaults(link_xml,logger);
|
||||
}
|
||||
|
||||
for (TiXmlElement* link_xml = mujoco_xml->FirstChildElement("body"); link_xml; link_xml = link_xml->NextSiblingElement("body"))
|
||||
{
|
||||
@@ -861,8 +1092,7 @@ bool BulletMJCFImporter::parseMJCFString(const char* xmlText, MJCFErrorLogger* l
|
||||
m_data->parseRootLevel(link_xml,logger);
|
||||
}
|
||||
|
||||
//<compiler>,<option>,<size>,<default>,<body>,<keyframe>,<contactpair>,
|
||||
//<light>, <camera>,<constraint>,<tendon>,<actuator>,<customfield>,<textfield>
|
||||
|
||||
|
||||
return true;
|
||||
}
|
||||
@@ -901,10 +1131,43 @@ bool BulletMJCFImporter::getLinkColor(int linkIndex, btVector4& colorRGBA) const
|
||||
return false;
|
||||
}
|
||||
|
||||
//todo: placeholder implementation
|
||||
//MuJoCo type/affinity is different from Bullet group/mask, so we should implement a custom collision filter instead
|
||||
//(contype1 & conaffinity2) || (contype2 & conaffinity1)
|
||||
int BulletMJCFImporter::getCollisionGroupAndMask(int linkIndex, int& colGroup, int& colMask) const
|
||||
{
|
||||
int flags = 0;
|
||||
|
||||
const UrdfLink* link = m_data->getLink(m_data->m_activeModel,linkIndex);
|
||||
if (link)
|
||||
{
|
||||
for (int i=0;i<link->m_collisionArray.size();i++)
|
||||
{
|
||||
const UrdfCollision& col = link->m_collisionArray[i];
|
||||
colGroup = col.m_collisionGroup;
|
||||
flags |= URDF_HAS_COLLISION_GROUP;
|
||||
colMask = col.m_collisionMask;
|
||||
flags |= URDF_HAS_COLLISION_MASK;
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
return flags;
|
||||
}
|
||||
|
||||
|
||||
std::string BulletMJCFImporter::getJointName(int linkIndex) const
|
||||
{
|
||||
const UrdfLink* link = m_data->getLink(m_data->m_activeModel,linkIndex);
|
||||
return link->m_name;
|
||||
if (link)
|
||||
{
|
||||
if (link->m_parentJoint)
|
||||
{
|
||||
return link->m_parentJoint->m_name;
|
||||
}
|
||||
return link->m_name;
|
||||
}
|
||||
return "";
|
||||
}
|
||||
|
||||
//fill mass and inertial data. If inertial data is missing, please initialize mass, inertia to sensitive values, and inertialFrame to identity.
|
||||
@@ -935,7 +1198,8 @@ void BulletMJCFImporter::getLinkChildIndices(int urdfLinkIndex, btAlignedObjectA
|
||||
{
|
||||
for (int i=0;i<link->m_childLinks.size();i++)
|
||||
{
|
||||
childLinkIndices.push_back(link->m_childLinks[i]->m_linkIndex);
|
||||
int childIndex = link->m_childLinks[i]->m_linkIndex;
|
||||
childLinkIndices.push_back(childIndex);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -978,12 +1242,13 @@ bool BulletMJCFImporter::getJointInfo(int urdfLinkIndex, btTransform& parent2joi
|
||||
bool BulletMJCFImporter::getRootTransformInWorld(btTransform& rootTransformInWorld) const
|
||||
{
|
||||
rootTransformInWorld.setIdentity();
|
||||
|
||||
/*
|
||||
const UrdfLink* link = m_data->getLink(m_data->m_activeModel,0);
|
||||
if (link)
|
||||
{
|
||||
rootTransformInWorld = link->m_linkTransformInWorld;
|
||||
}
|
||||
*/
|
||||
return true;
|
||||
}
|
||||
|
||||
@@ -1060,18 +1325,26 @@ class btCompoundShape* BulletMJCFImporter::convertLinkCollisionShapes(int linkIn
|
||||
case URDF_GEOM_CAPSULE:
|
||||
{
|
||||
//todo: convert fromto to btCapsuleShape + local btTransform
|
||||
|
||||
btVector3 f = col->m_geometry.m_capsuleFrom;
|
||||
btVector3 t = col->m_geometry.m_capsuleTo;
|
||||
//MuJoCo seems to take the average of the spheres as center?
|
||||
btVector3 c = (f+t)*0.5;
|
||||
//f-=c;
|
||||
//t-=c;
|
||||
btVector3 fromto[2] = {f,t};
|
||||
btScalar radii[2] = {col->m_geometry.m_capsuleRadius,col->m_geometry.m_capsuleRadius};
|
||||
if (col->m_geometry.m_hasFromTo)
|
||||
{
|
||||
btVector3 f = col->m_geometry.m_capsuleFrom;
|
||||
btVector3 t = col->m_geometry.m_capsuleTo;
|
||||
//MuJoCo seems to take the average of the spheres as center?
|
||||
//btVector3 c = (f+t)*0.5;
|
||||
//f-=c;
|
||||
//t-=c;
|
||||
btVector3 fromto[2] = {f,t};
|
||||
btScalar radii[2] = {btScalar(col->m_geometry.m_capsuleRadius)
|
||||
,btScalar(col->m_geometry.m_capsuleRadius)};
|
||||
|
||||
btMultiSphereShape* ms = new btMultiSphereShape(fromto,radii,2);
|
||||
childShape = ms;
|
||||
btMultiSphereShape* ms = new btMultiSphereShape(fromto,radii,2);
|
||||
childShape = ms;
|
||||
} else
|
||||
{
|
||||
btCapsuleShapeZ* cap = new btCapsuleShapeZ(col->m_geometry.m_capsuleRadius,
|
||||
2.*col->m_geometry.m_capsuleHalfHeight);
|
||||
childShape = cap;
|
||||
}
|
||||
break;
|
||||
}
|
||||
default:
|
||||
|
||||
@@ -46,6 +46,9 @@ public:
|
||||
/// optional method to provide the link color. return true if the color is available and copied into colorRGBA, return false otherwise
|
||||
virtual bool getLinkColor(int linkIndex, btVector4& colorRGBA) const;
|
||||
|
||||
//optional method to get collision group (type) and mask (affinity)
|
||||
virtual int getCollisionGroupAndMask(int linkIndex, int& colGroup, int& colMask) const ;
|
||||
|
||||
///this API will likely change, don't override it!
|
||||
virtual bool getLinkContactInfo(int linkIndex, URDFLinkContactInfo& contactInfo ) const;
|
||||
|
||||
|
||||
@@ -51,6 +51,8 @@ static btAlignedObjectArray<std::string> gMCFJFileNameArray;
|
||||
|
||||
#define MAX_NUM_MOTORS 1024
|
||||
|
||||
|
||||
|
||||
struct ImportMJCFInternalData
|
||||
{
|
||||
ImportMJCFInternalData()
|
||||
@@ -77,7 +79,7 @@ struct ImportMJCFInternalData
|
||||
|
||||
ImportMJCFSetup::ImportMJCFSetup(struct GUIHelperInterface* helper, int option, const char* fileName)
|
||||
:CommonMultiBodyBase(helper),
|
||||
m_grav(0),
|
||||
m_grav(-10),
|
||||
m_upAxis(2)
|
||||
{
|
||||
m_data = new ImportMJCFInternalData;
|
||||
@@ -118,9 +120,10 @@ ImportMJCFSetup::ImportMJCFSetup(struct GUIHelperInterface* helper, int option,
|
||||
if (gMCFJFileNameArray.size()==0)
|
||||
{
|
||||
gMCFJFileNameArray.push_back("mjcf/humanoid.xml");
|
||||
gMCFJFileNameArray.push_back("mjcf/inverted_pendulum.xml");
|
||||
gMCFJFileNameArray.push_back("mjcf/ant.xml");
|
||||
gMCFJFileNameArray.push_back("mjcf/hello_mjcf2.xml");
|
||||
gMCFJFileNameArray.push_back("mjcf/capsule.xml");
|
||||
gMCFJFileNameArray.push_back("mjcf/ant.xml");
|
||||
// gMCFJFileNameArray.push_back("mjcf/hopper.xml");
|
||||
// gMCFJFileNameArray.push_back("mjcf/swimmer.xml");
|
||||
// gMCFJFileNameArray.push_back("mjcf/reacher.xml");
|
||||
@@ -146,25 +149,8 @@ ImportMJCFSetup::~ImportMJCFSetup()
|
||||
delete m_data;
|
||||
}
|
||||
|
||||
static btVector4 colors[4] =
|
||||
{
|
||||
btVector4(1,0,0,1),
|
||||
btVector4(0,1,0,1),
|
||||
btVector4(0,1,1,1),
|
||||
btVector4(1,1,0,1),
|
||||
};
|
||||
|
||||
|
||||
static btVector3 selectColor()
|
||||
{
|
||||
|
||||
static int curColor = 0;
|
||||
btVector4 color = colors[curColor];
|
||||
curColor++;
|
||||
curColor&=3;
|
||||
return color;
|
||||
}
|
||||
|
||||
void ImportMJCFSetup::setFileName(const char* mjcfFileName)
|
||||
{
|
||||
memcpy(m_fileName,mjcfFileName,strlen(mjcfFileName)+1);
|
||||
@@ -187,13 +173,19 @@ struct MyMJCFLogger : public MJCFErrorLogger
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
void ImportMJCFSetup::initPhysics()
|
||||
{
|
||||
|
||||
|
||||
m_guiHelper->setUpAxis(m_upAxis);
|
||||
|
||||
this->createEmptyDynamicsWorld();
|
||||
createEmptyDynamicsWorld();
|
||||
|
||||
//MuJoCo uses a slightly different collision filter mode, use the FILTER_GROUPAMASKB_OR_GROUPBMASKA2
|
||||
//@todo also use the modified collision filter for raycast and other collision related queries
|
||||
m_filterCallback->m_filterMode = FILTER_GROUPAMASKB_OR_GROUPBMASKA2;
|
||||
|
||||
//m_dynamicsWorld->getSolverInfo().m_numIterations = 100;
|
||||
m_guiHelper->createPhysicsDebugDrawer(m_dynamicsWorld);
|
||||
m_dynamicsWorld->getDebugDrawer()->setDebugMode(
|
||||
@@ -228,7 +220,7 @@ void ImportMJCFSetup::initPhysics()
|
||||
|
||||
|
||||
//todo: move these internal API called inside the 'ConvertURDF2Bullet' call, hidden from the user
|
||||
int rootLinkIndex = importer.getRootLinkIndex();
|
||||
//int rootLinkIndex = importer.getRootLinkIndex();
|
||||
//b3Printf("urdf root link index = %d\n",rootLinkIndex);
|
||||
MyMultiBodyCreator creation(m_guiHelper);
|
||||
|
||||
@@ -238,7 +230,7 @@ void ImportMJCFSetup::initPhysics()
|
||||
ConvertURDF2Bullet(importer,creation, rootTrans,m_dynamicsWorld,m_useMultiBody,importer.getPathPrefix(),CUF_USE_MJCF);
|
||||
|
||||
mb = creation.getBulletMultiBody();
|
||||
if (/* DISABLES CODE */ (0)) // mb)
|
||||
if (mb)
|
||||
{
|
||||
printf("first MJCF file converted!\n");
|
||||
std::string* name =
|
||||
|
||||
@@ -30,7 +30,7 @@ bool b3ImportMeshUtility::loadAndRegisterMeshFromFileInternal(const std::string&
|
||||
|
||||
GLInstanceGraphicsShape* gfxShape = btgCreateGraphicsShapeFromWavefrontObj(shapes);
|
||||
|
||||
int textureIndex = -1;
|
||||
//int textureIndex = -1;
|
||||
//try to load some texture
|
||||
for (int i=0;i<shapes.size();i++)
|
||||
{
|
||||
|
||||
@@ -33,7 +33,7 @@ GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(std::vector<tiny
|
||||
int vtxBaseIndex = vertices->size();
|
||||
|
||||
|
||||
if (f<0 && f>=shape.mesh.indices.size())
|
||||
if (f<0 && f>=int(shape.mesh.indices.size()))
|
||||
{
|
||||
continue;
|
||||
}
|
||||
@@ -49,7 +49,7 @@ GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(std::vector<tiny
|
||||
{
|
||||
int uv0Index = shape.mesh.indices[f]*2+0;
|
||||
int uv1Index = shape.mesh.indices[f]*2+1;
|
||||
if (uv0Index>=0 && uv1Index>=0 && (uv0Index < shape.mesh.texcoords.size()) && (uv1Index < shape.mesh.texcoords.size()))
|
||||
if (uv0Index>=0 && uv1Index>=0 && (uv0Index < int(shape.mesh.texcoords.size()) && (uv1Index < shape.mesh.texcoords.size())))
|
||||
{
|
||||
vtx0.uv[0] = shape.mesh.texcoords[uv0Index];
|
||||
vtx0.uv[1] = shape.mesh.texcoords[uv1Index];
|
||||
|
||||
@@ -155,25 +155,8 @@ ImportSDFSetup::~ImportSDFSetup()
|
||||
delete m_data;
|
||||
}
|
||||
|
||||
static btVector4 colors[4] =
|
||||
{
|
||||
btVector4(1,0,0,1),
|
||||
btVector4(0,1,0,1),
|
||||
btVector4(0,1,1,1),
|
||||
btVector4(1,1,0,1),
|
||||
};
|
||||
|
||||
|
||||
static btVector3 selectColor()
|
||||
{
|
||||
|
||||
static int curColor = 0;
|
||||
btVector4 color = colors[curColor];
|
||||
curColor++;
|
||||
curColor&=3;
|
||||
return color;
|
||||
}
|
||||
|
||||
void ImportSDFSetup::setFileName(const char* urdfFileName)
|
||||
{
|
||||
memcpy(m_fileName,urdfFileName,strlen(urdfFileName)+1);
|
||||
@@ -227,7 +210,7 @@ void ImportSDFSetup::initPhysics()
|
||||
|
||||
|
||||
//todo: move these internal API called inside the 'ConvertURDF2Bullet' call, hidden from the user
|
||||
int rootLinkIndex = u2b.getRootLinkIndex();
|
||||
//int rootLinkIndex = u2b.getRootLinkIndex();
|
||||
//b3Printf("urdf root link index = %d\n",rootLinkIndex);
|
||||
MyMultiBodyCreator creation(m_guiHelper);
|
||||
|
||||
|
||||
@@ -41,8 +41,10 @@ struct MyTexture
|
||||
unsigned char* textureData;
|
||||
};
|
||||
|
||||
struct BulletURDFInternalData
|
||||
ATTRIBUTE_ALIGNED16(struct) BulletURDFInternalData
|
||||
{
|
||||
BT_DECLARE_ALIGNED_ALLOCATOR();
|
||||
|
||||
UrdfParser m_urdfParser;
|
||||
struct GUIHelperInterface* m_guiHelper;
|
||||
char m_pathPrefix[1024];
|
||||
@@ -119,7 +121,7 @@ bool BulletURDFImporter::loadURDF(const char* fileName, bool forceFixedBase)
|
||||
b3FileUtils fu;
|
||||
|
||||
//bool fileFound = fu.findFile(fileName, relativeFileName, 1024);
|
||||
bool fileFound = b3ResourcePath::findResourcePath(fileName,relativeFileName,1024);
|
||||
bool fileFound = (b3ResourcePath::findResourcePath(fileName,relativeFileName,1024))>0;
|
||||
|
||||
std::string xml_string;
|
||||
m_data->m_pathPrefix[0] = 0;
|
||||
@@ -171,7 +173,7 @@ bool BulletURDFImporter::loadSDF(const char* fileName, bool forceFixedBase)
|
||||
b3FileUtils fu;
|
||||
|
||||
//bool fileFound = fu.findFile(fileName, relativeFileName, 1024);
|
||||
bool fileFound = b3ResourcePath::findResourcePath(fileName,relativeFileName,1024);
|
||||
bool fileFound = (b3ResourcePath::findResourcePath(fileName,relativeFileName,1024))>0;
|
||||
|
||||
std::string xml_string;
|
||||
m_data->m_pathPrefix[0] = 0;
|
||||
|
||||
@@ -159,25 +159,8 @@ ImportUrdfSetup::~ImportUrdfSetup()
|
||||
delete m_data;
|
||||
}
|
||||
|
||||
static btVector4 colors[4] =
|
||||
{
|
||||
btVector4(1,0,0,1),
|
||||
btVector4(0,1,0,1),
|
||||
btVector4(0,1,1,1),
|
||||
btVector4(1,1,0,1),
|
||||
};
|
||||
|
||||
|
||||
static btVector3 selectColor()
|
||||
{
|
||||
|
||||
static int curColor = 0;
|
||||
btVector4 color = colors[curColor];
|
||||
curColor++;
|
||||
curColor&=3;
|
||||
return color;
|
||||
}
|
||||
|
||||
void ImportUrdfSetup::setFileName(const char* urdfFileName)
|
||||
{
|
||||
memcpy(m_fileName,urdfFileName,strlen(urdfFileName)+1);
|
||||
@@ -237,7 +220,7 @@ void ImportUrdfSetup::initPhysics()
|
||||
|
||||
|
||||
//todo: move these internal API called inside the 'ConvertURDF2Bullet' call, hidden from the user
|
||||
int rootLinkIndex = u2b.getRootLinkIndex();
|
||||
//int rootLinkIndex = u2b.getRootLinkIndex();
|
||||
//b3Printf("urdf root link index = %d\n",rootLinkIndex);
|
||||
MyMultiBodyCreator creation(m_guiHelper);
|
||||
|
||||
|
||||
@@ -11,8 +11,8 @@
|
||||
#include "MultiBodyCreationInterface.h"
|
||||
#include <string>
|
||||
|
||||
static int bodyCollisionFilterGroup=btBroadphaseProxy::CharacterFilter;
|
||||
static int bodyCollisionFilterMask=btBroadphaseProxy::AllFilter&(~btBroadphaseProxy::CharacterFilter);
|
||||
//static int bodyCollisionFilterGroup=btBroadphaseProxy::CharacterFilter;
|
||||
//static int bodyCollisionFilterMask=btBroadphaseProxy::AllFilter&(~btBroadphaseProxy::CharacterFilter);
|
||||
static bool enableConstraints = true;
|
||||
|
||||
static btVector4 colors[4] =
|
||||
@@ -231,6 +231,8 @@ void ConvertURDF2BulletInternal(
|
||||
|
||||
|
||||
bool hasParentJoint = u2b.getJointInfo(urdfLinkIndex, parent2joint, linkTransformInWorldSpace, jointAxisInJointSpace, jointType,jointLowerLimit,jointUpperLimit, jointDamping, jointFriction);
|
||||
std::string linkName = u2b.getLinkName(urdfLinkIndex);
|
||||
|
||||
if (flags & CUF_USE_SDF)
|
||||
{
|
||||
parent2joint =parentTransformInWorldSpace.inverse()*linkTransformInWorldSpace;
|
||||
@@ -314,7 +316,11 @@ void ConvertURDF2BulletInternal(
|
||||
bool isFixedBase = (mass==0);//todo: figure out when base is fixed
|
||||
int totalNumJoints = cache.m_totalNumJoints1;
|
||||
cache.m_bulletMultiBody = creation.allocateMultiBody(urdfLinkIndex, totalNumJoints,mass, localInertiaDiagonal, isFixedBase, canSleep);
|
||||
|
||||
if (flags & CUF_USE_MJCF)
|
||||
{
|
||||
cache.m_bulletMultiBody->setBaseWorldTransform(linkTransformInWorldSpace);
|
||||
}
|
||||
|
||||
cache.registerMultiBody(urdfLinkIndex, cache.m_bulletMultiBody, inertialFrameInWorldSpace, mass, localInertiaDiagonal, compoundShape, localInertialFrame);
|
||||
}
|
||||
|
||||
@@ -440,9 +446,19 @@ void ConvertURDF2BulletInternal(
|
||||
|
||||
//base and fixed? -> static, otherwise flag as dynamic
|
||||
bool isDynamic = (mbLinkIndex<0 && cache.m_bulletMultiBody->hasFixedBase())? false : true;
|
||||
short collisionFilterGroup = isDynamic? short(btBroadphaseProxy::DefaultFilter) : short(btBroadphaseProxy::StaticFilter);
|
||||
short collisionFilterMask = isDynamic? short(btBroadphaseProxy::AllFilter) : short(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||
int collisionFilterGroup = isDynamic? int(btBroadphaseProxy::DefaultFilter) : int(btBroadphaseProxy::StaticFilter);
|
||||
int collisionFilterMask = isDynamic? int(btBroadphaseProxy::AllFilter) : int(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||
|
||||
int colGroup=0, colMask=0;
|
||||
int flags = u2b.getCollisionGroupAndMask(urdfLinkIndex,colGroup, colMask);
|
||||
if (flags & URDF_HAS_COLLISION_GROUP)
|
||||
{
|
||||
collisionFilterGroup = colGroup;
|
||||
}
|
||||
if (flags & URDF_HAS_COLLISION_MASK)
|
||||
{
|
||||
collisionFilterMask = colMask;
|
||||
}
|
||||
world1->addCollisionObject(col,collisionFilterGroup,collisionFilterMask);
|
||||
|
||||
btVector4 color = selectColor2();//(0.0,0.0,0.5);
|
||||
@@ -505,7 +521,12 @@ void ConvertURDF2Bullet(
|
||||
|
||||
btTransform localInertialFrameRoot = cache.m_urdfLinkLocalInertialFrames[urdfLinkIndex];
|
||||
|
||||
mb->setBaseWorldTransform(rootTransformInWorldSpace*localInertialFrameRoot);
|
||||
if (flags & CUF_USE_MJCF)
|
||||
{
|
||||
} else
|
||||
{
|
||||
mb->setBaseWorldTransform(rootTransformInWorldSpace*localInertialFrameRoot);
|
||||
}
|
||||
btAlignedObjectArray<btQuaternion> scratch_q;
|
||||
btAlignedObjectArray<btVector3> scratch_m;
|
||||
mb->forwardKinematics(scratch_q,scratch_m);
|
||||
|
||||
@@ -30,6 +30,7 @@ public:
|
||||
/// optional method to provide the link color. return true if the color is available and copied into colorRGBA, return false otherwise
|
||||
virtual bool getLinkColor(int linkIndex, btVector4& colorRGBA) const { return false;}
|
||||
|
||||
virtual int getCollisionGroupAndMask(int linkIndex, int& colGroup, int& colMask) const { return 0;}
|
||||
///this API will likely change, don't override it!
|
||||
virtual bool getLinkContactInfo(int linkIndex, URDFLinkContactInfo& contactInfo ) const { return false;}
|
||||
|
||||
|
||||
@@ -55,5 +55,11 @@ struct URDFLinkContactInfo
|
||||
}
|
||||
};
|
||||
|
||||
enum UrdfCollisionFlags
|
||||
{
|
||||
URDF_FORCE_CONCAVE_TRIMESH=1,
|
||||
URDF_HAS_COLLISION_GROUP=2,
|
||||
URDF_HAS_COLLISION_MASK=4,
|
||||
};
|
||||
|
||||
#endif //URDF_JOINT_TYPES_H
|
||||
|
||||
@@ -58,6 +58,8 @@ struct UrdfGeometry
|
||||
btVector3 m_boxSize;
|
||||
|
||||
double m_capsuleRadius;
|
||||
double m_capsuleHalfHeight;
|
||||
int m_hasFromTo;
|
||||
btVector3 m_capsuleFrom;
|
||||
btVector3 m_capsuleTo;
|
||||
|
||||
@@ -80,10 +82,7 @@ struct UrdfVisual
|
||||
UrdfMaterial m_localMaterial;
|
||||
};
|
||||
|
||||
enum UrdfCollisionFlags
|
||||
{
|
||||
URDF_FORCE_CONCAVE_TRIMESH=1,
|
||||
};
|
||||
|
||||
|
||||
|
||||
struct UrdfCollision
|
||||
@@ -92,6 +91,8 @@ struct UrdfCollision
|
||||
UrdfGeometry m_geometry;
|
||||
std::string m_name;
|
||||
int m_flags;
|
||||
int m_collisionGroup;
|
||||
int m_collisionMask;
|
||||
UrdfCollision()
|
||||
:m_flags(0)
|
||||
{
|
||||
|
||||
@@ -225,13 +225,13 @@ void InverseDynamicsExample::initPhysics()
|
||||
{
|
||||
qd[dof] = 0;
|
||||
char tmp[25];
|
||||
sprintf(tmp,"q_desired[%u]",dof);
|
||||
sprintf(tmp,"q_desired[%lu]",dof);
|
||||
qd_name[dof] = tmp;
|
||||
SliderParams slider(qd_name[dof].c_str(),&qd[dof]);
|
||||
slider.m_minVal=-3.14;
|
||||
slider.m_maxVal=3.14;
|
||||
|
||||
sprintf(tmp,"q[%u]",dof);
|
||||
sprintf(tmp,"q[%lu]",dof);
|
||||
q_name[dof] = tmp;
|
||||
m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
|
||||
btVector4 color = sJointCurveColors[dof&7];
|
||||
@@ -343,6 +343,7 @@ void InverseDynamicsExample::stepSimulation(float deltaTime)
|
||||
btAlignedObjectArray<btQuaternion> scratch_q;
|
||||
btAlignedObjectArray<btVector3> scratch_m;
|
||||
m_multiBody->forwardKinematics(scratch_q, scratch_m);
|
||||
#if 0
|
||||
for (int i = 0; i < m_multiBody->getNumLinks(); i++)
|
||||
{
|
||||
//btVector3 pos = m_multiBody->getLink(i).m_cachedWorldTransform.getOrigin();
|
||||
@@ -355,6 +356,7 @@ void InverseDynamicsExample::stepSimulation(float deltaTime)
|
||||
|
||||
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -155,10 +155,7 @@ class InverseKinematicsExample : public CommonExampleInterface
|
||||
b3AlignedObjectArray<Node*> m_ikNodes;
|
||||
Jacobian* m_ikJacobian;
|
||||
|
||||
float m_x;
|
||||
float m_y;
|
||||
float m_z;
|
||||
b3AlignedObjectArray<int> m_movingInstances;
|
||||
b3AlignedObjectArray<int> m_movingInstances;
|
||||
int m_targetInstance;
|
||||
enum
|
||||
{
|
||||
@@ -169,12 +166,9 @@ public:
|
||||
|
||||
InverseKinematicsExample(CommonGraphicsApp* app, int option)
|
||||
:m_app(app),
|
||||
m_x(0),
|
||||
m_y(0),
|
||||
m_z(0),
|
||||
m_targetInstance(-1),
|
||||
m_ikMethod(option)
|
||||
{
|
||||
m_ikMethod(option),
|
||||
m_targetInstance(-1)
|
||||
{
|
||||
m_app->setUpAxis(2);
|
||||
|
||||
{
|
||||
@@ -336,7 +330,7 @@ public:
|
||||
|
||||
void InverseKinematicsExample::BuildKukaIIWAShape()
|
||||
{
|
||||
const VectorR3& unitx = VectorR3::UnitX;
|
||||
//const VectorR3& unitx = VectorR3::UnitX;
|
||||
const VectorR3& unity = VectorR3::UnitY;
|
||||
const VectorR3& unitz = VectorR3::UnitZ;
|
||||
const VectorR3 unit1(sqrt(14.0) / 8.0, 1.0 / 8.0, 7.0 / 8.0);
|
||||
|
||||
@@ -211,11 +211,11 @@ btMultiBody* createInvertedPendulumMultiBody(btMultiBodyDynamicsWorld* world, GU
|
||||
local_origin.resize(pMultiBody->getNumLinks() + 1);
|
||||
world_to_local[0] = pMultiBody->getWorldToBaseRot();
|
||||
local_origin[0] = pMultiBody->getBasePos();
|
||||
double friction = 1;
|
||||
// double friction = 1;
|
||||
{
|
||||
|
||||
// float pos[4]={local_origin[0].x(),local_origin[0].y(),local_origin[0].z(),1};
|
||||
float quat[4]={-world_to_local[0].x(),-world_to_local[0].y(),-world_to_local[0].z(),world_to_local[0].w()};
|
||||
// float quat[4]={-world_to_local[0].x(),-world_to_local[0].y(),-world_to_local[0].z(),world_to_local[0].w()};
|
||||
|
||||
|
||||
if (1)
|
||||
@@ -238,8 +238,8 @@ btMultiBody* createInvertedPendulumMultiBody(btMultiBodyDynamicsWorld* world, GU
|
||||
col->setWorldTransform(tr);
|
||||
|
||||
bool isDynamic = (baseMass > 0 && !fixedBase);
|
||||
short collisionFilterGroup = isDynamic? short(btBroadphaseProxy::DefaultFilter) : short(btBroadphaseProxy::StaticFilter);
|
||||
short collisionFilterMask = isDynamic? short(btBroadphaseProxy::AllFilter) : short(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||
int collisionFilterGroup = isDynamic? int(btBroadphaseProxy::DefaultFilter) : int(btBroadphaseProxy::StaticFilter);
|
||||
int collisionFilterMask = isDynamic? int(btBroadphaseProxy::AllFilter) : int(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||
|
||||
|
||||
world->addCollisionObject(col,collisionFilterGroup,collisionFilterMask);//, 2,1+2);
|
||||
@@ -291,8 +291,8 @@ btMultiBody* createInvertedPendulumMultiBody(btMultiBodyDynamicsWorld* world, GU
|
||||
col->setWorldTransform(tr);
|
||||
// col->setFriction(friction);
|
||||
bool isDynamic = 1;//(linkMass > 0);
|
||||
short collisionFilterGroup = isDynamic? short(btBroadphaseProxy::DefaultFilter) : short(btBroadphaseProxy::StaticFilter);
|
||||
short collisionFilterMask = isDynamic? short(btBroadphaseProxy::AllFilter) : short(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||
int collisionFilterGroup = isDynamic? int(btBroadphaseProxy::DefaultFilter) : int(btBroadphaseProxy::StaticFilter);
|
||||
int collisionFilterMask = isDynamic? int(btBroadphaseProxy::AllFilter) : int(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||
|
||||
//if (i==0||i>numLinks-2)
|
||||
{
|
||||
@@ -450,7 +450,7 @@ void InvertedPendulumPDControl::stepSimulation(float deltaTime)
|
||||
m_multiBody->getBaseOmega()[2]
|
||||
);
|
||||
*/
|
||||
btScalar jointVel =m_multiBody->getJointVel(0);
|
||||
// btScalar jointVel =m_multiBody->getJointVel(0);
|
||||
|
||||
// b3Printf("child angvel = %f",jointVel);
|
||||
|
||||
|
||||
@@ -91,7 +91,7 @@ void MultiBodyConstraintFeedbackSetup::initPhysics()
|
||||
m_guiHelper->createCollisionShapeGraphicsObject(box);
|
||||
btTransform start; start.setIdentity();
|
||||
btVector3 groundOrigin(-0.4f, 3.f, 0.f);
|
||||
btVector3 basePosition = btVector3(-0.4f, 3.f, 0.f);
|
||||
//btVector3 basePosition = btVector3(-0.4f, 3.f, 0.f);
|
||||
groundOrigin[upAxis] -=.5;
|
||||
groundOrigin[2]-=0.6;
|
||||
start.setOrigin(groundOrigin);
|
||||
@@ -263,11 +263,11 @@ void MultiBodyConstraintFeedbackSetup::initPhysics()
|
||||
local_origin.resize(pMultiBody->getNumLinks() + 1);
|
||||
world_to_local[0] = pMultiBody->getWorldToBaseRot();
|
||||
local_origin[0] = pMultiBody->getBasePos();
|
||||
double friction = 1;
|
||||
// double friction = 1;
|
||||
{
|
||||
|
||||
// float pos[4]={local_origin[0].x(),local_origin[0].y(),local_origin[0].z(),1};
|
||||
float quat[4]={-world_to_local[0].x(),-world_to_local[0].y(),-world_to_local[0].z(),world_to_local[0].w()};
|
||||
// float quat[4]={-world_to_local[0].x(),-world_to_local[0].y(),-world_to_local[0].z(),world_to_local[0].w()};
|
||||
|
||||
|
||||
if (1)
|
||||
@@ -290,8 +290,8 @@ void MultiBodyConstraintFeedbackSetup::initPhysics()
|
||||
col->setWorldTransform(tr);
|
||||
|
||||
bool isDynamic = (baseMass > 0 && floating);
|
||||
short collisionFilterGroup = isDynamic? short(btBroadphaseProxy::DefaultFilter) : short(btBroadphaseProxy::StaticFilter);
|
||||
short collisionFilterMask = isDynamic? short(btBroadphaseProxy::AllFilter) : short(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||
int collisionFilterGroup = isDynamic? int(btBroadphaseProxy::DefaultFilter) : int(btBroadphaseProxy::StaticFilter);
|
||||
int collisionFilterMask = isDynamic? int(btBroadphaseProxy::AllFilter) : int(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||
|
||||
|
||||
world->addCollisionObject(col,collisionFilterGroup,collisionFilterMask);//, 2,1+2);
|
||||
@@ -343,8 +343,8 @@ void MultiBodyConstraintFeedbackSetup::initPhysics()
|
||||
col->setWorldTransform(tr);
|
||||
// col->setFriction(friction);
|
||||
bool isDynamic = 1;//(linkMass > 0);
|
||||
short collisionFilterGroup = isDynamic? short(btBroadphaseProxy::DefaultFilter) : short(btBroadphaseProxy::StaticFilter);
|
||||
short collisionFilterMask = isDynamic? short(btBroadphaseProxy::AllFilter) : short(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||
int collisionFilterGroup = isDynamic? int(btBroadphaseProxy::DefaultFilter) : int(btBroadphaseProxy::StaticFilter);
|
||||
int collisionFilterMask = isDynamic? int(btBroadphaseProxy::AllFilter) : int(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||
|
||||
//if (i==0||i>numLinks-2)
|
||||
{
|
||||
@@ -416,7 +416,7 @@ void MultiBodyConstraintFeedbackSetup::stepSimulation(float deltaTime)
|
||||
m_multiBody->getBaseOmega()[2]
|
||||
);
|
||||
*/
|
||||
btScalar jointVel =m_multiBody->getJointVel(0);
|
||||
// btScalar jointVel =m_multiBody->getJointVel(0);
|
||||
|
||||
// b3Printf("child angvel = %f",jointVel);
|
||||
|
||||
|
||||
@@ -7,7 +7,7 @@
|
||||
#include "../CommonInterfaces/CommonMultiBodyBase.h"
|
||||
#include "../Utils/b3ResourcePath.h"
|
||||
|
||||
static btScalar radius(0.2);
|
||||
//static btScalar radius(0.2);
|
||||
|
||||
struct MultiBodySoftContact : public CommonMultiBodyBase
|
||||
{
|
||||
@@ -126,8 +126,8 @@ void MultiBodySoftContact::initPhysics()
|
||||
col->setCollisionShape(childShape);
|
||||
pMultiBody->setBaseCollider(col);
|
||||
bool isDynamic = (mass > 0 && !isFixed);
|
||||
short collisionFilterGroup = isDynamic? short(btBroadphaseProxy::DefaultFilter) : short(btBroadphaseProxy::StaticFilter);
|
||||
short collisionFilterMask = isDynamic? short(btBroadphaseProxy::AllFilter) : short(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||
int collisionFilterGroup = isDynamic? int(btBroadphaseProxy::DefaultFilter) : int(btBroadphaseProxy::StaticFilter);
|
||||
int collisionFilterMask = isDynamic? int(btBroadphaseProxy::AllFilter) : int(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||
|
||||
m_dynamicsWorld->addCollisionObject(col,collisionFilterGroup,collisionFilterMask);//, 2,1+2);
|
||||
|
||||
|
||||
@@ -242,7 +242,7 @@ void MultiDofDemo::initPhysics()
|
||||
|
||||
if (multibodyConstraint) {
|
||||
btVector3 pointInA = -linkHalfExtents;
|
||||
btVector3 pointInB = halfExtents;
|
||||
// btVector3 pointInB = halfExtents;
|
||||
btMatrix3x3 frameInA;
|
||||
btMatrix3x3 frameInB;
|
||||
frameInA.setIdentity();
|
||||
|
||||
@@ -150,8 +150,8 @@ void Pendulum::initPhysics()
|
||||
btMultiBodyLinkCollider* col = new btMultiBodyLinkCollider(pMultiBody, i);
|
||||
col->setCollisionShape(shape);
|
||||
bool isDynamic = 1;
|
||||
short collisionFilterGroup = isDynamic? short(btBroadphaseProxy::DefaultFilter) : short(btBroadphaseProxy::StaticFilter);
|
||||
short collisionFilterMask = isDynamic? short(btBroadphaseProxy::AllFilter) : short(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||
int collisionFilterGroup = isDynamic? int(btBroadphaseProxy::DefaultFilter) : int(btBroadphaseProxy::StaticFilter);
|
||||
int collisionFilterMask = isDynamic? int(btBroadphaseProxy::AllFilter) : int(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||
world->addCollisionObject(col,collisionFilterGroup,collisionFilterMask);//,2,1+2);
|
||||
btVector4 color(1,0,0,1);
|
||||
m_guiHelper->createCollisionObjectGraphicsObject(col,color);
|
||||
|
||||
@@ -294,8 +294,8 @@ void TestJointTorqueSetup::initPhysics()
|
||||
col->setWorldTransform(tr);
|
||||
|
||||
bool isDynamic = (baseMass > 0 && floating);
|
||||
short collisionFilterGroup = isDynamic? short(btBroadphaseProxy::DefaultFilter) : short(btBroadphaseProxy::StaticFilter);
|
||||
short collisionFilterMask = isDynamic? short(btBroadphaseProxy::AllFilter) : short(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||
int collisionFilterGroup = isDynamic? int(btBroadphaseProxy::DefaultFilter) : int(btBroadphaseProxy::StaticFilter);
|
||||
int collisionFilterMask = isDynamic? int(btBroadphaseProxy::AllFilter) : int(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||
|
||||
|
||||
world->addCollisionObject(col,collisionFilterGroup,collisionFilterMask);//, 2,1+2);
|
||||
@@ -347,8 +347,8 @@ void TestJointTorqueSetup::initPhysics()
|
||||
col->setWorldTransform(tr);
|
||||
// col->setFriction(friction);
|
||||
bool isDynamic = 1;//(linkMass > 0);
|
||||
short collisionFilterGroup = isDynamic? short(btBroadphaseProxy::DefaultFilter) : short(btBroadphaseProxy::StaticFilter);
|
||||
short collisionFilterMask = isDynamic? short(btBroadphaseProxy::AllFilter) : short(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||
int collisionFilterGroup = isDynamic? int(btBroadphaseProxy::DefaultFilter) : int(btBroadphaseProxy::StaticFilter);
|
||||
int collisionFilterMask = isDynamic? int(btBroadphaseProxy::AllFilter) : int(btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
|
||||
|
||||
//if (i==0||i>numLinks-2)
|
||||
{
|
||||
|
||||
@@ -224,12 +224,12 @@ private:
|
||||
extern TaskManager gTaskMgr;
|
||||
|
||||
|
||||
static void initTaskScheduler()
|
||||
inline static void initTaskScheduler()
|
||||
{
|
||||
gTaskMgr.init();
|
||||
}
|
||||
|
||||
static void cleanupTaskScheduler()
|
||||
inline static void cleanupTaskScheduler()
|
||||
{
|
||||
gTaskMgr.shutdown();
|
||||
}
|
||||
|
||||
@@ -163,8 +163,6 @@ void* SamplelsMemoryFunc()
|
||||
class MultiThreadingExample : public CommonExampleInterface
|
||||
{
|
||||
CommonGraphicsApp* m_app;
|
||||
GUIHelperInterface* m_guiHelper;
|
||||
int m_exampleIndex;
|
||||
b3ThreadSupportInterface* m_threadSupport;
|
||||
btAlignedObjectArray<SampleJob1*> m_jobs;
|
||||
int m_numThreads;
|
||||
@@ -172,12 +170,10 @@ public:
|
||||
|
||||
MultiThreadingExample(GUIHelperInterface* guiHelper, int tutorialIndex)
|
||||
:m_app(guiHelper->getAppInterface()),
|
||||
m_guiHelper(guiHelper),
|
||||
m_exampleIndex(tutorialIndex),
|
||||
m_threadSupport(0),
|
||||
m_numThreads(8)
|
||||
{
|
||||
int numBodies = 1;
|
||||
//int numBodies = 1;
|
||||
|
||||
m_app->setUpAxis(1);
|
||||
m_app->m_renderer->enableBlend(true);
|
||||
|
||||
@@ -279,7 +279,9 @@ void b3Win32ThreadSupport::startThreads(const Win32ThreadConstructionInfo& threa
|
||||
|
||||
}
|
||||
|
||||
SetThreadAffinityMask(handle, 1<<i);
|
||||
DWORD mask = 1;
|
||||
mask = 1<<mask;
|
||||
SetThreadAffinityMask(handle, mask);
|
||||
|
||||
threadStatus.m_taskId = i;
|
||||
threadStatus.m_commandId = 0;
|
||||
|
||||
@@ -43,8 +43,8 @@ struct CommonOpenCLBase : public CommonExampleInterface
|
||||
|
||||
virtual void initCL(int preferredDeviceIndex, int preferredPlatformIndex)
|
||||
{
|
||||
void* glCtx=0;
|
||||
void* glDC = 0;
|
||||
// void* glCtx=0;
|
||||
// void* glDC = 0;
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -208,9 +208,6 @@ void PairBench::initPhysics()
|
||||
useShadowMap = false;
|
||||
|
||||
|
||||
int startItem = 0;
|
||||
|
||||
|
||||
initCL(gPreferredOpenCLDeviceIndex,gPreferredOpenCLPlatformIndex);
|
||||
|
||||
if (m_clData->m_clContext)
|
||||
@@ -298,7 +295,7 @@ void PairBench::createBroadphase(int arraySizeX, int arraySizeY, int arraySizeZ)
|
||||
char * patloc;
|
||||
|
||||
|
||||
for (oriptr = buf; patloc = strstr(oriptr, pattern); oriptr = patloc + patlen)
|
||||
for (oriptr = buf; (patloc = strstr(oriptr, pattern)); oriptr = patloc + patlen)
|
||||
{
|
||||
if (patloc)
|
||||
{
|
||||
@@ -335,12 +332,14 @@ void PairBench::createBroadphase(int arraySizeX, int arraySizeY, int arraySizeZ)
|
||||
if (l>500)
|
||||
{
|
||||
b3Vector4 color=b3MakeVector4(0,1,0,0.1);
|
||||
int id = m_guiHelper->getRenderInterface()->registerGraphicsInstance(shapeId,position,orn,color,scaling);
|
||||
int id;
|
||||
id = m_guiHelper->getRenderInterface()->registerGraphicsInstance(shapeId,position,orn,color,scaling);
|
||||
m_data->m_broadphaseGPU->createLargeProxy(aabbMin,aabbMax,index,group,mask);
|
||||
} else
|
||||
{
|
||||
b3Vector4 color=b3MakeVector4(1,0,0,1);
|
||||
int id = m_guiHelper->getRenderInterface()->registerGraphicsInstance(shapeId,position,orn,color,scaling);
|
||||
int id;
|
||||
id = m_guiHelper->getRenderInterface()->registerGraphicsInstance(shapeId,position,orn,color,scaling);
|
||||
m_data->m_broadphaseGPU->createProxy(aabbMin,aabbMax,index,group,mask);
|
||||
index++;
|
||||
}
|
||||
@@ -403,7 +402,8 @@ void PairBench::createBroadphase(int arraySizeX, int arraySizeY, int arraySizeZ)
|
||||
}*/
|
||||
|
||||
|
||||
int id = m_guiHelper->getRenderInterface()->registerGraphicsInstance(shapeId,position,orn,color,scaling);
|
||||
int id;
|
||||
id = m_guiHelper->getRenderInterface()->registerGraphicsInstance(shapeId,position,orn,color,scaling);
|
||||
|
||||
|
||||
b3Vector3 aabbMin = position-scaling;
|
||||
@@ -486,7 +486,7 @@ void PairBench::stepSimulation(float deltaTime)
|
||||
return;
|
||||
|
||||
|
||||
bool animate=true;
|
||||
//bool animate=true;
|
||||
int numObjects= 0;
|
||||
{
|
||||
B3_PROFILE("Num Objects");
|
||||
@@ -503,7 +503,7 @@ void PairBench::stepSimulation(float deltaTime)
|
||||
int arraySizeInBytes = numObjects * (3)*sizeof(b3Vector4);
|
||||
|
||||
glBindBuffer(GL_ARRAY_BUFFER, vbo);
|
||||
cl_bool blocking= CL_TRUE;
|
||||
// cl_bool blocking= CL_TRUE;
|
||||
char* hostPtr= 0;
|
||||
{
|
||||
B3_PROFILE("glMapBufferRange");
|
||||
@@ -583,7 +583,7 @@ void PairBench::stepSimulation(float deltaTime)
|
||||
B3_PROFILE("updateOnCpu");
|
||||
if (!gPairBenchFileName)
|
||||
{
|
||||
int allAabbs = m_data->m_broadphaseGPU->getAllAabbsCPU().size();
|
||||
// int allAabbs = m_data->m_broadphaseGPU->getAllAabbsCPU().size();
|
||||
|
||||
|
||||
b3AlignedObjectArray<b3Vector4> posOrnColorsCpu;
|
||||
@@ -625,11 +625,12 @@ void PairBench::stepSimulation(float deltaTime)
|
||||
b3Clock cl;
|
||||
dt = cl.getTimeMicroseconds();
|
||||
B3_PROFILE("calculateOverlappingPairs");
|
||||
int sz = sizeof(b3Int4)*64*numObjects;
|
||||
//int sz = sizeof(b3Int4)*64*numObjects;
|
||||
|
||||
|
||||
m_data->m_broadphaseGPU->calculateOverlappingPairs(maxOverlap);
|
||||
int numPairs = m_data->m_broadphaseGPU->getNumOverlap();
|
||||
int numPairs;
|
||||
numPairs = m_data->m_broadphaseGPU->getNumOverlap();
|
||||
//printf("numPairs = %d\n", numPairs);
|
||||
dt = cl.getTimeMicroseconds()-dt;
|
||||
|
||||
|
||||
@@ -223,8 +223,8 @@ int GpuConvexScene::createDynamicsObjects2( const float* vertices, int numVertic
|
||||
}
|
||||
|
||||
int shapeId = m_guiHelper->getRenderInterface()->registerShape(&vertices[0],numVertices,indices,numIndices,B3_GL_TRIANGLES,textureIndex);
|
||||
int group=1;
|
||||
int mask=1;
|
||||
//int group=1;
|
||||
//int mask=1;
|
||||
int index=0;
|
||||
|
||||
|
||||
@@ -237,7 +237,7 @@ int GpuConvexScene::createDynamicsObjects2( const float* vertices, int numVertic
|
||||
int curColor = 0;
|
||||
float scaling[4] = {1,1,1,1};
|
||||
int prevBody = -1;
|
||||
int insta = 0;
|
||||
//int insta = 0;
|
||||
|
||||
b3ConvexUtility* utilPtr = new b3ConvexUtility();
|
||||
|
||||
@@ -290,9 +290,11 @@ int GpuConvexScene::createDynamicsObjects2( const float* vertices, int numVertic
|
||||
b3Vector4 color = colors[curColor];
|
||||
curColor++;
|
||||
curColor&=3;
|
||||
b3Vector4 scalin=b3MakeVector4(1,1,1,1);
|
||||
int id = m_guiHelper->getRenderInterface()->registerGraphicsInstance(shapeId,position,orn,color,scaling);
|
||||
int pid = m_data->m_rigidBodyPipeline->registerPhysicsInstance(mass,position,orn,colIndex,index,false);
|
||||
// b3Vector4 scaling=b3MakeVector4(1,1,1,1);
|
||||
int id;
|
||||
id= m_guiHelper->getRenderInterface()->registerGraphicsInstance(shapeId,position,orn,color,scaling);
|
||||
int pid;
|
||||
pid = m_data->m_rigidBodyPipeline->registerPhysicsInstance(mass,position,orn,colIndex,index,false);
|
||||
|
||||
|
||||
if (prevBody>=0)
|
||||
@@ -319,8 +321,8 @@ void GpuConvexScene::createStaticEnvironment()
|
||||
int numIndices = sizeof(cube_indices)/sizeof(int);
|
||||
//int shapeId = ci.m_instancingRenderer->registerShape(&cube_vertices[0],numVertices,cube_indices,numIndices);
|
||||
int shapeId = m_instancingRenderer->registerShape(&cube_vertices[0],numVertices,cube_indices,numIndices);
|
||||
int group=1;
|
||||
int mask=1;
|
||||
//int group=1;
|
||||
//int mask=1;
|
||||
int index=0;
|
||||
|
||||
|
||||
@@ -332,8 +334,10 @@ void GpuConvexScene::createStaticEnvironment()
|
||||
|
||||
b3Vector4 color=b3MakeVector4(0,0,1,1);
|
||||
|
||||
int id = m_instancingRenderer->registerGraphicsInstance(shapeId,position,orn,color,scaling);
|
||||
int pid = m_data->m_rigidBodyPipeline->registerPhysicsInstance(0.f,position,orn,colIndex,index,false);
|
||||
int id;
|
||||
id = m_instancingRenderer->registerGraphicsInstance(shapeId,position,orn,color,scaling);
|
||||
int pid;
|
||||
pid = m_data->m_rigidBodyPipeline->registerPhysicsInstance(0.f,position,orn,colIndex,index,false);
|
||||
|
||||
}
|
||||
}
|
||||
@@ -345,8 +349,8 @@ void GpuConvexPlaneScene::createStaticEnvironment()
|
||||
int numIndices = sizeof(cube_indices)/sizeof(int);
|
||||
//int shapeId = ci.m_instancingRenderer->registerShape(&cube_vertices[0],numVertices,cube_indices,numIndices);
|
||||
int shapeId = m_guiHelper->getRenderInterface()->registerShape(&cube_vertices[0],numVertices,cube_indices,numIndices);
|
||||
int group=1;
|
||||
int mask=1;
|
||||
// int group=1;
|
||||
// int mask=1;
|
||||
int index=0;
|
||||
|
||||
|
||||
@@ -358,8 +362,10 @@ void GpuConvexPlaneScene::createStaticEnvironment()
|
||||
|
||||
b3Vector4 color=b3MakeVector4(0,0,1,1);
|
||||
|
||||
int id = m_guiHelper->getRenderInterface()->registerGraphicsInstance(shapeId,position,orn,color,scaling);
|
||||
int pid = m_data->m_rigidBodyPipeline->registerPhysicsInstance(0.f,position,orn,colIndex,index,false);
|
||||
int id;
|
||||
id = m_guiHelper->getRenderInterface()->registerGraphicsInstance(shapeId,position,orn,color,scaling);
|
||||
int pid;
|
||||
pid = m_data->m_rigidBodyPipeline->registerPhysicsInstance(0.f,position,orn,colIndex,index,false);
|
||||
|
||||
}
|
||||
|
||||
@@ -535,8 +541,8 @@ void GpuTetraScene::createFromTetGenData(const char* ele,
|
||||
int numVertices = sizeof(mytetra_vertices)/strideInBytes;
|
||||
int numIndices = sizeof(mytetra_indices)/sizeof(int);
|
||||
int shapeId = m_instancingRenderer->registerShape(&mytetra_vertices[0],numVertices,mytetra_indices,numIndices);
|
||||
int group=1;
|
||||
int mask=1;
|
||||
// int group=1;
|
||||
// int mask=1;
|
||||
|
||||
|
||||
|
||||
@@ -553,8 +559,10 @@ void GpuTetraScene::createFromTetGenData(const char* ele,
|
||||
b3Vector4 color = colors[curColor++];
|
||||
curColor&=3;
|
||||
|
||||
int id = m_instancingRenderer->registerGraphicsInstance(shapeId,position,orn,color,scaling);
|
||||
int pid = m_data->m_rigidBodyPipeline->registerPhysicsInstance(1.f,position,orn,colIndex,0,false);
|
||||
int id;
|
||||
id = m_instancingRenderer->registerGraphicsInstance(shapeId,position,orn,color,scaling);
|
||||
int pid;
|
||||
pid = m_data->m_rigidBodyPipeline->registerPhysicsInstance(1.f,position,orn,colIndex,0,false);
|
||||
//rigidBodyIds.push_back(pid);
|
||||
|
||||
}
|
||||
@@ -620,7 +628,8 @@ void GpuTetraScene::createFromTetGenData(const char* ele,
|
||||
bool useGPU = true;
|
||||
if (useGPU)
|
||||
{
|
||||
int cid = m_data->m_rigidBodyPipeline->createFixedConstraint(bodyIndexA,bodyIndexB,pivotInA,pivotInB,relTargetAB,breakingThreshold);
|
||||
int cid;
|
||||
cid = m_data->m_rigidBodyPipeline->createFixedConstraint(bodyIndexA,bodyIndexB,pivotInA,pivotInB,relTargetAB,breakingThreshold);
|
||||
} else
|
||||
{
|
||||
b3FixedConstraint* c = new b3FixedConstraint(bodyIndexA,bodyIndexB,frameInA,frameInB);
|
||||
|
||||
@@ -233,7 +233,7 @@ void GpuRigidBodyDemo::stepSimulation(float deltaTime)
|
||||
GLuint vbo = m_instancingRenderer->getInternalData()->m_vbo;
|
||||
int arraySizeInBytes = numObjects * (3)*sizeof(b3Vector4);
|
||||
glBindBuffer(GL_ARRAY_BUFFER, vbo);
|
||||
cl_bool blocking= CL_TRUE;
|
||||
// cl_bool blocking= CL_TRUE;
|
||||
positions= (b3Vector4*)glMapBufferRange( GL_ARRAY_BUFFER,m_instancingRenderer->getMaxShapeCapacity(),arraySizeInBytes, GL_MAP_READ_BIT );//GL_READ_WRITE);//GL_WRITE_ONLY
|
||||
GLint err = glGetError();
|
||||
assert(err==GL_NO_ERROR);
|
||||
@@ -296,7 +296,7 @@ void GpuRigidBodyDemo::stepSimulation(float deltaTime)
|
||||
int arraySizeInBytes = numObjects * (3)*sizeof(b3Vector4);
|
||||
|
||||
glBindBuffer(GL_ARRAY_BUFFER, vbo);
|
||||
cl_bool blocking= CL_TRUE;
|
||||
// cl_bool blocking= CL_TRUE;
|
||||
positions= (b3Vector4*)glMapBufferRange( GL_ARRAY_BUFFER,m_instancingRenderer->getMaxShapeCapacity(),arraySizeInBytes, GL_MAP_WRITE_BIT );//GL_READ_WRITE);//GL_WRITE_ONLY
|
||||
err = glGetError();
|
||||
assert(err==GL_NO_ERROR);
|
||||
@@ -329,7 +329,7 @@ b3Vector3 GpuRigidBodyDemo::getRayTo(int x,int y)
|
||||
float farPlane = 10000.f;
|
||||
rayForward*= farPlane;
|
||||
|
||||
b3Vector3 rightOffset;
|
||||
// b3Vector3 rightOffset;
|
||||
b3Vector3 m_cameraUp=b3MakeVector3(0,1,0);
|
||||
b3Vector3 vertical = m_cameraUp;
|
||||
|
||||
@@ -401,7 +401,7 @@ bool GpuRigidBodyDemo::mouseMoveCallback(float x,float y)
|
||||
m_data->m_rigidBodyPipeline->removeConstraintByUid(m_data->m_pickConstraint);
|
||||
b3Vector3 newRayTo = getRayTo(x,y);
|
||||
b3Vector3 rayFrom;
|
||||
b3Vector3 oldPivotInB = m_data->m_pickPivotInB;
|
||||
// b3Vector3 oldPivotInB = m_data->m_pickPivotInB;
|
||||
b3Vector3 newPivotB;
|
||||
m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraPosition(rayFrom);
|
||||
b3Vector3 dir = newRayTo-rayFrom;
|
||||
|
||||
@@ -163,10 +163,10 @@ struct InternalDataRenderer : public GLInstanceRendererInternalData
|
||||
|
||||
|
||||
InternalDataRenderer() :
|
||||
m_activeCamera(&m_defaultCamera1),
|
||||
m_shadowMap(0),
|
||||
m_shadowTexture(0),
|
||||
m_renderFrameBuffer(0),
|
||||
m_activeCamera(&m_defaultCamera1)
|
||||
m_renderFrameBuffer(0)
|
||||
{
|
||||
//clear to zero to make it obvious if the matrix is used uninitialized
|
||||
for (int i=0;i<16;i++)
|
||||
@@ -616,7 +616,7 @@ int GLInstancingRenderer::registerTexture(const unsigned char* texels, int width
|
||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
glActiveTexture(GL_TEXTURE0);
|
||||
int textureIndex = m_data->m_textureHandles.size();
|
||||
const GLubyte* image= (const GLubyte*)texels;
|
||||
// const GLubyte* image= (const GLubyte*)texels;
|
||||
GLuint textureHandle;
|
||||
glGenTextures(1,(GLuint*)&textureHandle);
|
||||
glBindTexture(GL_TEXTURE_2D,textureHandle);
|
||||
@@ -661,7 +661,7 @@ void GLInstancingRenderer::updateTexture(int textureIndex, const unsigned cha
|
||||
|
||||
glBindTexture(GL_TEXTURE_2D,h.m_glTexture);
|
||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
const GLubyte* image= (const GLubyte*)texels;
|
||||
// const GLubyte* image= (const GLubyte*)texels;
|
||||
glTexImage2D(GL_TEXTURE_2D, 0, GL_RGB, h.m_width,h.m_height,0,GL_RGB,GL_UNSIGNED_BYTE,&flippedTexels[0]);
|
||||
b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
glGenerateMipmap(GL_TEXTURE_2D);
|
||||
|
||||
@@ -456,7 +456,7 @@ void GLPrimitiveRenderer::drawTexturedRect2a(float x0, float y0, float x1, float
|
||||
PrimVertex( PrimVec4( -1.f+2.f*x1/float(m_screenWidth), 1.f-2.f*y0/float(m_screenHeight), 0.f, 1.f ), PrimVec4( color[0], color[1], color[2], color[3] ) ,PrimVec2(u1,v0))
|
||||
};
|
||||
|
||||
int sz = m_data2->m_numVerticesText;
|
||||
// int sz = m_data2->m_numVerticesText;
|
||||
|
||||
m_data2->m_verticesRect[m_data2->m_numVerticesRect++]=vertexData[0];
|
||||
m_data2->m_verticesRect[m_data2->m_numVerticesRect++]=vertexData[1];
|
||||
@@ -492,7 +492,7 @@ void GLPrimitiveRenderer::drawTexturedRect2(float x0, float y0, float x1, float
|
||||
PrimVertex( PrimVec4( -1.f+2.f*x1/float(m_screenWidth), 1.f-2.f*y0/float(m_screenHeight), 0.f, 1.f ), PrimVec4( color[0], color[1], color[2], color[3] ) ,PrimVec2(u1,v0))
|
||||
};
|
||||
|
||||
int sz = m_data2->m_numVerticesText;
|
||||
// int sz = m_data2->m_numVerticesText;
|
||||
|
||||
m_data2->m_verticesText[m_data2->m_numVerticesText++]=vertexData[0];
|
||||
m_data2->m_verticesText[m_data2->m_numVerticesText++]=vertexData[1];
|
||||
|
||||
@@ -223,8 +223,8 @@ MacOpenGLWindow::MacOpenGLWindow()
|
||||
m_mouseX(0),
|
||||
m_mouseY(0),
|
||||
m_modifierFlags(0),
|
||||
m_mouseMoveCallback(0),
|
||||
m_mouseButtonCallback(0),
|
||||
m_mouseMoveCallback(0),
|
||||
m_wheelCallback(0),
|
||||
m_keyboardCallback(0),
|
||||
m_retinaScaleFactor(1),
|
||||
@@ -334,10 +334,10 @@ void MacOpenGLWindow::createWindow(const b3gWindowConstructionInfo& ci)
|
||||
|
||||
// add Edit menu
|
||||
NSMenuItem *editMenuItem = [[NSMenuItem new] autorelease];
|
||||
NSMenu *menu = [[NSMenu allocWithZone:[NSMenu menuZone]]initWithTitle:@"Edit"];
|
||||
NSMenu *menu = [[NSMenu alloc]initWithTitle:@"Edit"];
|
||||
[editMenuItem setSubmenu: menu];
|
||||
|
||||
NSMenuItem *copyItem = [[NSMenuItem allocWithZone:[NSMenu menuZone]]initWithTitle:@"Copy" action:@selector(copy:) keyEquivalent:@"c"];
|
||||
NSMenuItem *copyItem = [[NSMenuItem alloc]initWithTitle:@"Copy" action:@selector(copy:) keyEquivalent:@"c"];
|
||||
|
||||
[menu addItem:copyItem];
|
||||
[menubar addItem:editMenuItem];
|
||||
|
||||
@@ -672,13 +672,15 @@ void SimpleOpenGL3App::getScreenPixels(unsigned char* rgbaBuffer, int bufferSize
|
||||
if ((width*height*4) == bufferSizeInBytes)
|
||||
{
|
||||
glReadPixels(0,0,width, height, GL_RGBA, GL_UNSIGNED_BYTE, rgbaBuffer);
|
||||
int glstat = glGetError();
|
||||
int glstat;
|
||||
glstat = glGetError();
|
||||
b3Assert(glstat==GL_NO_ERROR);
|
||||
}
|
||||
if ((width*height*sizeof(float)) == depthBufferSizeInBytes)
|
||||
{
|
||||
glReadPixels(0,0,width, height, GL_DEPTH_COMPONENT, GL_FLOAT, depthBuffer);
|
||||
int glstat = glGetError();
|
||||
int glstat;
|
||||
glstat = glGetError();
|
||||
b3Assert(glstat==GL_NO_ERROR);
|
||||
}
|
||||
|
||||
|
||||
@@ -20,10 +20,7 @@
|
||||
class DynamicTexturedCubeDemo : public CommonExampleInterface
|
||||
{
|
||||
CommonGraphicsApp* m_app;
|
||||
float m_x;
|
||||
float m_y;
|
||||
float m_z;
|
||||
b3AlignedObjectArray<int> m_movingInstances;
|
||||
b3AlignedObjectArray<int> m_movingInstances;
|
||||
|
||||
|
||||
TinyVRGui* m_tinyVrGUI;
|
||||
@@ -37,10 +34,7 @@ public:
|
||||
|
||||
DynamicTexturedCubeDemo(CommonGraphicsApp* app)
|
||||
:m_app(app),
|
||||
m_x(0),
|
||||
m_y(0),
|
||||
m_z(0),
|
||||
m_tinyVrGUI(0)
|
||||
m_tinyVrGUI(0)
|
||||
{
|
||||
m_app->setUpAxis(2);
|
||||
|
||||
|
||||
@@ -76,16 +76,16 @@ struct RaytracerInternalData
|
||||
RaytracerInternalData()
|
||||
:m_canvasIndex(-1),
|
||||
m_canvas(0),
|
||||
m_roll(0),
|
||||
m_pitch(0),
|
||||
m_yaw(0),
|
||||
#ifdef _DEBUG
|
||||
m_width(64),
|
||||
m_height(64)
|
||||
m_width(64),
|
||||
m_height(64),
|
||||
#else
|
||||
m_width(128),
|
||||
m_height(128)
|
||||
m_width(128),
|
||||
m_height(128),
|
||||
#endif
|
||||
m_pitch(0),
|
||||
m_roll(0),
|
||||
m_yaw(0)
|
||||
{
|
||||
btConeShape* cone = new btConeShape(1,1);
|
||||
btSphereShape* sphere = new btSphereShape(1);
|
||||
@@ -300,7 +300,7 @@ void RaytracerPhysicsSetup::stepSimulation(float deltaTime)
|
||||
|
||||
|
||||
|
||||
int mode = 0;
|
||||
// int mode = 0;
|
||||
int x,y;
|
||||
|
||||
for (x=0;x<m_internalData->m_width;x++)
|
||||
|
||||
@@ -298,7 +298,7 @@ void TimeSeriesCanvas::insertDataAtCurrentTime(float orgV, int dataSourceIndex,
|
||||
float amp = m_internalData->m_pixelsPerUnit;
|
||||
//insert some new value(s) in the right-most column
|
||||
{
|
||||
float time = m_internalData->getTime();
|
||||
// float time = m_internalData->getTime();
|
||||
|
||||
float v = zero+amp*orgV;
|
||||
|
||||
|
||||
@@ -43,14 +43,14 @@ struct TinyRendererSetupInternalData
|
||||
int m_animateRenderer;
|
||||
|
||||
TinyRendererSetupInternalData(int width, int height)
|
||||
:m_roll(0),
|
||||
m_pitch(0),
|
||||
m_yaw(0),
|
||||
|
||||
m_width(width),
|
||||
m_height(height),
|
||||
:
|
||||
m_rgbColorBuffer(width,height,TGAImage::RGB),
|
||||
m_textureHandle(0),
|
||||
m_width(width),
|
||||
m_height(height),
|
||||
m_pitch(0),
|
||||
m_roll(0),
|
||||
m_yaw(0),
|
||||
m_textureHandle(0),
|
||||
m_animateRenderer(0)
|
||||
{
|
||||
m_depthBuffer.resize(m_width*m_height);
|
||||
|
||||
@@ -19,9 +19,10 @@ struct TestCanvasInterface2 : public Common2dCanvasInterface
|
||||
int m_height;
|
||||
|
||||
TestCanvasInterface2(b3AlignedObjectArray<unsigned char>& texelsRGB, int width, int height)
|
||||
:m_width(width),
|
||||
m_height(height),
|
||||
m_texelsRGB(texelsRGB)
|
||||
:
|
||||
m_texelsRGB(texelsRGB),
|
||||
m_width(width),
|
||||
m_height(height)
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
@@ -157,7 +157,8 @@ void RigidBodySoftContact::initPhysics()
|
||||
btScalar(2.0*j)));
|
||||
|
||||
|
||||
btRigidBody* body = createRigidBody(mass,startTransform,colShape);
|
||||
btRigidBody* body;
|
||||
body = createRigidBody(mass,startTransform,colShape);
|
||||
//body->setAngularVelocity(btVector3(1,1,1));
|
||||
|
||||
|
||||
|
||||
@@ -25,13 +25,9 @@ class GripperGraspExample : public CommonExampleInterface
|
||||
GUIHelperInterface* m_guiHelper;
|
||||
b3RobotSimAPI m_robotSim;
|
||||
int m_options;
|
||||
int m_r2d2Index;
|
||||
int m_gripperIndex;
|
||||
|
||||
float m_x;
|
||||
float m_y;
|
||||
float m_z;
|
||||
b3AlignedObjectArray<int> m_movingInstances;
|
||||
b3AlignedObjectArray<int> m_movingInstances;
|
||||
enum
|
||||
{
|
||||
numCubesX = 20,
|
||||
@@ -43,12 +39,8 @@ public:
|
||||
:m_app(helper->getAppInterface()),
|
||||
m_guiHelper(helper),
|
||||
m_options(options),
|
||||
m_r2d2Index(-1),
|
||||
m_gripperIndex(-1),
|
||||
m_x(0),
|
||||
m_y(0),
|
||||
m_z(0)
|
||||
{
|
||||
m_gripperIndex(-1)
|
||||
{
|
||||
m_app->setUpAxis(2);
|
||||
}
|
||||
virtual ~GripperGraspExample()
|
||||
|
||||
@@ -30,7 +30,7 @@ class KukaGraspExample : public CommonExampleInterface
|
||||
b3Vector4 m_targetOri;
|
||||
b3Vector4 m_worldOri;
|
||||
double m_time;
|
||||
int m_options;
|
||||
// int m_options;
|
||||
|
||||
b3AlignedObjectArray<int> m_movingInstances;
|
||||
enum
|
||||
@@ -40,10 +40,10 @@ class KukaGraspExample : public CommonExampleInterface
|
||||
};
|
||||
public:
|
||||
|
||||
KukaGraspExample(GUIHelperInterface* helper, int options)
|
||||
KukaGraspExample(GUIHelperInterface* helper, int /* options */)
|
||||
:m_app(helper->getAppInterface()),
|
||||
m_guiHelper(helper),
|
||||
m_options(options),
|
||||
// m_options(options),
|
||||
m_kukaIndex(-1),
|
||||
m_time(0)
|
||||
{
|
||||
|
||||
@@ -23,9 +23,6 @@ class R2D2GraspExample : public CommonExampleInterface
|
||||
int m_options;
|
||||
int m_r2d2Index;
|
||||
|
||||
float m_x;
|
||||
float m_y;
|
||||
float m_z;
|
||||
b3AlignedObjectArray<int> m_movingInstances;
|
||||
enum
|
||||
{
|
||||
@@ -38,10 +35,7 @@ public:
|
||||
:m_app(helper->getAppInterface()),
|
||||
m_guiHelper(helper),
|
||||
m_options(options),
|
||||
m_r2d2Index(-1),
|
||||
m_x(0),
|
||||
m_y(0),
|
||||
m_z(0)
|
||||
m_r2d2Index(-1)
|
||||
{
|
||||
m_app->setUpAxis(2);
|
||||
}
|
||||
@@ -70,7 +64,7 @@ public:
|
||||
b3RobotSimLoadFileResults results;
|
||||
if (m_robotSim.loadFile(args, results) && results.m_uniqueObjectIds.size()==1)
|
||||
{
|
||||
int m_r2d2Index = results.m_uniqueObjectIds[0];
|
||||
m_r2d2Index = results.m_uniqueObjectIds[0];
|
||||
int numJoints = m_robotSim.getNumJoints(m_r2d2Index);
|
||||
b3Printf("numJoints = %d",numJoints);
|
||||
|
||||
|
||||
@@ -106,10 +106,10 @@ struct RobotSimThreadLocalStorage
|
||||
void RobotThreadFunc(void* userPtr,void* lsMemory)
|
||||
{
|
||||
printf("RobotThreadFunc thread started\n");
|
||||
RobotSimThreadLocalStorage* localStorage = (RobotSimThreadLocalStorage*) lsMemory;
|
||||
// RobotSimThreadLocalStorage* localStorage = (RobotSimThreadLocalStorage*) lsMemory;
|
||||
|
||||
RobotSimArgs* args = (RobotSimArgs*) userPtr;
|
||||
int workLeft = true;
|
||||
// int workLeft = true;
|
||||
b3Clock clock;
|
||||
clock.reset();
|
||||
bool init = true;
|
||||
@@ -157,7 +157,7 @@ void* RobotlsMemoryFunc()
|
||||
|
||||
ATTRIBUTE_ALIGNED16(class) MultiThreadedOpenGLGuiHelper2 : public GUIHelperInterface
|
||||
{
|
||||
CommonGraphicsApp* m_app;
|
||||
// CommonGraphicsApp* m_app;
|
||||
|
||||
b3CriticalSection* m_cs;
|
||||
|
||||
@@ -188,9 +188,8 @@ public:
|
||||
int m_instanceId;
|
||||
|
||||
|
||||
MultiThreadedOpenGLGuiHelper2(CommonGraphicsApp* app, GUIHelperInterface* guiHelper)
|
||||
:m_app(app)
|
||||
,m_cs(0),
|
||||
MultiThreadedOpenGLGuiHelper2( GUIHelperInterface* guiHelper)
|
||||
: m_cs(0),
|
||||
m_texels(0),
|
||||
m_textureId(-1)
|
||||
{
|
||||
@@ -439,11 +438,13 @@ struct b3RobotSimAPI_InternalData
|
||||
bool m_connected;
|
||||
|
||||
b3RobotSimAPI_InternalData()
|
||||
:m_threadSupport(0),
|
||||
m_multiThreadedHelper(0),
|
||||
m_clientServerDirect(0),
|
||||
m_physicsClient(0),
|
||||
m_useMultiThreading(false),
|
||||
:
|
||||
m_physicsClient(0),
|
||||
m_threadSupport(0),
|
||||
m_multiThreadedHelper(0),
|
||||
|
||||
m_clientServerDirect(0),
|
||||
m_useMultiThreading(false),
|
||||
m_connected(false)
|
||||
{
|
||||
}
|
||||
@@ -615,7 +616,8 @@ void b3RobotSimAPI::processMultiThreadedGraphicsRequests()
|
||||
case eRobotSimGUIHelperRemoveAllGraphicsInstances:
|
||||
{
|
||||
m_data->m_multiThreadedHelper->m_childGuiHelper->removeAllGraphicsInstances();
|
||||
int numRenderInstances = m_data->m_multiThreadedHelper->m_childGuiHelper->getRenderInterface()->getTotalNumInstances();
|
||||
int numRenderInstances;
|
||||
numRenderInstances = m_data->m_multiThreadedHelper->m_childGuiHelper->getRenderInterface()->getTotalNumInstances();
|
||||
b3Assert(numRenderInstances==0);
|
||||
|
||||
m_data->m_multiThreadedHelper->getCriticalSection()->lock();
|
||||
@@ -695,7 +697,7 @@ bool b3RobotSimAPI::getJointStates(int bodyUniqueId, b3JointStates& state)
|
||||
|
||||
if (statusHandle)
|
||||
{
|
||||
double rootInertialFrame[7];
|
||||
// double rootInertialFrame[7];
|
||||
const double* rootLocalInertialFrame;
|
||||
const double* actualStateQ;
|
||||
const double* actualStateQdot;
|
||||
@@ -843,7 +845,8 @@ bool b3RobotSimAPI::loadFile(const struct b3RobotSimLoadFileArgs& args, b3RobotS
|
||||
if (numBodies)
|
||||
{
|
||||
results.m_uniqueObjectIds.resize(numBodies);
|
||||
int numBodies = b3GetStatusBodyIndices(statusHandle, &results.m_uniqueObjectIds[0],results.m_uniqueObjectIds.size());
|
||||
int numBodies;
|
||||
numBodies = b3GetStatusBodyIndices(statusHandle, &results.m_uniqueObjectIds[0],results.m_uniqueObjectIds.size());
|
||||
|
||||
}
|
||||
statusOk = true;
|
||||
@@ -865,11 +868,7 @@ bool b3RobotSimAPI::connect(GUIHelperInterface* guiHelper)
|
||||
{
|
||||
if (m_data->m_useMultiThreading)
|
||||
{
|
||||
m_data->m_multiThreadedHelper = new MultiThreadedOpenGLGuiHelper2(guiHelper->getAppInterface(), guiHelper);
|
||||
|
||||
MultiThreadedOpenGLGuiHelper2* guiHelperWrapper = new MultiThreadedOpenGLGuiHelper2(guiHelper->getAppInterface(), guiHelper);
|
||||
|
||||
|
||||
m_data->m_multiThreadedHelper = new MultiThreadedOpenGLGuiHelper2(guiHelper);
|
||||
|
||||
|
||||
m_data->m_threadSupport = createRobotSimThreadSupport(MAX_ROBOT_NUM_THREADS);
|
||||
@@ -892,7 +891,7 @@ bool b3RobotSimAPI::connect(GUIHelperInterface* guiHelper)
|
||||
int numMoving = 0;
|
||||
m_data->m_args[w].m_positions.resize(numMoving);
|
||||
m_data->m_args[w].m_physicsServerPtr = &m_data->m_physicsServer;
|
||||
int index = 0;
|
||||
//int index = 0;
|
||||
|
||||
m_data->m_threadSupport->runTask(B3_THREAD_SCHEDULE_TASK, (void*)&m_data->m_args[w], w);
|
||||
while (m_data->m_args[w].m_cs->getSharedParam(0) == eRobotSimIsUnInitialized)
|
||||
@@ -903,7 +902,8 @@ bool b3RobotSimAPI::connect(GUIHelperInterface* guiHelper)
|
||||
m_data->m_args[0].m_cs->setSharedParam(1, eRobotSimGUIHelperIdle);
|
||||
m_data->m_multiThreadedHelper->setCriticalSection(m_data->m_args[0].m_cs);
|
||||
|
||||
bool serverConnected = m_data->m_physicsServer.connectSharedMemory(m_data->m_multiThreadedHelper);
|
||||
bool serverConnected;
|
||||
serverConnected = m_data->m_physicsServer.connectSharedMemory(m_data->m_multiThreadedHelper);
|
||||
b3Assert(serverConnected);
|
||||
|
||||
m_data->m_physicsClient = b3ConnectSharedMemory(SHARED_MEMORY_KEY);
|
||||
@@ -912,7 +912,8 @@ bool b3RobotSimAPI::connect(GUIHelperInterface* guiHelper)
|
||||
{
|
||||
PhysicsServerCommandProcessor* sdk = new PhysicsServerCommandProcessor;
|
||||
m_data->m_clientServerDirect = new PhysicsDirect(sdk,true);
|
||||
bool connected = m_data->m_clientServerDirect->connect(guiHelper);
|
||||
bool connected;
|
||||
connected = m_data->m_clientServerDirect->connect(guiHelper);
|
||||
m_data->m_physicsClient = (b3PhysicsClientHandle)m_data->m_clientServerDirect;
|
||||
|
||||
}
|
||||
|
||||
206
examples/SharedMemory/CMakeLists.txt
Normal file
206
examples/SharedMemory/CMakeLists.txt
Normal file
@@ -0,0 +1,206 @@
|
||||
|
||||
|
||||
SET(SharedMemory_SRCS
|
||||
IKTrajectoryHelper.cpp
|
||||
IKTrajectoryHelper.h
|
||||
PhysicsClient.cpp
|
||||
PhysicsClientSharedMemory.cpp
|
||||
PhysicsClientExample.cpp
|
||||
PhysicsServerExample.cpp
|
||||
PhysicsServerSharedMemory.cpp
|
||||
PhysicsServerSharedMemory.h
|
||||
PhysicsServer.cpp
|
||||
PhysicsServer.h
|
||||
PhysicsClientC_API.cpp
|
||||
SharedMemoryCommands.h
|
||||
SharedMemoryPublic.h
|
||||
PhysicsServer.cpp
|
||||
PosixSharedMemory.cpp
|
||||
Win32SharedMemory.cpp
|
||||
InProcessMemory.cpp
|
||||
PhysicsDirect.cpp
|
||||
PhysicsDirect.h
|
||||
PhysicsDirectC_API.cpp
|
||||
PhysicsDirectC_API.h
|
||||
PhysicsLoopBack.cpp
|
||||
PhysicsLoopBack.h
|
||||
PhysicsLoopBackC_API.cpp
|
||||
PhysicsLoopBackC_API.h
|
||||
PhysicsClientSharedMemory_C_API.cpp
|
||||
PhysicsClientSharedMemory_C_API.h
|
||||
PhysicsClientSharedMemory2_C_API.cpp
|
||||
PhysicsClientSharedMemory2_C_API.h
|
||||
PhysicsClientSharedMemory2.cpp
|
||||
PhysicsClientSharedMemory2.h
|
||||
SharedMemoryCommandProcessor.cpp
|
||||
SharedMemoryCommandProcessor.h
|
||||
PhysicsServerCommandProcessor.cpp
|
||||
PhysicsServerCommandProcessor.h
|
||||
TinyRendererVisualShapeConverter.cpp
|
||||
TinyRendererVisualShapeConverter.h
|
||||
../TinyRenderer/geometry.cpp
|
||||
../TinyRenderer/model.cpp
|
||||
../TinyRenderer/tgaimage.cpp
|
||||
../TinyRenderer/our_gl.cpp
|
||||
../TinyRenderer/TinyRenderer.cpp
|
||||
../OpenGLWindow/SimpleCamera.cpp
|
||||
../OpenGLWindow/SimpleCamera.h
|
||||
../Importers/ImportURDFDemo/ConvertRigidBodies2MultiBody.h
|
||||
../Importers/ImportURDFDemo/MultiBodyCreationInterface.h
|
||||
../Importers/ImportURDFDemo/MyMultiBodyCreator.cpp
|
||||
../Importers/ImportURDFDemo/MyMultiBodyCreator.h
|
||||
../Importers/ImportURDFDemo/BulletUrdfImporter.cpp
|
||||
../Importers/ImportURDFDemo/BulletUrdfImporter.h
|
||||
../Importers/ImportURDFDemo/UrdfParser.cpp
|
||||
../Importers/ImportURDFDemo/urdfStringSplit.cpp
|
||||
../Importers/ImportURDFDemo/UrdfParser.cpp
|
||||
../Importers/ImportURDFDemo/UrdfParser.h
|
||||
../Importers/ImportURDFDemo/URDF2Bullet.cpp
|
||||
../Importers/ImportURDFDemo/URDF2Bullet.h
|
||||
../Importers/ImportMJCFDemo/BulletMJCFImporter.cpp
|
||||
../Importers/ImportMJCFDemo/BulletMJCFImporter.h
|
||||
../Utils/b3ResourcePath.cpp
|
||||
../Utils/b3Clock.cpp
|
||||
../Importers/ImportURDFDemo/URDFImporterInterface.h
|
||||
../Importers/ImportURDFDemo/URDFJointTypes.h
|
||||
../Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp
|
||||
../Importers/ImportObjDemo/LoadMeshFromObj.cpp
|
||||
../Importers/ImportSTLDemo/ImportSTLSetup.h
|
||||
../Importers/ImportSTLDemo/LoadMeshFromSTL.h
|
||||
../Importers/ImportColladaDemo/LoadMeshFromCollada.cpp
|
||||
../Importers/ImportColladaDemo/ColladaGraphicsInstance.h
|
||||
../ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp
|
||||
../ThirdPartyLibs/tinyxml/tinystr.cpp
|
||||
../ThirdPartyLibs/tinyxml/tinyxml.cpp
|
||||
../ThirdPartyLibs/tinyxml/tinyxmlerror.cpp
|
||||
../ThirdPartyLibs/tinyxml/tinyxmlparser.cpp
|
||||
../Importers/ImportMeshUtility/b3ImportMeshUtility.cpp
|
||||
../ThirdPartyLibs/stb_image/stb_image.cpp
|
||||
../MultiThreading/b3ThreadSupportInterface.cpp
|
||||
../MultiThreading/b3ThreadSupportInterface.h
|
||||
)
|
||||
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/src
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs
|
||||
)
|
||||
|
||||
LINK_LIBRARIES(
|
||||
Bullet3Common BulletWorldImporter BulletFileLoader BulletInverseDynamicsUtils BulletInverseDynamics BulletDynamics BulletCollision LinearMath BussIK
|
||||
)
|
||||
|
||||
IF (WIN32)
|
||||
ADD_EXECUTABLE(App_SharedMemoryPhysics
|
||||
${SharedMemory_SRCS}
|
||||
main.cpp
|
||||
../MultiThreading/b3Win32ThreadSupport.cpp
|
||||
../MultiThreading/b3Win32ThreadSupport.h
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/build3/bullet.rc
|
||||
)
|
||||
ELSE(WIN32)
|
||||
IF(APPLE)
|
||||
LINK_LIBRARIES( pthread dl )
|
||||
ADD_EXECUTABLE(App_SharedMemoryPhysics
|
||||
${SharedMemory_SRCS}
|
||||
../MultiThreading/b3PosixThreadSupport.cpp
|
||||
../MultiThreading/b3PosixThreadSupport.h
|
||||
main.cpp
|
||||
)
|
||||
|
||||
ELSE(APPLE)
|
||||
LINK_LIBRARIES( pthread dl )
|
||||
ADD_EXECUTABLE(App_SharedMemoryPhysics
|
||||
${SharedMemory_SRCS}
|
||||
../MultiThreading/b3PosixThreadSupport.cpp
|
||||
../MultiThreading/b3PosixThreadSupport.h
|
||||
main.cpp
|
||||
)
|
||||
ENDIF(APPLE)
|
||||
ENDIF(WIN32)
|
||||
|
||||
|
||||
|
||||
|
||||
IF (INTERNAL_ADD_POSTFIX_EXECUTABLE_NAMES)
|
||||
SET_TARGET_PROPERTIES(App_SharedMemoryPhysics PROPERTIES DEBUG_POSTFIX "_Debug")
|
||||
SET_TARGET_PROPERTIES(App_SharedMemoryPhysics PROPERTIES MINSIZEREL_POSTFIX "_MinsizeRel")
|
||||
SET_TARGET_PROPERTIES(App_SharedMemoryPhysics PROPERTIES RELWITHDEBINFO_POSTFIX "_RelWithDebugInfo")
|
||||
ENDIF(INTERNAL_ADD_POSTFIX_EXECUTABLE_NAMES)
|
||||
|
||||
|
||||
|
||||
INCLUDE_DIRECTORIES(
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/src
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/Glew
|
||||
)
|
||||
|
||||
ADD_DEFINITIONS(-DB3_USE_STANDALONE_EXAMPLE)
|
||||
|
||||
LINK_LIBRARIES(
|
||||
Bullet3Common BulletWorldImporter BulletInverseDynamicsUtils BulletInverseDynamics BulletDynamics BulletCollision LinearMath BussIK OpenGLWindow
|
||||
)
|
||||
|
||||
|
||||
|
||||
IF (WIN32)
|
||||
ADD_DEFINITIONS(-DGLEW_STATIC)
|
||||
LINK_LIBRARIES( ${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY} )
|
||||
|
||||
ADD_EXECUTABLE(App_SharedMemoryPhysics_GUI
|
||||
${SharedMemory_SRCS}
|
||||
../StandaloneMain/main_opengl_single_example.cpp
|
||||
../ExampleBrowser/OpenGLGuiHelper.cpp
|
||||
../ExampleBrowser/GL_ShapeDrawer.cpp
|
||||
../ExampleBrowser/CollisionShape2TriangleMesh.cpp
|
||||
../MultiThreading/b3Win32ThreadSupport.cpp
|
||||
../MultiThreading/b3Win32ThreadSupport.h
|
||||
${BULLET_PHYSICS_SOURCE_DIR}/build3/bullet.rc
|
||||
)
|
||||
ELSE(WIN32)
|
||||
IF(APPLE)
|
||||
LINK_LIBRARIES( pthread dl )
|
||||
FIND_LIBRARY(COCOA NAMES Cocoa)
|
||||
MESSAGE(${COCOA})
|
||||
LINK_LIBRARIES(${COCOA} ${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY})
|
||||
|
||||
ADD_EXECUTABLE(App_SharedMemoryPhysics_GUI
|
||||
${SharedMemory_SRCS}
|
||||
../StandaloneMain/main_opengl_single_example.cpp
|
||||
../ExampleBrowser/OpenGLGuiHelper.cpp
|
||||
../ExampleBrowser/GL_ShapeDrawer.cpp
|
||||
../ExampleBrowser/CollisionShape2TriangleMesh.cpp
|
||||
../MultiThreading/b3PosixThreadSupport.cpp
|
||||
../MultiThreading/b3PosixThreadSupport.h
|
||||
)
|
||||
|
||||
ELSE(APPLE)
|
||||
LINK_LIBRARIES( pthread dl )
|
||||
ADD_DEFINITIONS("-DGLEW_INIT_OPENGL11_FUNCTIONS=1")
|
||||
ADD_DEFINITIONS("-DGLEW_STATIC")
|
||||
ADD_DEFINITIONS("-DGLEW_DYNAMIC_LOAD_ALL_GLX_FUNCTIONS=1")
|
||||
|
||||
ADD_EXECUTABLE(App_SharedMemoryPhysics_GUI
|
||||
${SharedMemory_SRCS}
|
||||
../StandaloneMain/main_opengl_single_example.cpp
|
||||
../ExampleBrowser/OpenGLGuiHelper.cpp
|
||||
../ExampleBrowser/GL_ShapeDrawer.cpp
|
||||
../ExampleBrowser/CollisionShape2TriangleMesh.cpp
|
||||
../MultiThreading/b3PosixThreadSupport.cpp
|
||||
../MultiThreading/b3PosixThreadSupport.h
|
||||
)
|
||||
ENDIF(APPLE)
|
||||
ENDIF(WIN32)
|
||||
|
||||
|
||||
|
||||
|
||||
IF (INTERNAL_ADD_POSTFIX_EXECUTABLE_NAMES)
|
||||
SET_TARGET_PROPERTIES(App_SharedMemoryPhysics_GUI PROPERTIES DEBUG_POSTFIX "_Debug")
|
||||
SET_TARGET_PROPERTIES(App_SharedMemoryPhysics_GUI PROPERTIES MINSIZEREL_POSTFIX "_MinsizeRel")
|
||||
SET_TARGET_PROPERTIES(App_SharedMemoryPhysics_GUI PROPERTIES RELWITHDEBINFO_POSTFIX "_RelWithDebugInfo")
|
||||
ENDIF(INTERNAL_ADD_POSTFIX_EXECUTABLE_NAMES)
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -347,6 +347,18 @@ int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHand
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
int b3PhysicsParamSetCollisionFilterMode(b3SharedMemoryCommandHandle commandHandle, int filterMode)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
|
||||
command->m_physSimParamArgs.m_collisionFilterMode = filterMode;
|
||||
command->m_updateFlags |= SIM_PARAM_UPDATE_COLLISION_FILTER_MODE;
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
|
||||
int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double timeStep)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
@@ -1109,6 +1121,19 @@ int b3InitChangeUserConstraintSetFrameInB(b3SharedMemoryCommandHandle commandHan
|
||||
return 0;
|
||||
}
|
||||
|
||||
int b3InitChangeUserConstraintSetMaxForce(b3SharedMemoryCommandHandle commandHandle, double maxAppliedForce)
|
||||
{
|
||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||
b3Assert(command);
|
||||
b3Assert(command->m_type == CMD_USER_CONSTRAINT);
|
||||
b3Assert(command->m_updateFlags & USER_CONSTRAINT_CHANGE_CONSTRAINT);
|
||||
|
||||
command->m_updateFlags |=USER_CONSTRAINT_CHANGE_MAX_FORCE;
|
||||
command->m_userConstraintArguments.m_maxAppliedForce = maxAppliedForce;
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitRemoveUserConstraintCommand(b3PhysicsClientHandle physClient, int userConstraintUniqueId)
|
||||
{
|
||||
|
||||
@@ -77,6 +77,8 @@ int b3GetStatusUserConstraintUniqueId(b3SharedMemoryStatusHandle statusHandle);
|
||||
b3SharedMemoryCommandHandle b3InitChangeUserConstraintCommand(b3PhysicsClientHandle physClient, int userConstraintUniqueId);
|
||||
int b3InitChangeUserConstraintSetPivotInB(b3SharedMemoryCommandHandle commandHandle, double jointChildPivot[3]);
|
||||
int b3InitChangeUserConstraintSetFrameInB(b3SharedMemoryCommandHandle commandHandle, double jointChildFrameOrn[4]);
|
||||
int b3InitChangeUserConstraintSetMaxForce(b3SharedMemoryCommandHandle commandHandle, double maxAppliedForce);
|
||||
|
||||
|
||||
b3SharedMemoryCommandHandle b3InitRemoveUserConstraintCommand(b3PhysicsClientHandle physClient, int userConstraintUniqueId);
|
||||
|
||||
@@ -170,6 +172,10 @@ int b3PhysicsParamSetDefaultContactERP(b3SharedMemoryCommandHandle commandHandle
|
||||
int b3PhysicsParamSetNumSubSteps(b3SharedMemoryCommandHandle commandHandle, int numSubSteps);
|
||||
int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandHandle, int enableRealTimeSimulation);
|
||||
int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations);
|
||||
int b3PhysicsParamSetCollisionFilterMode(b3SharedMemoryCommandHandle commandHandle, int filterMode);
|
||||
|
||||
|
||||
|
||||
int b3PhysicsParamSetUseSplitImpulse(b3SharedMemoryCommandHandle commandHandle, int useSplitImpulse);
|
||||
int b3PhysicsParamSetSplitImpulsePenetrationThreshold(b3SharedMemoryCommandHandle commandHandle, double splitImpulsePenetrationThreshold);
|
||||
|
||||
|
||||
@@ -514,13 +514,13 @@ m_wantsTermination(false),
|
||||
m_sharedMemoryKey(SHARED_MEMORY_KEY),
|
||||
m_selectedBody(-1),
|
||||
m_prevSelectedBody(-1),
|
||||
m_numMotors(0),
|
||||
m_options(options),
|
||||
m_isOptionalServerConnected(false),
|
||||
m_canvas(0),
|
||||
m_canvasRGBIndex(-1),
|
||||
m_canvasDepthIndex(-1),
|
||||
m_canvasSegMaskIndex(-1)
|
||||
m_canvasSegMaskIndex(-1),
|
||||
m_numMotors(0),
|
||||
m_options(options),
|
||||
m_isOptionalServerConnected(false)
|
||||
|
||||
{
|
||||
b3Printf("Started PhysicsClientExample\n");
|
||||
|
||||
@@ -62,10 +62,9 @@ struct PhysicsClientSharedMemoryInternalData {
|
||||
: m_sharedMemory(0),
|
||||
m_ownsSharedMemory(false),
|
||||
m_testBlock1(0),
|
||||
m_counter(0),
|
||||
m_cachedCameraPixelsWidth(0),
|
||||
m_cachedCameraPixelsHeight(0),
|
||||
|
||||
m_counter(0),
|
||||
m_isConnected(false),
|
||||
m_waitingForServer(false),
|
||||
m_hasLastServerStatus(false),
|
||||
@@ -283,7 +282,7 @@ void PhysicsClientSharedMemory::processBodyJointInfo(int bodyUniqueId, const Sha
|
||||
}
|
||||
|
||||
const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
|
||||
SharedMemoryStatus* stat = 0;
|
||||
// SharedMemoryStatus* stat = 0;
|
||||
|
||||
if (!m_data->m_testBlock1) {
|
||||
m_data->m_lastServerStatus.m_type = CMD_SHARED_MEMORY_NOT_INITIALIZED;
|
||||
@@ -308,7 +307,7 @@ const SharedMemoryStatus* PhysicsClientSharedMemory::processServerStatus() {
|
||||
const SharedMemoryStatus& serverCmd = m_data->m_testBlock1->m_serverCommands[0];
|
||||
m_data->m_lastServerStatus = serverCmd;
|
||||
|
||||
EnumSharedMemoryServerStatus s = (EnumSharedMemoryServerStatus)serverCmd.m_type;
|
||||
// EnumSharedMemoryServerStatus s = (EnumSharedMemoryServerStatus)serverCmd.m_type;
|
||||
// consume the command
|
||||
|
||||
switch (serverCmd.m_type) {
|
||||
|
||||
@@ -170,7 +170,7 @@ struct UdpNetworkedInternalData
|
||||
|
||||
if (gVerboseNetworkMessagesClient)
|
||||
{
|
||||
printf("A packet of length %u containing '%s' was "
|
||||
printf("A packet of length %lu containing '%s' was "
|
||||
"received from %s on channel %u.\n",
|
||||
m_event.packet->dataLength,
|
||||
m_event.packet->data,
|
||||
@@ -225,7 +225,7 @@ struct UdpNetworkedInternalData
|
||||
{
|
||||
if (gVerboseNetworkMessagesClient)
|
||||
{
|
||||
printf("A packet of length %u containing '%s' was "
|
||||
printf("A packet of length %lu containing '%s' was "
|
||||
"received from %s on channel %u.\n",
|
||||
m_event.packet->dataLength,
|
||||
m_event.packet->data,
|
||||
@@ -303,10 +303,10 @@ enum UDPCommandEnums
|
||||
void UDPThreadFunc(void* userPtr, void* lsMemory)
|
||||
{
|
||||
printf("UDPThreadFunc thread started\n");
|
||||
UDPThreadLocalStorage* localStorage = (UDPThreadLocalStorage*)lsMemory;
|
||||
// UDPThreadLocalStorage* localStorage = (UDPThreadLocalStorage*)lsMemory;
|
||||
|
||||
UdpNetworkedInternalData* args = (UdpNetworkedInternalData*)userPtr;
|
||||
int workLeft = true;
|
||||
// int workLeft = true;
|
||||
b3Clock clock;
|
||||
clock.reset();
|
||||
bool init = true;
|
||||
@@ -366,7 +366,8 @@ void UDPThreadFunc(void* userPtr, void* lsMemory)
|
||||
|
||||
int sz = sizeof(SharedMemoryCommand);
|
||||
ENetPacket *packet = enet_packet_create(&args->m_clientCmd, sz, ENET_PACKET_FLAG_RELIABLE);
|
||||
int res = enet_peer_send(args->m_peer, 0, packet);
|
||||
int res;
|
||||
res = enet_peer_send(args->m_peer, 0, packet);
|
||||
args->m_cs->lock();
|
||||
args->m_hasCommand = false;
|
||||
args->m_cs->unlock();
|
||||
@@ -440,7 +441,7 @@ UdpNetworkedPhysicsProcessor::~UdpNetworkedPhysicsProcessor()
|
||||
|
||||
bool UdpNetworkedPhysicsProcessor::processCommand(const struct SharedMemoryCommand& clientCmd, struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes)
|
||||
{
|
||||
int sz = sizeof(SharedMemoryCommand);
|
||||
// int sz = sizeof(SharedMemoryCommand);
|
||||
int timeout = 1024 * 1024 * 1024;
|
||||
|
||||
m_data->m_cs->lock();
|
||||
|
||||
@@ -12,7 +12,8 @@ b3PhysicsClientHandle b3ConnectPhysicsUDP(const char* hostName, int port)
|
||||
|
||||
PhysicsDirect* direct = new PhysicsDirect(udp,true);
|
||||
|
||||
bool connected = direct->connect();
|
||||
bool connected;
|
||||
connected = direct->connect();
|
||||
printf("direct!\n");
|
||||
return (b3PhysicsClientHandle)direct;
|
||||
}
|
||||
|
||||
@@ -12,7 +12,8 @@ b3PhysicsClientHandle b3ConnectPhysicsDirect()
|
||||
PhysicsServerCommandProcessor* sdk = new PhysicsServerCommandProcessor;
|
||||
|
||||
PhysicsDirect* direct = new PhysicsDirect(sdk,true);
|
||||
bool connected = direct->connect();
|
||||
bool connected;
|
||||
connected = direct->connect();
|
||||
return (b3PhysicsClientHandle )direct;
|
||||
}
|
||||
|
||||
|
||||
@@ -9,7 +9,8 @@ b3PhysicsClientHandle b3ConnectPhysicsLoopback(int key)
|
||||
{
|
||||
PhysicsLoopBack* loopBack = new PhysicsLoopBack();
|
||||
loopBack->setSharedMemoryKey(key);
|
||||
bool connected = loopBack->connect();
|
||||
bool connected;
|
||||
connected = loopBack->connect();
|
||||
return (b3PhysicsClientHandle )loopBack;
|
||||
}
|
||||
|
||||
|
||||
@@ -376,6 +376,47 @@ struct MyBroadphaseCallback : public btBroadphaseAabbCallback
|
||||
};
|
||||
|
||||
|
||||
|
||||
enum MyFilterModes
|
||||
{
|
||||
FILTER_GROUPAMASKB_AND_GROUPBMASKA=0,
|
||||
FILTER_GROUPAMASKB_OR_GROUPBMASKA
|
||||
};
|
||||
|
||||
struct MyOverlapFilterCallback : public btOverlapFilterCallback
|
||||
{
|
||||
int m_filterMode;
|
||||
|
||||
MyOverlapFilterCallback()
|
||||
:m_filterMode(FILTER_GROUPAMASKB_AND_GROUPBMASKA)
|
||||
{
|
||||
}
|
||||
|
||||
virtual ~MyOverlapFilterCallback()
|
||||
{}
|
||||
// return true when pairs need collision
|
||||
virtual bool needBroadphaseCollision(btBroadphaseProxy* proxy0,btBroadphaseProxy* proxy1) const
|
||||
{
|
||||
if (m_filterMode==FILTER_GROUPAMASKB_AND_GROUPBMASKA)
|
||||
{
|
||||
bool collides = (proxy0->m_collisionFilterGroup & proxy1->m_collisionFilterMask) != 0;
|
||||
collides = collides && (proxy1->m_collisionFilterGroup & proxy0->m_collisionFilterMask);
|
||||
return collides;
|
||||
}
|
||||
|
||||
if (m_filterMode==FILTER_GROUPAMASKB_OR_GROUPBMASKA)
|
||||
{
|
||||
bool collides = (proxy0->m_collisionFilterGroup & proxy1->m_collisionFilterMask) != 0;
|
||||
collides = collides || (proxy1->m_collisionFilterGroup & proxy0->m_collisionFilterMask);
|
||||
return collides;
|
||||
}
|
||||
return false;
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
|
||||
|
||||
struct PhysicsServerCommandProcessorInternalData
|
||||
{
|
||||
///handle management
|
||||
@@ -438,7 +479,7 @@ struct PhysicsServerCommandProcessorInternalData
|
||||
|
||||
if (m_firstFreeHandle<0)
|
||||
{
|
||||
int curCapacity = m_bodyHandles.size();
|
||||
//int curCapacity = m_bodyHandles.size();
|
||||
int additionalCapacity= m_bodyHandles.size();
|
||||
increaseHandleCapacity(additionalCapacity);
|
||||
|
||||
@@ -501,6 +542,9 @@ struct PhysicsServerCommandProcessorInternalData
|
||||
btAlignedObjectArray<std::string*> m_strings;
|
||||
|
||||
btAlignedObjectArray<btCollisionShape*> m_collisionShapes;
|
||||
|
||||
MyOverlapFilterCallback* m_broadphaseCollisionFilterCallback;
|
||||
btHashedOverlappingPairCache* m_pairCache;
|
||||
btBroadphaseInterface* m_broadphase;
|
||||
btCollisionDispatcher* m_dispatcher;
|
||||
btMultiBodyConstraintSolver* m_solver;
|
||||
@@ -541,14 +585,15 @@ struct PhysicsServerCommandProcessorInternalData
|
||||
TinyRendererVisualShapeConverter m_visualConverter;
|
||||
|
||||
PhysicsServerCommandProcessorInternalData()
|
||||
:m_hasGround(false),
|
||||
m_gripperRigidbodyFixed(0),
|
||||
:
|
||||
m_allowRealTimeSimulation(false),
|
||||
m_hasGround(false),
|
||||
m_gripperRigidbodyFixed(0),
|
||||
m_gripperMultiBody(0),
|
||||
m_kukaGripperFixed(0),
|
||||
m_kukaGripperMultiBody(0),
|
||||
m_kukaGripperRevolute1(0),
|
||||
m_kukaGripperRevolute2(0),
|
||||
m_allowRealTimeSimulation(false),
|
||||
m_huskyId(-1),
|
||||
m_KukaId(-1),
|
||||
m_sphereId(-1),
|
||||
@@ -558,6 +603,12 @@ struct PhysicsServerCommandProcessorInternalData
|
||||
m_physicsDeltaTime(1./240.),
|
||||
m_numSimulationSubSteps(0),
|
||||
m_userConstraintUIDGenerator(1),
|
||||
m_broadphaseCollisionFilterCallback(0),
|
||||
m_pairCache(0),
|
||||
m_broadphase(0),
|
||||
m_dispatcher(0),
|
||||
m_solver(0),
|
||||
m_collisionConfiguration(0),
|
||||
m_dynamicsWorld(0),
|
||||
m_remoteDebugDrawer(0),
|
||||
m_guiHelper(0),
|
||||
@@ -697,7 +748,6 @@ PhysicsServerCommandProcessor::~PhysicsServerCommandProcessor()
|
||||
}
|
||||
|
||||
|
||||
|
||||
void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
|
||||
{
|
||||
///collision configuration contains default setup for memory, collision setup
|
||||
@@ -710,6 +760,14 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
|
||||
///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
|
||||
m_data->m_dispatcher = new btCollisionDispatcher(m_data->m_collisionConfiguration);
|
||||
|
||||
|
||||
m_data->m_broadphaseCollisionFilterCallback = new MyOverlapFilterCallback();
|
||||
m_data->m_broadphaseCollisionFilterCallback->m_filterMode = FILTER_GROUPAMASKB_OR_GROUPBMASKA;
|
||||
|
||||
m_data->m_pairCache = new btHashedOverlappingPairCache();
|
||||
|
||||
m_data->m_pairCache->setOverlapFilterCallback(m_data->m_broadphaseCollisionFilterCallback);
|
||||
|
||||
m_data->m_broadphase = new btDbvtBroadphase();
|
||||
|
||||
m_data->m_solver = new btMultiBodyConstraintSolver;
|
||||
@@ -864,9 +922,16 @@ void PhysicsServerCommandProcessor::deleteDynamicsWorld()
|
||||
delete m_data->m_solver;
|
||||
m_data->m_solver=0;
|
||||
|
||||
|
||||
delete m_data->m_broadphase;
|
||||
m_data->m_broadphase=0;
|
||||
|
||||
delete m_data->m_pairCache;
|
||||
m_data->m_pairCache= 0;
|
||||
|
||||
delete m_data->m_broadphaseCollisionFilterCallback;
|
||||
m_data->m_broadphaseCollisionFilterCallback= 0;
|
||||
|
||||
delete m_data->m_dispatcher;
|
||||
m_data->m_dispatcher=0;
|
||||
|
||||
@@ -1182,7 +1247,7 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
|
||||
util->m_mb = mb;
|
||||
for (int i = 0; i < bufferSizeInBytes; i++)
|
||||
{
|
||||
bufferServerToClient[i] = 0xcc;
|
||||
bufferServerToClient[i] = 0;//0xcc;
|
||||
}
|
||||
util->m_memSerializer = new btDefaultSerializer(bufferSizeInBytes ,(unsigned char*)bufferServerToClient);
|
||||
//disable serialization of the collision objects (they are too big, and the client likely doesn't need them);
|
||||
@@ -1336,7 +1401,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
//m_data->m_testBlock1->m_numProcessedClientCommands++;
|
||||
|
||||
//no timestamp yet
|
||||
int timeStamp = 0;
|
||||
//int timeStamp = 0;
|
||||
|
||||
//catch uninitialized cases
|
||||
serverStatusOut.m_type = CMD_INVALID_STATUS;
|
||||
@@ -1621,7 +1686,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
|
||||
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_SHADOW) != 0)
|
||||
{
|
||||
m_data->m_visualConverter.setShadow(clientCmd.m_requestPixelDataArguments.m_hasShadow);
|
||||
m_data->m_visualConverter.setShadow((clientCmd.m_requestPixelDataArguments.m_hasShadow!=0));
|
||||
}
|
||||
|
||||
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_AMBIENT_COEFF) != 0)
|
||||
@@ -1844,7 +1909,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
b3Printf("Processed CMD_LOAD_SDF:%s", sdfArgs.m_sdfFileName);
|
||||
}
|
||||
bool useMultiBody=(clientCmd.m_updateFlags & URDF_ARGS_USE_MULTIBODY) ? sdfArgs.m_useMultiBody : true;
|
||||
bool useMultiBody=(clientCmd.m_updateFlags & URDF_ARGS_USE_MULTIBODY) ? (sdfArgs.m_useMultiBody!=0) : true;
|
||||
|
||||
int flags = CUF_USE_SDF; //CUF_USE_URDF_INERTIA
|
||||
bool completedOk = loadSdf(sdfArgs.m_sdfFileName,bufferServerToClient, bufferSizeInBytes, useMultiBody, flags);
|
||||
@@ -1893,8 +1958,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
initialOrn[2] = urdfArgs.m_initialOrientation[2];
|
||||
initialOrn[3] = urdfArgs.m_initialOrientation[3];
|
||||
}
|
||||
bool useMultiBody=(clientCmd.m_updateFlags & URDF_ARGS_USE_MULTIBODY) ? urdfArgs.m_useMultiBody : true;
|
||||
bool useFixedBase = (clientCmd.m_updateFlags & URDF_ARGS_USE_FIXED_BASE) ? urdfArgs.m_useFixedBase: false;
|
||||
bool useMultiBody=(clientCmd.m_updateFlags & URDF_ARGS_USE_MULTIBODY) ? (urdfArgs.m_useMultiBody!=0) : true;
|
||||
bool useFixedBase = (clientCmd.m_updateFlags & URDF_ARGS_USE_FIXED_BASE) ? (urdfArgs.m_useFixedBase!=0): false;
|
||||
int bodyUniqueId;
|
||||
//load the actual URDF and send a report: completed or failed
|
||||
bool completedOk = loadUrdf(urdfArgs.m_urdfFileName,
|
||||
@@ -2531,6 +2596,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = clientCmd.m_physSimParamArgs.m_numSolverIterations;
|
||||
}
|
||||
|
||||
if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_COLLISION_FILTER_MODE)
|
||||
{
|
||||
m_data->m_broadphaseCollisionFilterCallback->m_filterMode = clientCmd.m_physSimParamArgs.m_collisionFilterMode;
|
||||
}
|
||||
|
||||
if (clientCmd.m_updateFlags & SIM_PARAM_UPDATE_USE_SPLIT_IMPULSE)
|
||||
{
|
||||
m_data->m_dynamicsWorld->getSolverInfo().m_splitImpulse = clientCmd.m_physSimParamArgs.m_useSplitImpulse;
|
||||
@@ -2920,9 +2990,9 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
|
||||
serverCmd.m_type = CMD_REQUEST_AABB_OVERLAP_COMPLETED;
|
||||
|
||||
int m_startingOverlappingObjectIndex;
|
||||
int m_numOverlappingObjectsCopied;
|
||||
int m_numRemainingOverlappingObjects;
|
||||
//int m_startingOverlappingObjectIndex;
|
||||
//int m_numOverlappingObjectsCopied;
|
||||
//int m_numRemainingOverlappingObjects;
|
||||
serverCmd.m_sendOverlappingObjectsArgs.m_startingOverlappingObjectIndex = clientCmd.m_requestOverlappingObjectsArgs.m_startingOverlappingObjectIndex;
|
||||
serverCmd.m_sendOverlappingObjectsArgs.m_numOverlappingObjectsCopied = m_data->m_cachedOverlappingObjects.m_bodyUniqueIds.size();
|
||||
serverCmd.m_sendOverlappingObjectsArgs.m_numRemainingOverlappingObjects = remainingObjects - curNumObjects;
|
||||
@@ -3133,8 +3203,6 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
///ContactResultCallback is used to report contact points
|
||||
struct MyContactResultCallback : public btCollisionWorld::ContactResultCallback
|
||||
{
|
||||
//short int m_collisionFilterGroup;
|
||||
//short int m_collisionFilterMask;
|
||||
int m_bodyUniqueIdA;
|
||||
int m_bodyUniqueIdB;
|
||||
int m_linkIndexA;
|
||||
@@ -3596,6 +3664,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
btMatrix3x3 childFrameBasis(childFrameOrn);
|
||||
userConstraintPtr->m_mbConstraint->setFrameInB(childFrameBasis);
|
||||
}
|
||||
if (clientCmd.m_updateFlags & USER_CONSTRAINT_CHANGE_MAX_FORCE)
|
||||
{
|
||||
btScalar maxImp = clientCmd.m_userConstraintArguments.m_maxAppliedForce*m_data->m_physicsDeltaTime;
|
||||
userConstraintPtr->m_mbConstraint->setMaxAppliedImpulse(maxImp);
|
||||
}
|
||||
}
|
||||
if (userConstraintPtr->m_rbConstraint)
|
||||
{
|
||||
@@ -3789,8 +3862,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
//retrieve the visual shape information for a specific body
|
||||
|
||||
int totalNumVisualShapes = m_data->m_visualConverter.getNumVisualShapes(clientCmd.m_requestVisualShapeDataArguments.m_bodyUniqueId);
|
||||
int totalBytesPerVisualShape = sizeof (b3VisualShapeData);
|
||||
int visualShapeStorage = bufferSizeInBytes / totalBytesPerVisualShape - 1;
|
||||
//int totalBytesPerVisualShape = sizeof (b3VisualShapeData);
|
||||
//int visualShapeStorage = bufferSizeInBytes / totalBytesPerVisualShape - 1;
|
||||
b3VisualShapeData* visualShapeStoragePtr = (b3VisualShapeData*)bufferServerToClient;
|
||||
|
||||
int remain = totalNumVisualShapes - clientCmd.m_requestVisualShapeDataArguments.m_startingVisualShapeIndex;
|
||||
@@ -3940,7 +4013,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
{
|
||||
b3Printf("Processed CMD_LOAD_MJCF:%s", mjcfArgs.m_mjcfFileName);
|
||||
}
|
||||
bool useMultiBody=(clientCmd.m_updateFlags & URDF_ARGS_USE_MULTIBODY) ? mjcfArgs.m_useMultiBody : true;
|
||||
bool useMultiBody=(clientCmd.m_updateFlags & URDF_ARGS_USE_MULTIBODY) ? (mjcfArgs.m_useMultiBody!=0) : true;
|
||||
int flags = CUF_USE_MJCF;//CUF_USE_URDF_INERTIA
|
||||
bool completedOk = loadMjcf(mjcfArgs.m_mjcfFileName,bufferServerToClient, bufferSizeInBytes, useMultiBody, flags);
|
||||
if (completedOk)
|
||||
@@ -4084,7 +4157,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
return hasStatus;
|
||||
}
|
||||
|
||||
static int skip=1;
|
||||
//static int skip=1;
|
||||
|
||||
void PhysicsServerCommandProcessor::renderScene()
|
||||
{
|
||||
|
||||
@@ -56,6 +56,29 @@ const char* startFileNameVR = "0_VRDemoSettings.txt";
|
||||
|
||||
#include <vector>
|
||||
|
||||
static void loadCurrentSettingsVR(b3CommandLineArgs& args)
|
||||
{
|
||||
//int currentEntry = 0;
|
||||
FILE* f = fopen(startFileNameVR, "r");
|
||||
if (f)
|
||||
{
|
||||
char oneline[1024];
|
||||
char* argv[] = { 0,&oneline[0] };
|
||||
|
||||
while (fgets(oneline, 1024, f) != NULL)
|
||||
{
|
||||
char *pos;
|
||||
if ((pos = strchr(oneline, '\n')) != NULL)
|
||||
*pos = '\0';
|
||||
args.addArgs(2, argv);
|
||||
}
|
||||
fclose(f);
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
|
||||
#if B3_USE_MIDI
|
||||
//remember the settings (you don't want to re-tune again and again...)
|
||||
static void saveCurrentSettingsVR()
|
||||
{
|
||||
@@ -70,27 +93,6 @@ static void saveCurrentSettingsVR()
|
||||
}
|
||||
};
|
||||
|
||||
static void loadCurrentSettingsVR(b3CommandLineArgs& args)
|
||||
{
|
||||
int currentEntry = 0;
|
||||
FILE* f = fopen(startFileNameVR, "r");
|
||||
if (f)
|
||||
{
|
||||
char oneline[1024];
|
||||
char* argv[] = { 0,&oneline[0] };
|
||||
|
||||
while (fgets(oneline, 1024, f) != NULL)
|
||||
{
|
||||
char *pos;
|
||||
if ((pos = strchr(oneline, '\n')) != NULL)
|
||||
*pos = '\0';
|
||||
args.addArgs(2, argv);
|
||||
}
|
||||
fclose(f);
|
||||
}
|
||||
|
||||
};
|
||||
#if B3_USE_MIDI
|
||||
|
||||
|
||||
static float getParamf(float rangeMin, float rangeMax, int midiVal)
|
||||
@@ -280,10 +282,10 @@ float sleepTimeThreshold = 8./1000.;
|
||||
void MotionThreadFunc(void* userPtr,void* lsMemory)
|
||||
{
|
||||
printf("MotionThreadFunc thread started\n");
|
||||
MotionThreadLocalStorage* localStorage = (MotionThreadLocalStorage*) lsMemory;
|
||||
//MotionThreadLocalStorage* localStorage = (MotionThreadLocalStorage*) lsMemory;
|
||||
|
||||
MotionArgs* args = (MotionArgs*) userPtr;
|
||||
int workLeft = true;
|
||||
//int workLeft = true;
|
||||
b3Clock clock;
|
||||
clock.reset();
|
||||
bool init = true;
|
||||
@@ -494,7 +496,7 @@ struct UserDebugText
|
||||
|
||||
class MultiThreadedOpenGLGuiHelper : public GUIHelperInterface
|
||||
{
|
||||
CommonGraphicsApp* m_app;
|
||||
// CommonGraphicsApp* m_app;
|
||||
|
||||
b3CriticalSection* m_cs;
|
||||
b3CriticalSection* m_cs2;
|
||||
@@ -558,8 +560,9 @@ public:
|
||||
}
|
||||
|
||||
MultiThreadedOpenGLGuiHelper(CommonGraphicsApp* app, GUIHelperInterface* guiHelper)
|
||||
:m_app(app)
|
||||
,m_cs(0),
|
||||
:
|
||||
//m_app(app),
|
||||
m_cs(0),
|
||||
m_cs2(0),
|
||||
m_cs3(0),
|
||||
m_csGUI(0),
|
||||
@@ -816,7 +819,7 @@ public:
|
||||
m_tmpText.m_itemUniqueId = m_uidGenerator++;
|
||||
m_tmpText.m_lifeTime = lifeTime;
|
||||
m_tmpText.textSize = size;
|
||||
int len = strlen(txt);
|
||||
//int len = strlen(txt);
|
||||
strcpy(m_tmpText.m_text,txt);
|
||||
m_tmpText.m_textPositionXYZ[0] = positionXYZ[0];
|
||||
m_tmpText.m_textPositionXYZ[1] = positionXYZ[1];
|
||||
@@ -893,7 +896,7 @@ class PhysicsServerExample : public SharedMemoryCommon
|
||||
bool m_isConnected;
|
||||
btClock m_clock;
|
||||
bool m_replay;
|
||||
int m_options;
|
||||
// int m_options;
|
||||
|
||||
#ifdef BT_ENABLE_VR
|
||||
TinyVRGui* m_tinyVrGui;
|
||||
@@ -1123,8 +1126,8 @@ PhysicsServerExample::PhysicsServerExample(MultiThreadedOpenGLGuiHelper* helper,
|
||||
m_physicsServer(sharedMem),
|
||||
m_wantsShutdown(false),
|
||||
m_isConnected(false),
|
||||
m_replay(false),
|
||||
m_options(options)
|
||||
m_replay(false)
|
||||
//m_options(options)
|
||||
#ifdef BT_ENABLE_VR
|
||||
,m_tinyVrGui(0)
|
||||
#endif
|
||||
@@ -1201,7 +1204,7 @@ void PhysicsServerExample::initPhysics()
|
||||
int numMoving = 0;
|
||||
m_args[w].m_positions.resize(numMoving);
|
||||
m_args[w].m_physicsServerPtr = &m_physicsServer;
|
||||
int index = 0;
|
||||
//int index = 0;
|
||||
|
||||
m_threadSupport->runTask(B3_THREAD_SCHEDULE_TASK, (void*) &this->m_args[w], w);
|
||||
|
||||
@@ -1365,7 +1368,8 @@ void PhysicsServerExample::stepSimulation(float deltaTime)
|
||||
m_multiThreadedHelper->m_childGuiHelper->removeAllGraphicsInstances();
|
||||
if (m_multiThreadedHelper->m_childGuiHelper->getRenderInterface())
|
||||
{
|
||||
int numRenderInstances = m_multiThreadedHelper->m_childGuiHelper->getRenderInterface()->getTotalNumInstances();
|
||||
int numRenderInstances;
|
||||
numRenderInstances = m_multiThreadedHelper->m_childGuiHelper->getRenderInterface()->getTotalNumInstances();
|
||||
b3Assert(numRenderInstances==0);
|
||||
}
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
@@ -1376,17 +1380,17 @@ void PhysicsServerExample::stepSimulation(float deltaTime)
|
||||
case eGUIHelperCopyCameraImageData:
|
||||
{
|
||||
m_multiThreadedHelper->m_childGuiHelper->copyCameraImageData(m_multiThreadedHelper->m_viewMatrix,
|
||||
m_multiThreadedHelper->m_projectionMatrix,
|
||||
m_multiThreadedHelper->m_pixelsRGBA,
|
||||
m_multiThreadedHelper->m_rgbaBufferSizeInPixels,
|
||||
m_multiThreadedHelper->m_depthBuffer,
|
||||
m_multiThreadedHelper->m_depthBufferSizeInPixels,
|
||||
m_multiThreadedHelper->m_segmentationMaskBuffer,
|
||||
m_multiThreadedHelper->m_segmentationMaskBufferSizeInPixels,
|
||||
m_multiThreadedHelper->m_startPixelIndex,
|
||||
m_multiThreadedHelper->m_destinationWidth,
|
||||
m_multiThreadedHelper->m_destinationHeight,
|
||||
m_multiThreadedHelper->m_numPixelsCopied);
|
||||
m_multiThreadedHelper->m_projectionMatrix,
|
||||
m_multiThreadedHelper->m_pixelsRGBA,
|
||||
m_multiThreadedHelper->m_rgbaBufferSizeInPixels,
|
||||
m_multiThreadedHelper->m_depthBuffer,
|
||||
m_multiThreadedHelper->m_depthBufferSizeInPixels,
|
||||
m_multiThreadedHelper->m_segmentationMaskBuffer,
|
||||
m_multiThreadedHelper->m_segmentationMaskBufferSizeInPixels,
|
||||
m_multiThreadedHelper->m_startPixelIndex,
|
||||
m_multiThreadedHelper->m_destinationWidth,
|
||||
m_multiThreadedHelper->m_destinationHeight,
|
||||
m_multiThreadedHelper->m_numPixelsCopied);
|
||||
m_multiThreadedHelper->mainThreadRelease();
|
||||
break;
|
||||
}
|
||||
@@ -1507,8 +1511,8 @@ extern btTransform gVRTrackingObjectTr;
|
||||
|
||||
void PhysicsServerExample::drawUserDebugLines()
|
||||
{
|
||||
static char line0[1024];
|
||||
static char line1[1024];
|
||||
//static char line0[1024];
|
||||
//static char line1[1024];
|
||||
|
||||
//draw all user-debug-lines
|
||||
|
||||
@@ -1634,15 +1638,16 @@ void PhysicsServerExample::renderScene()
|
||||
{
|
||||
|
||||
static int frameCount=0;
|
||||
static btScalar prevTime = m_clock.getTimeSeconds();
|
||||
//static btScalar prevTime = m_clock.getTimeSeconds();
|
||||
frameCount++;
|
||||
|
||||
|
||||
#if 0
|
||||
|
||||
static btScalar worseFps = 1000000;
|
||||
int numFrames = 200;
|
||||
static int count = 0;
|
||||
count++;
|
||||
|
||||
#if 0
|
||||
if (0 == (count & 1))
|
||||
{
|
||||
btScalar curTime = m_clock.getTimeSeconds();
|
||||
@@ -1973,7 +1978,7 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt
|
||||
|
||||
if (controllerId == gGraspingController && (button == 33))
|
||||
{
|
||||
gVRGripperClosed =state;
|
||||
gVRGripperClosed =(state!=0);
|
||||
}
|
||||
else
|
||||
{
|
||||
|
||||
@@ -128,18 +128,16 @@ bool PhysicsServerSharedMemory::connectSharedMemory( struct GUIHelperInterface*
|
||||
|
||||
bool allowCreation = true;
|
||||
bool allConnected = false;
|
||||
|
||||
int numConnected = 0;
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
int counter = 0;
|
||||
for (int block=0;block<MAX_SHARED_MEMORY_BLOCKS;block++)
|
||||
{
|
||||
if (m_data->m_areConnected[block])
|
||||
{
|
||||
allConnected = true;
|
||||
numConnected++;
|
||||
b3Warning("connectSharedMemory, while already connected");
|
||||
continue;
|
||||
}
|
||||
@@ -163,6 +161,7 @@ bool PhysicsServerSharedMemory::connectSharedMemory( struct GUIHelperInterface*
|
||||
b3Printf("Created and initialized shared memory block\n");
|
||||
}
|
||||
m_data->m_areConnected[block] = true;
|
||||
numConnected++;
|
||||
} else
|
||||
{
|
||||
m_data->m_sharedMemory->releaseSharedMemory(m_data->m_sharedMemoryKey+block, SHARED_MEMORY_SIZE);
|
||||
@@ -181,6 +180,8 @@ bool PhysicsServerSharedMemory::connectSharedMemory( struct GUIHelperInterface*
|
||||
}
|
||||
}
|
||||
|
||||
allConnected = (numConnected==MAX_SHARED_MEMORY_BLOCKS);
|
||||
|
||||
return allConnected;
|
||||
}
|
||||
|
||||
|
||||
@@ -125,7 +125,6 @@ bool SharedMemoryCommandProcessor::processCommand(const struct SharedMemoryComma
|
||||
|
||||
bool SharedMemoryCommandProcessor::receiveStatus(struct SharedMemoryStatus& serverStatusOut, char* bufferServerToClient, int bufferSizeInBytes)
|
||||
{
|
||||
SharedMemoryStatus* stat = 0;
|
||||
|
||||
m_data->m_lastServerStatus.m_dataStream = 0;
|
||||
m_data->m_lastServerStatus.m_numDataStreamBytes = 0;
|
||||
|
||||
@@ -313,6 +313,7 @@ enum EnumSimParamUpdateFlags
|
||||
SIM_PARAM_UPDATE_INTERNAL_SIMULATION_FLAGS=64,
|
||||
SIM_PARAM_UPDATE_USE_SPLIT_IMPULSE=128,
|
||||
SIM_PARAM_UPDATE_SPLIT_IMPULSE_PENETRATION_THRESHOLD = 256,
|
||||
SIM_PARAM_UPDATE_COLLISION_FILTER_MODE=512
|
||||
};
|
||||
|
||||
enum EnumLoadBunnyUpdateFlags
|
||||
@@ -341,6 +342,7 @@ struct SendPhysicsSimulationParameters
|
||||
double m_splitImpulsePenetrationThreshold;
|
||||
int m_internalSimFlags;
|
||||
double m_defaultContactERP;
|
||||
int m_collisionFilterMode;
|
||||
};
|
||||
|
||||
struct LoadBunnyArgs
|
||||
@@ -538,6 +540,8 @@ enum EnumUserConstraintFlags
|
||||
USER_CONSTRAINT_CHANGE_CONSTRAINT=4,
|
||||
USER_CONSTRAINT_CHANGE_PIVOT_IN_B=8,
|
||||
USER_CONSTRAINT_CHANGE_FRAME_ORN_IN_B=16,
|
||||
USER_CONSTRAINT_CHANGE_MAX_FORCE=32,
|
||||
|
||||
};
|
||||
|
||||
struct UserConstraintArgs
|
||||
@@ -550,6 +554,7 @@ struct UserConstraintArgs
|
||||
double m_childFrame[7];
|
||||
double m_jointAxis[3];
|
||||
int m_jointType;
|
||||
double m_maxAppliedForce;
|
||||
int m_userConstraintUniqueId;
|
||||
};
|
||||
|
||||
|
||||
@@ -546,7 +546,7 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(int linkIndex, const
|
||||
btAlignedObjectArray<GLInstanceVertex> vertices;
|
||||
btAlignedObjectArray<int> indices;
|
||||
btTransform startTrans; startTrans.setIdentity();
|
||||
int graphicsIndex = -1;
|
||||
//int graphicsIndex = -1;
|
||||
|
||||
const UrdfVisual& vis = link->m_visualArray[v];
|
||||
btTransform childTrans = vis.m_linkLocalFrame;
|
||||
@@ -660,7 +660,7 @@ int TinyRendererVisualShapeConverter::getVisualShapesData(int bodyUniqueId, int
|
||||
break;
|
||||
}
|
||||
}
|
||||
int count = 0;
|
||||
//int count = 0;
|
||||
|
||||
if (start >= 0)
|
||||
{
|
||||
|
||||
@@ -81,6 +81,8 @@ int main(int argc, char* argv[])
|
||||
|
||||
|
||||
example->initPhysics();
|
||||
|
||||
|
||||
while (example->isConnected() && !(example->wantsTermination() || interrupted))
|
||||
{
|
||||
example->stepSimulation(1.f/60.f);
|
||||
|
||||
@@ -232,15 +232,15 @@ extern float eye[3];
|
||||
extern int glutScreenWidth;
|
||||
extern int glutScreenHeight;
|
||||
|
||||
static bool sDemoMode = false;
|
||||
//static bool sDemoMode = false;
|
||||
|
||||
const int maxProxies = 32766;
|
||||
const int maxOverlap = 65535;
|
||||
//const int maxOverlap = 65535;
|
||||
|
||||
static btVector3* gGroundVertices=0;
|
||||
static int* gGroundIndices=0;
|
||||
static btBvhTriangleMeshShape* trimeshShape =0;
|
||||
static btRigidBody* staticBody = 0;
|
||||
//static btBvhTriangleMeshShape* trimeshShape =0;
|
||||
//static btRigidBody* staticBody = 0;
|
||||
static float waveheight = 5.f;
|
||||
|
||||
const float TRIANGLE_SIZE=8.f;
|
||||
@@ -249,12 +249,12 @@ int current_demo=20;
|
||||
|
||||
|
||||
#ifdef _DEBUG
|
||||
const int gNumObjects = 1;
|
||||
//const int gNumObjects = 1;
|
||||
#else
|
||||
const int gNumObjects = 1;//try this in release mode: 3000. never go above 16384, unless you increate maxNumObjects value in DemoApplication.cp
|
||||
//const int gNumObjects = 1;//try this in release mode: 3000. never go above 16384, unless you increate maxNumObjects value in DemoApplication.cp
|
||||
#endif
|
||||
|
||||
const int maxNumObjects = 32760;
|
||||
//const int maxNumObjects = 32760;
|
||||
|
||||
#define CUBE_HALF_EXTENTS 1.5
|
||||
#define EXTRA_HEIGHT -10.f
|
||||
@@ -1452,7 +1452,8 @@ static void Init_ClusterRobot(SoftDemo* pdemo)
|
||||
ls.position=psb2->clusterCom(0);psb2->appendLinearJoint(ls,prb);
|
||||
|
||||
btBoxShape* pbox=new btBoxShape(btVector3(20,1,40));
|
||||
btRigidBody* pgrn=pdemo->createRigidBody(0,btTransform(btQuaternion(0,-SIMD_HALF_PI/2,0),btVector3(0,0,0)),pbox);
|
||||
btRigidBody* pgrn;
|
||||
pgrn =pdemo->createRigidBody(0,btTransform(btQuaternion(0,-SIMD_HALF_PI/2,0),btVector3(0,0,0)),pbox);
|
||||
|
||||
pdemo->m_autocam=true;
|
||||
|
||||
|
||||
@@ -22,6 +22,7 @@
|
||||
int gSharedMemoryKey = -1;
|
||||
int gDebugDrawFlags = 0;
|
||||
bool gDisplayDistortion = false;
|
||||
bool gDisableDesktopGL = false;
|
||||
|
||||
//how can you try typing on a keyboard, without seeing it?
|
||||
//it is pretty funny, to see the desktop in VR!
|
||||
@@ -834,23 +835,26 @@ void CMainApplication::RenderFrame()
|
||||
}
|
||||
RenderStereoTargets();
|
||||
|
||||
if (gDisplayDistortion)
|
||||
if (!gDisableDesktopGL)
|
||||
{
|
||||
B3_PROFILE("RenderDistortion");
|
||||
RenderDistortion();
|
||||
} else
|
||||
{
|
||||
glBindFramebuffer( GL_FRAMEBUFFER, 0 );
|
||||
glDisable( GL_MULTISAMPLE );
|
||||
glBindFramebuffer(GL_READ_FRAMEBUFFER, rightEyeDesc.m_nRenderFramebufferId );
|
||||
glBindFramebuffer(GL_DRAW_FRAMEBUFFER, 0);
|
||||
if (gDisplayDistortion)
|
||||
{
|
||||
B3_PROFILE("RenderDistortion");
|
||||
RenderDistortion();
|
||||
} else
|
||||
{
|
||||
glBindFramebuffer( GL_FRAMEBUFFER, 0 );
|
||||
glDisable( GL_MULTISAMPLE );
|
||||
glBindFramebuffer(GL_READ_FRAMEBUFFER, rightEyeDesc.m_nRenderFramebufferId );
|
||||
glBindFramebuffer(GL_DRAW_FRAMEBUFFER, 0);
|
||||
|
||||
glBlitFramebuffer( 0, 0, m_nRenderWidth, m_nRenderHeight, 0, 0, m_nRenderWidth, m_nRenderHeight,
|
||||
GL_COLOR_BUFFER_BIT,
|
||||
GL_LINEAR );
|
||||
glBlitFramebuffer( 0, 0, m_nRenderWidth, m_nRenderHeight, 0, 0, m_nRenderWidth, m_nRenderHeight,
|
||||
GL_COLOR_BUFFER_BIT,
|
||||
GL_LINEAR );
|
||||
|
||||
glBindFramebuffer(GL_READ_FRAMEBUFFER, 0);
|
||||
glBindFramebuffer(GL_DRAW_FRAMEBUFFER, 0 );
|
||||
glBindFramebuffer(GL_READ_FRAMEBUFFER, 0);
|
||||
glBindFramebuffer(GL_DRAW_FRAMEBUFFER, 0 );
|
||||
}
|
||||
}
|
||||
|
||||
vr::Texture_t leftEyeTexture = {(void*)leftEyeDesc.m_nResolveTextureId, vr::API_OpenGL, vr::ColorSpace_Gamma };
|
||||
@@ -873,7 +877,10 @@ void CMainApplication::RenderFrame()
|
||||
// SwapWindow
|
||||
{
|
||||
B3_PROFILE("m_app->swapBuffer");
|
||||
m_app->swapBuffer();
|
||||
if (!gDisableDesktopGL)
|
||||
{
|
||||
m_app->swapBuffer();
|
||||
}
|
||||
//SDL_GL_SwapWindow( m_pWindow );
|
||||
|
||||
}
|
||||
@@ -2216,6 +2223,11 @@ void CGLRenderModel::Draw()
|
||||
int main(int argc, char *argv[])
|
||||
{
|
||||
|
||||
b3CommandLineArgs args(argc,argv);
|
||||
if (args.CheckCmdLineFlag("disable_desktop_gl"))
|
||||
{
|
||||
gDisableDesktopGL = true;
|
||||
}
|
||||
|
||||
#ifdef BT_USE_CUSTOM_PROFILER
|
||||
b3SetCustomEnterProfileZoneFunc(dcEnter);
|
||||
|
||||
@@ -486,7 +486,7 @@ void MatrixRmn::ComputeSVD( MatrixRmn& U, VectorRn& w, MatrixRmn& V ) const
|
||||
&& U.NumRows==U.NumCols && V.NumRows==V.NumCols
|
||||
&& w.GetLength()==Min(NumRows,NumCols) );
|
||||
|
||||
double temp=0.0;
|
||||
// double temp=0.0;
|
||||
VectorRn& superDiag = VectorRn::GetWorkVector( w.GetLength()-1 ); // Some extra work space. Will get passed around.
|
||||
|
||||
// Choose larger of U, V to hold intermediate results
|
||||
|
||||
@@ -23,7 +23,7 @@ subject to the following restrictions:
|
||||
#include <math.h>
|
||||
#include "LinearR3.h"
|
||||
|
||||
|
||||
#if 0
|
||||
|
||||
/****************************************************************
|
||||
Axes
|
||||
@@ -65,7 +65,7 @@ static float zy[] = {
|
||||
static int zorder[] = {
|
||||
1, 2, 3, 4, -5, 6
|
||||
};
|
||||
|
||||
#endif
|
||||
#define LENFRAC 0.10
|
||||
#define BASEFRAC 1.10
|
||||
|
||||
@@ -88,9 +88,9 @@ static int zorder[] = {
|
||||
|
||||
/* x, y, z, axes: */
|
||||
|
||||
static float axx[3] = { 1., 0., 0. };
|
||||
static float ayy[3] = { 0., 1., 0. };
|
||||
static float azz[3] = { 0., 0., 1. };
|
||||
//static float axx[3] = { 1., 0., 0. };
|
||||
//static float ayy[3] = { 0., 1., 0. };
|
||||
//static float azz[3] = { 0., 0., 1. };
|
||||
|
||||
|
||||
|
||||
|
||||
@@ -45,7 +45,7 @@ public:
|
||||
|
||||
double GetTheta() const { return theta; }
|
||||
double AddToTheta( double& delta ) {
|
||||
double orgTheta = theta;
|
||||
//double orgTheta = theta;
|
||||
theta += delta;
|
||||
#if 0
|
||||
if (theta < minTheta)
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
@@ -31,11 +31,11 @@ struct DepthShader : public IShader {
|
||||
|
||||
DepthShader(Model* model, Matrix& lightModelView, Matrix& projectionMat, Matrix& modelMat, Vec3f localScaling, float lightDistance)
|
||||
:m_model(model),
|
||||
m_lightModelView(lightModelView),
|
||||
m_projectionMat(projectionMat),
|
||||
m_modelMat(modelMat),
|
||||
m_localScaling(localScaling),
|
||||
m_lightDistance(lightDistance)
|
||||
m_projectionMat(projectionMat),
|
||||
m_localScaling(localScaling),
|
||||
m_lightModelView(lightModelView),
|
||||
m_lightDistance(lightDistance)
|
||||
{
|
||||
m_invModelMat = m_modelMat.invert_transpose();
|
||||
}
|
||||
@@ -92,19 +92,21 @@ struct Shader : public IShader {
|
||||
:m_model(model),
|
||||
m_light_dir_local(light_dir_local),
|
||||
m_light_color(light_color),
|
||||
m_ambient_coefficient(ambient_coefficient),
|
||||
m_diffuse_coefficient(diffuse_coefficient),
|
||||
m_specular_coefficient(specular_coefficient),
|
||||
m_modelView1(modelView),
|
||||
m_lightModelView(lightModelView),
|
||||
m_projectionMat(projectionMat),
|
||||
m_modelMat(modelMat),
|
||||
m_viewportMat(viewportMat),
|
||||
m_localScaling(localScaling),
|
||||
m_colorRGBA(colorRGBA),
|
||||
m_width(width),
|
||||
m_height(height),
|
||||
m_shadowBuffer(shadowBuffer)
|
||||
m_modelMat(modelMat),
|
||||
m_modelView1(modelView),
|
||||
m_projectionMat(projectionMat),
|
||||
m_localScaling(localScaling),
|
||||
m_lightModelView(lightModelView),
|
||||
m_colorRGBA(colorRGBA),
|
||||
m_viewportMat(viewportMat),
|
||||
m_ambient_coefficient(ambient_coefficient),
|
||||
m_diffuse_coefficient(diffuse_coefficient),
|
||||
m_specular_coefficient(specular_coefficient),
|
||||
|
||||
m_shadowBuffer(shadowBuffer),
|
||||
m_width(width),
|
||||
m_height(height)
|
||||
|
||||
{
|
||||
m_invModelMat = m_modelMat.invert_transpose();
|
||||
}
|
||||
@@ -157,11 +159,12 @@ struct Shader : public IShader {
|
||||
};
|
||||
|
||||
TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray<float>&depthBuffer,b3AlignedObjectArray<float>* shadowBuffer)
|
||||
:m_rgbColorBuffer(rgbColorBuffer),
|
||||
:
|
||||
m_model(0),
|
||||
m_rgbColorBuffer(rgbColorBuffer),
|
||||
m_depthBuffer(depthBuffer),
|
||||
m_shadowBuffer(shadowBuffer),
|
||||
m_segmentationMaskBufferPtr(0),
|
||||
m_model(0),
|
||||
m_userData(0),
|
||||
m_userIndex(-1),
|
||||
m_objectIndex(-1)
|
||||
@@ -180,11 +183,11 @@ m_objectIndex(-1)
|
||||
}
|
||||
|
||||
TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray<float>&depthBuffer, b3AlignedObjectArray<float>* shadowBuffer, b3AlignedObjectArray<int>* segmentationMaskBuffer, int objectIndex)
|
||||
:m_rgbColorBuffer(rgbColorBuffer),
|
||||
:m_model(0),
|
||||
m_rgbColorBuffer(rgbColorBuffer),
|
||||
m_depthBuffer(depthBuffer),
|
||||
m_shadowBuffer(shadowBuffer),
|
||||
m_segmentationMaskBufferPtr(segmentationMaskBuffer),
|
||||
m_model(0),
|
||||
m_userData(0),
|
||||
m_userIndex(-1),
|
||||
m_objectIndex(objectIndex)
|
||||
@@ -203,10 +206,10 @@ m_objectIndex(objectIndex)
|
||||
}
|
||||
|
||||
TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray<float>&depthBuffer)
|
||||
:m_rgbColorBuffer(rgbColorBuffer),
|
||||
:m_model(0),
|
||||
m_rgbColorBuffer(rgbColorBuffer),
|
||||
m_depthBuffer(depthBuffer),
|
||||
m_segmentationMaskBufferPtr(0),
|
||||
m_model(0),
|
||||
m_userData(0),
|
||||
m_userIndex(-1),
|
||||
m_objectIndex(-1)
|
||||
@@ -225,10 +228,10 @@ m_objectIndex(-1)
|
||||
}
|
||||
|
||||
TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray<float>&depthBuffer, b3AlignedObjectArray<int>* segmentationMaskBuffer, int objectIndex)
|
||||
:m_rgbColorBuffer(rgbColorBuffer),
|
||||
:m_model(0),
|
||||
m_rgbColorBuffer(rgbColorBuffer),
|
||||
m_depthBuffer(depthBuffer),
|
||||
m_segmentationMaskBufferPtr(segmentationMaskBuffer),
|
||||
m_model(0),
|
||||
m_userData(0),
|
||||
m_userIndex(-1),
|
||||
m_objectIndex(objectIndex)
|
||||
|
||||
@@ -457,8 +457,8 @@ void Dof6ConstraintTutorial::animate()
|
||||
/////// servo motor: flip its target periodically
|
||||
#ifdef USE_6DOF2
|
||||
static float servoNextFrame = -1;
|
||||
btScalar pos = m_data->m_ServoMotorConstraint->getRotationalLimitMotor(2)->m_currentPosition;
|
||||
btScalar target = m_data->m_ServoMotorConstraint->getRotationalLimitMotor(2)->m_servoTarget;
|
||||
//btScalar pos = m_data->m_ServoMotorConstraint->getRotationalLimitMotor(2)->m_currentPosition;
|
||||
//btScalar target = m_data->m_ServoMotorConstraint->getRotationalLimitMotor(2)->m_servoTarget;
|
||||
if(servoNextFrame < 0)
|
||||
{
|
||||
m_data->m_ServoMotorConstraint->getRotationalLimitMotor(2)->m_servoTarget *= -1;
|
||||
@@ -510,7 +510,7 @@ void Dof6ConstraintTutorial::stepSimulation(float deltaTime)
|
||||
//animate();
|
||||
|
||||
|
||||
float time = m_data->m_timeSeriesCanvas->getCurrentTime();
|
||||
//float time = m_data->m_timeSeriesCanvas->getCurrentTime();
|
||||
|
||||
float prevPos = m_data->m_TranslateSpringBody->getWorldTransform().getOrigin().x();
|
||||
m_dynamicsWorld->stepSimulation(deltaTime);
|
||||
|
||||
@@ -292,11 +292,11 @@ public:
|
||||
:m_app(guiHelper->getAppInterface()),
|
||||
m_guiHelper(guiHelper),
|
||||
m_tutorialIndex(tutorialIndex),
|
||||
m_stage(0),
|
||||
m_counter(0),
|
||||
m_timeSeriesCanvas0(0),
|
||||
m_timeSeriesCanvas1(0)
|
||||
{
|
||||
m_timeSeriesCanvas1(0),
|
||||
m_stage(0),
|
||||
m_counter(0)
|
||||
{
|
||||
int numBodies = 1;
|
||||
|
||||
m_app->setUpAxis(1);
|
||||
|
||||
@@ -158,9 +158,9 @@ static btScalar loadMass = 350.f;//
|
||||
#endif
|
||||
|
||||
|
||||
static int rightIndex = 0;
|
||||
static int upIndex = 1;
|
||||
static int forwardIndex = 2;
|
||||
//static int rightIndex = 0;
|
||||
//static int upIndex = 1;
|
||||
//static int forwardIndex = 2;
|
||||
static btVector3 wheelDirectionCS0(0,-1,0);
|
||||
static btVector3 wheelAxleCS(-1,0,0);
|
||||
|
||||
@@ -173,8 +173,8 @@ static bool useMCLPSolver = false;//true;
|
||||
#include "Hinge2Vehicle.h"
|
||||
|
||||
|
||||
static const int maxProxies = 32766;
|
||||
static const int maxOverlap = 65535;
|
||||
//static const int maxProxies = 32766;
|
||||
//static const int maxOverlap = 65535;
|
||||
|
||||
static float gEngineForce = 0.f;
|
||||
|
||||
@@ -182,21 +182,21 @@ static float defaultBreakingForce = 10.f;
|
||||
static float gBreakingForce = 100.f;
|
||||
|
||||
static float maxEngineForce = 1000.f;//this should be engine/velocity dependent
|
||||
static float maxBreakingForce = 100.f;
|
||||
//static float maxBreakingForce = 100.f;
|
||||
|
||||
static float gVehicleSteering = 0.f;
|
||||
static float steeringIncrement = 0.04f;
|
||||
static float steeringClamp = 0.3f;
|
||||
static float wheelRadius = 0.5f;
|
||||
static float wheelWidth = 0.4f;
|
||||
static float wheelFriction = 1000;//BT_LARGE_FLOAT;
|
||||
static float suspensionStiffness = 20.f;
|
||||
static float suspensionDamping = 2.3f;
|
||||
static float suspensionCompression = 4.4f;
|
||||
static float rollInfluence = 0.1f;//1.0f;
|
||||
//static float wheelFriction = 1000;//BT_LARGE_FLOAT;
|
||||
//static float suspensionStiffness = 20.f;
|
||||
//static float suspensionDamping = 2.3f;
|
||||
//static float suspensionCompression = 4.4f;
|
||||
//static float rollInfluence = 0.1f;//1.0f;
|
||||
|
||||
|
||||
static btScalar suspensionRestLength(0.6);
|
||||
//static btScalar suspensionRestLength(0.6);
|
||||
|
||||
#define CUBE_HALF_EXTENTS 1
|
||||
|
||||
@@ -209,8 +209,8 @@ static btScalar suspensionRestLength(0.6);
|
||||
|
||||
Hinge2Vehicle::Hinge2Vehicle(struct GUIHelperInterface* helper)
|
||||
:CommonRigidBodyBase(helper),
|
||||
m_guiHelper(helper),
|
||||
m_carChassis(0),
|
||||
m_guiHelper(helper),
|
||||
m_liftBody(0),
|
||||
m_forkBody(0),
|
||||
m_loadBody(0),
|
||||
@@ -378,10 +378,10 @@ tr.setOrigin(btVector3(0,-3,0));
|
||||
m_wheelShape = new btCylinderShapeX(btVector3(wheelWidth,wheelRadius,wheelRadius));
|
||||
|
||||
|
||||
const float position[4]={0,10,10,0};
|
||||
const float quaternion[4]={0,0,0,1};
|
||||
const float color[4]={0,1,0,1};
|
||||
const float scaling[4] = {1,1,1,1};
|
||||
//const float position[4]={0,10,10,0};
|
||||
//const float quaternion[4]={0,0,0,1};
|
||||
//const float color[4]={0,1,0,1};
|
||||
//const float scaling[4] = {1,1,1,1};
|
||||
|
||||
btVector3 wheelPos[4] = {
|
||||
btVector3(btScalar(-1.), btScalar(-0.25), btScalar(1.25)),
|
||||
|
||||
@@ -354,7 +354,6 @@ static PyObject* pybullet_disconnectPhysicsServer(PyObject* self,
|
||||
}
|
||||
|
||||
static PyObject* pybullet_saveWorld(PyObject* self, PyObject* args,PyObject *keywds) {
|
||||
int size = PySequence_Size(args);
|
||||
const char* worldFileName = "";
|
||||
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
@@ -398,7 +397,6 @@ static PyObject* pybullet_saveWorld(PyObject* self, PyObject* args,PyObject *key
|
||||
#define MAX_SDF_BODIES 512
|
||||
static PyObject* pybullet_loadBullet(PyObject* self, PyObject* args,PyObject *keywds)
|
||||
{
|
||||
int size = PySequence_Size(args);
|
||||
const char* bulletFileName = "";
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
@@ -452,7 +450,6 @@ static PyObject* pybullet_loadBullet(PyObject* self, PyObject* args,PyObject *ke
|
||||
|
||||
static PyObject* pybullet_saveBullet(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
int size = PySequence_Size(args);
|
||||
const char* bulletFileName = "";
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
@@ -489,7 +486,6 @@ static PyObject* pybullet_saveBullet(PyObject* self, PyObject* args, PyObject* k
|
||||
|
||||
static PyObject* pybullet_loadMJCF(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
int size = PySequence_Size(args);
|
||||
const char* mjcfFileName = "";
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
@@ -546,12 +542,15 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
|
||||
int useSplitImpulse = -1;
|
||||
double splitImpulsePenetrationThreshold = -1;
|
||||
int numSubSteps = -1;
|
||||
int collisionFilterMode = -1;
|
||||
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
|
||||
int physicsClientId = 0;
|
||||
static char *kwlist[] = { "fixedTimeStep", "numSolverIterations","useSplitImpulse","splitImpulsePenetrationThreshold", "numSubSteps","physicsClientId", NULL };
|
||||
static char *kwlist[] = { "fixedTimeStep", "numSolverIterations","useSplitImpulse","splitImpulsePenetrationThreshold", "numSubSteps","collisionFilterMode", "physicsClientId", NULL };
|
||||
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidii", kwlist,&fixedTimeStep,&numSolverIterations,&useSplitImpulse,&splitImpulsePenetrationThreshold,&numSubSteps,&physicsClientId))
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "|diidiii", kwlist,&fixedTimeStep,&numSolverIterations,&useSplitImpulse,&splitImpulsePenetrationThreshold,&numSubSteps,
|
||||
&collisionFilterMode, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -571,6 +570,10 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
|
||||
{
|
||||
b3PhysicsParamSetNumSolverIterations(command, numSolverIterations);
|
||||
}
|
||||
if (collisionFilterMode>=0)
|
||||
{
|
||||
b3PhysicsParamSetCollisionFilterMode(command, collisionFilterMode);
|
||||
}
|
||||
if (numSubSteps >= 0)
|
||||
{
|
||||
b3PhysicsParamSetNumSubSteps(command, numSubSteps);
|
||||
@@ -614,7 +617,6 @@ static PyObject* pybullet_setPhysicsEngineParameter(PyObject* self, PyObject* ar
|
||||
// loadURDF(pos_x, pos_y, pos_z, orn_x, orn_y, orn_z, orn_w)
|
||||
static PyObject* pybullet_loadURDF(PyObject* self, PyObject* args, PyObject *keywds)
|
||||
{
|
||||
int size = PySequence_Size(args);
|
||||
int physicsClientId = 0;
|
||||
|
||||
static char *kwlist[] = { "fileName", "basePosition", "baseOrientation", "useMaximalCoordinates","useFixedBase","physicsClientId", NULL };
|
||||
@@ -753,7 +755,6 @@ b3PhysicsClientHandle sm=0;
|
||||
|
||||
static PyObject* pybullet_loadSDF(PyObject* self, PyObject* args, PyObject *keywds) {
|
||||
const char* sdfFileName = "";
|
||||
int size = PySequence_Size(args);
|
||||
int numBodies = 0;
|
||||
int i;
|
||||
int bodyIndicesOut[MAX_SDF_BODIES];
|
||||
@@ -1577,8 +1578,7 @@ static PyObject* pybullet_getBodyInfo(PyObject* self, PyObject* args, PyObject*
|
||||
|
||||
{
|
||||
int bodyUniqueId= -1;
|
||||
int numJoints = 0;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
|
||||
int physicsClientId = 0;
|
||||
static char *kwlist[] = { "bodyUniqueId", "physicsClientId", NULL };
|
||||
@@ -2128,15 +2128,13 @@ b3PhysicsClientHandle sm = 0;
|
||||
|
||||
static PyObject* pybullet_addUserDebugText(PyObject* self, PyObject* args, PyObject *keywds)
|
||||
{
|
||||
int size = PySequence_Size(args);
|
||||
|
||||
b3SharedMemoryCommandHandle commandHandle;
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
int res = 0;
|
||||
|
||||
PyObject* pyResultList = 0;
|
||||
char* text;
|
||||
char* text;
|
||||
double posXYZ[3];
|
||||
double colorRGB[3]={1,1,1};
|
||||
|
||||
@@ -2198,15 +2196,13 @@ static PyObject* pybullet_addUserDebugText(PyObject* self, PyObject* args, PyObj
|
||||
|
||||
static PyObject* pybullet_addUserDebugLine(PyObject* self, PyObject* args, PyObject *keywds)
|
||||
{
|
||||
int size = PySequence_Size(args);
|
||||
|
||||
b3SharedMemoryCommandHandle commandHandle;
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
int res = 0;
|
||||
|
||||
PyObject* pyResultList = 0;
|
||||
|
||||
|
||||
double fromXYZ[3];
|
||||
double toXYZ[3];
|
||||
double colorRGB[3]={1,1,1};
|
||||
@@ -2704,7 +2700,6 @@ static PyObject* pybullet_getVisualShapeData(PyObject* self, PyObject* args, PyO
|
||||
PyTuple_SetItem(visualShapeObList, 6, vec);
|
||||
}
|
||||
|
||||
visualShapeInfo.m_visualShapeData[0].m_rgbaColor[0];
|
||||
|
||||
PyTuple_SetItem(pyResultList, i, visualShapeObList);
|
||||
}
|
||||
@@ -2767,7 +2762,6 @@ static PyObject* pybullet_resetVisualShapeData(PyObject* self, PyObject* args,Py
|
||||
|
||||
static PyObject* pybullet_loadTexture(PyObject* self, PyObject* args, PyObject* keywds)
|
||||
{
|
||||
int size = PySequence_Size(args);
|
||||
const char* filename = 0;
|
||||
b3SharedMemoryCommandHandle commandHandle;
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
@@ -2970,7 +2964,6 @@ static PyObject* pybullet_getOverlappingObjects(PyObject* self, PyObject* args,
|
||||
|
||||
static PyObject* pybullet_getClosestPointData(PyObject* self, PyObject* args, PyObject *keywds)
|
||||
{
|
||||
int size = PySequence_Size(args);
|
||||
int bodyUniqueIdA = -1;
|
||||
int bodyUniqueIdB = -1;
|
||||
int linkIndexA = -2;
|
||||
@@ -2982,7 +2975,6 @@ static PyObject* pybullet_getClosestPointData(PyObject* self, PyObject* args, Py
|
||||
struct b3ContactInformation contactPointData;
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
PyObject* pyResultList = 0;
|
||||
int physicsClientId = 0;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
static char *kwlist[] = { "bodyA", "bodyB", "distance", "linkIndexA","linkIndexB","physicsClientId", NULL };
|
||||
@@ -3031,7 +3023,7 @@ static PyObject* pybullet_getClosestPointData(PyObject* self, PyObject* args, Py
|
||||
|
||||
static PyObject* pybullet_changeUserConstraint(PyObject* self, PyObject* args, PyObject *keywds)
|
||||
{
|
||||
static char *kwlist[] = { "userConstraintUniqueId","jointChildPivot", "jointChildFrameOrientation", "physicsClientId", NULL};
|
||||
static char *kwlist[] = { "userConstraintUniqueId","jointChildPivot", "jointChildFrameOrientation","maxForce", "physicsClientId", NULL};
|
||||
int userConstraintUniqueId=-1;
|
||||
b3SharedMemoryCommandHandle commandHandle;
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
@@ -3042,8 +3034,9 @@ static PyObject* pybullet_changeUserConstraint(PyObject* self, PyObject* args, P
|
||||
PyObject* jointChildFrameOrnObj=0;
|
||||
double jointChildPivot[3];
|
||||
double jointChildFrameOrn[4];
|
||||
double maxForce = -1;
|
||||
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|OOi", kwlist,&userConstraintUniqueId,&jointChildPivotObj, &jointChildFrameOrnObj,&physicsClientId))
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|OOdi", kwlist,&userConstraintUniqueId,&jointChildPivotObj, &jointChildFrameOrnObj,&maxForce, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -3065,6 +3058,10 @@ static PyObject* pybullet_changeUserConstraint(PyObject* self, PyObject* args, P
|
||||
{
|
||||
b3InitChangeUserConstraintSetFrameInB(commandHandle, jointChildFrameOrn);
|
||||
}
|
||||
if (maxForce>=0)
|
||||
{
|
||||
b3InitChangeUserConstraintSetMaxForce(commandHandle,maxForce);
|
||||
}
|
||||
|
||||
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
|
||||
statusType = b3GetStatusType(statusHandle);
|
||||
@@ -3111,9 +3108,6 @@ static PyObject* pybullet_updateUserConstraint(PyObject* self, PyObject* args, P
|
||||
|
||||
static PyObject* pybullet_createUserConstraint(PyObject* self, PyObject* args, PyObject *keywds)
|
||||
{
|
||||
int size = PySequence_Size(args);
|
||||
int bodyUniqueIdA = -1;
|
||||
int bodyUniqueIdB = -1;
|
||||
|
||||
b3SharedMemoryCommandHandle commandHandle;
|
||||
int parentBodyUniqueId=-1;
|
||||
@@ -3135,7 +3129,6 @@ static PyObject* pybullet_createUserConstraint(PyObject* self, PyObject* args, P
|
||||
struct b3JointInfo jointInfo;
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
PyObject* pyResultList = 0;
|
||||
int physicsClientId = 0;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
static char *kwlist[] = { "parentBodyUniqueId", "parentLinkIndex",
|
||||
@@ -3218,7 +3211,6 @@ static PyObject* pybullet_createUserConstraint(PyObject* self, PyObject* args, P
|
||||
}
|
||||
|
||||
static PyObject* pybullet_getContactPointData(PyObject* self, PyObject* args, PyObject *keywds) {
|
||||
int size = PySequence_Size(args);
|
||||
int bodyUniqueIdA = -1;
|
||||
int bodyUniqueIdB = -1;
|
||||
|
||||
@@ -3226,7 +3218,6 @@ static PyObject* pybullet_getContactPointData(PyObject* self, PyObject* args, Py
|
||||
struct b3ContactInformation contactPointData;
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int statusType;
|
||||
PyObject* pyResultList = 0;
|
||||
|
||||
|
||||
static char *kwlist[] = { "bodyA", "bodyB","physicsClientId", NULL };
|
||||
@@ -3273,7 +3264,6 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
|
||||
struct b3CameraImageData imageData;
|
||||
PyObject* objViewMat = 0, *objProjMat = 0, *lightDirObj = 0, *lightColorObj = 0;
|
||||
int width, height;
|
||||
int size = PySequence_Size(args);
|
||||
float viewMatrix[16];
|
||||
float projectionMatrix[16];
|
||||
float lightDir[3];
|
||||
@@ -3852,8 +3842,7 @@ static PyObject* pybullet_applyExternalForce(PyObject* self, PyObject* args,PyOb
|
||||
|
||||
b3SharedMemoryCommandHandle command;
|
||||
b3SharedMemoryStatusHandle statusHandle;
|
||||
int size = PySequence_Size(args);
|
||||
int physicsClientId = 0;
|
||||
int physicsClientId = 0;
|
||||
b3PhysicsClientHandle sm = 0;
|
||||
static char *kwlist[] = { "objectUniqueId", "linkIndex",
|
||||
"forceObj", "posObj", "flags", "physicsClientId", NULL };
|
||||
@@ -4156,7 +4145,6 @@ static PyObject* pybullet_calculateInverseKinematics(PyObject* self,
|
||||
{
|
||||
int szInBytes = sizeof(double) * numJoints;
|
||||
int i;
|
||||
PyObject* pylist = 0;
|
||||
lowerLimits = (double*)malloc(szInBytes);
|
||||
upperLimits = (double*)malloc(szInBytes);
|
||||
jointRanges = (double*)malloc(szInBytes);
|
||||
|
||||
@@ -1021,9 +1021,10 @@ inline void b3DynamicBvh::rayTest( const b3DbvtNode* root,
|
||||
unsigned int signs[3] = { rayDirectionInverse[0] < 0.0, rayDirectionInverse[1] < 0.0, rayDirectionInverse[2] < 0.0};
|
||||
|
||||
b3Scalar lambda_max = rayDir.dot(rayTo-rayFrom);
|
||||
|
||||
#ifdef COMPARE_BTRAY_AABB2
|
||||
b3Vector3 resultNormal;
|
||||
|
||||
#endif//COMPARE_BTRAY_AABB2
|
||||
|
||||
b3AlignedObjectArray<const b3DbvtNode*> stack;
|
||||
|
||||
int depth=1;
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user