From c0c4c8ba3f75a17595a809b8e025ba8b2c88c83f Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Sun, 15 Jan 2017 22:26:11 -0800 Subject: [PATCH] fix many warnings remove btMultiSapBroadphase.* make collisionFilterGroup/collisionFilterMark int (instead of short int) --- Extras/ConvexDecomposition/concavity.cpp | 26 +- Extras/Serialize/BulletFileLoader/bDNA.cpp | 3 +- Extras/Serialize/BulletFileLoader/bFile.cpp | 10 +- .../btBulletWorldImporter.cpp | 2 - .../BulletWorldImporter/btWorldImporter.cpp | 7 +- .../btBulletXmlWorldImporter.cpp | 92 ++-- data/kuka_iiwa/model.sdf | 16 +- data/multibody.bullet | Bin 14712 -> 14712 bytes examples/BasicDemo/CMakeLists.txt | 2 +- examples/Benchmarks/BenchmarkDemo.cpp | 5 +- .../Collision/CollisionTutorialBullet2.cpp | 12 +- .../Internal/Bullet2CollisionSdk.cpp | 9 +- .../Internal/RealTimeBullet3CollisionSdk.cpp | 25 +- examples/Constraints/ConstraintDemo.cpp | 13 +- examples/Constraints/Dof6Spring2Setup.cpp | 2 - examples/Constraints/TestHingeTorque.cpp | 10 +- examples/Evolution/NN3DWalkers.cpp | 12 +- examples/Evolution/NN3DWalkersTimeWarpBase.h | 2 +- .../GwenGUISupport/GwenParameterInterface.cpp | 11 +- .../InProcessExampleBrowser.cpp | 5 +- .../ExampleBrowser/OpenGLExampleBrowser.cpp | 2 +- examples/ForkLift/ForkLiftDemo.cpp | 4 +- .../FractureDemo/btFractureDynamicsWorld.cpp | 6 +- .../ImportColladaDemo/LoadMeshFromCollada.cpp | 2 +- .../ImportMJCFDemo/BulletMJCFImporter.cpp | 11 +- .../ImportMJCFDemo/ImportMJCFSetup.cpp | 19 +- .../ImportMeshUtility/b3ImportMeshUtility.cpp | 2 +- .../ImportSDFDemo/ImportSDFSetup.cpp | 19 +- .../ImportURDFDemo/ImportURDFSetup.cpp | 19 +- .../Importers/ImportURDFDemo/URDF2Bullet.cpp | 8 +- .../InverseDynamicsExample.cpp | 6 +- .../InverseKinematicsExample.cpp | 16 +- .../MultiBody/InvertedPendulumPDControl.cpp | 14 +- .../MultiBody/MultiBodyConstraintFeedback.cpp | 16 +- examples/MultiBody/MultiBodySoftContact.cpp | 6 +- examples/MultiBody/MultiDofDemo.cpp | 2 +- examples/MultiBody/Pendulum.cpp | 4 +- examples/MultiBody/TestJointTorqueSetup.cpp | 8 +- examples/MultiThreadedDemo/ParallelFor.h | 4 +- .../MultiThreading/MultiThreadingExample.cpp | 6 +- .../OpenCL/CommonOpenCL/CommonOpenCLBase.h | 4 +- examples/OpenCL/broadphase/PairBench.cpp | 25 +- examples/OpenCL/rigidbody/GpuConvexScene.cpp | 47 +- .../OpenCL/rigidbody/GpuRigidBodyDemo.cpp | 8 +- .../OpenGLWindow/GLInstancingRenderer.cpp | 8 +- examples/OpenGLWindow/GLPrimitiveRenderer.cpp | 4 +- examples/OpenGLWindow/MacOpenGLWindow.mm | 6 +- .../DynamicTexturedCubeDemo.cpp | 10 +- examples/RenderingExamples/RaytracerSetup.cpp | 16 +- .../RenderingExamples/TimeSeriesCanvas.cpp | 2 +- .../RenderingExamples/TinyRendererSetup.cpp | 14 +- examples/RenderingExamples/TinyVRGui.cpp | 7 +- examples/RigidBody/RigidBodySoftContact.cpp | 3 +- .../RoboticsLearning/GripperGraspExample.cpp | 14 +- .../RoboticsLearning/KukaGraspExample.cpp | 6 +- .../RoboticsLearning/R2D2GraspExample.cpp | 10 +- examples/RoboticsLearning/b3RobotSimAPI.cpp | 39 +- .../SharedMemory/PhysicsClientExample.cpp | 8 +- .../PhysicsClientSharedMemory.cpp | 7 +- examples/SharedMemory/PhysicsClientUDP.cpp | 13 +- .../SharedMemory/PhysicsClientUDP_C_API.cpp | 3 +- examples/SharedMemory/PhysicsDirectC_API.cpp | 3 +- .../SharedMemory/PhysicsLoopBackC_API.cpp | 3 +- .../PhysicsServerCommandProcessor.cpp | 25 +- .../SharedMemory/PhysicsServerExample.cpp | 76 +-- .../SharedMemoryCommandProcessor.cpp | 1 - .../TinyRendererVisualShapeConverter.cpp | 4 +- examples/SoftDemo/SoftDemo.cpp | 17 +- examples/ThirdPartyLibs/BussIK/MatrixRmn.cpp | 2 +- examples/ThirdPartyLibs/BussIK/Misc.cpp | 10 +- examples/ThirdPartyLibs/BussIK/Node.h | 2 +- examples/TinyRenderer/TinyRenderer.cpp | 53 +- examples/Tutorial/Dof6ConstraintTutorial.cpp | 6 +- examples/Tutorial/Tutorial.cpp | 8 +- examples/Vehicles/Hinge2Vehicle.cpp | 34 +- examples/pybullet/pybullet.c | 32 +- .../BroadPhaseCollision/b3DynamicBvh.h | 5 +- .../b3DynamicBvhBroadphase.cpp | 4 +- .../b3DynamicBvhBroadphase.h | 14 +- .../b3OverlappingPairCache.cpp | 4 +- .../b3OverlappingPairCache.h | 2 +- .../NarrowPhaseCollision/shared/b3ClipFaces.h | 2 +- .../shared/b3ContactConvexConvexSAT.h | 9 +- .../shared/b3FindConcaveSatAxis.h | 8 +- .../shared/b3FindSeparatingAxis.h | 2 +- .../shared/b3MprPenetration.h | 2 +- .../ConstraintSolver/b3PgsJacobiSolver.cpp | 7 +- .../b3Point2PointConstraint.cpp | 2 +- .../b3CpuRigidBodyPipeline.cpp | 16 +- .../b3GpuBroadphaseInterface.h | 4 +- .../b3GpuGridBroadphase.cpp | 9 +- .../BroadphaseCollision/b3GpuGridBroadphase.h | 4 +- .../b3GpuParallelLinearBvhBroadphase.cpp | 4 +- .../b3GpuParallelLinearBvhBroadphase.h | 4 +- .../b3GpuSapBroadphase.cpp | 92 +++- .../BroadphaseCollision/b3GpuSapBroadphase.h | 4 +- .../Initialize/b3OpenCLUtils.cpp | 10 +- .../b3ConvexHullContact.cpp | 83 +-- .../b3GjkPairDetector.cpp | 12 +- .../NarrowphaseCollision/b3QuantizedBvh.h | 2 +- src/Bullet3OpenCL/Raycast/b3GpuRaycast.cpp | 2 +- .../RigidBody/b3GpuGenericConstraint.cpp | 2 +- .../RigidBody/b3GpuJacobiContactSolver.cpp | 4 +- .../RigidBody/b3GpuNarrowPhase.cpp | 4 +- .../RigidBody/b3GpuPgsConstraintSolver.cpp | 18 +- .../RigidBody/b3GpuPgsContactSolver.cpp | 67 +-- src/Bullet3OpenCL/RigidBody/b3Solver.cpp | 49 +- .../Bullet2FileLoader/b3DNA.cpp | 5 +- .../Bullet2FileLoader/b3File.cpp | 7 +- .../BroadphaseCollision/btAxisSweep3.h | 13 +- .../btBroadphaseInterface.h | 2 +- .../BroadphaseCollision/btBroadphaseProxy.h | 13 +- .../BroadphaseCollision/btDbvtBroadphase.cpp | 7 +- .../BroadphaseCollision/btDbvtBroadphase.h | 4 +- .../btMultiSapBroadphase.cpp | 489 ------------------ .../btMultiSapBroadphase.h | 151 ------ .../BroadphaseCollision/btQuantizedBvh.h | 2 +- .../btSimpleBroadphase.cpp | 4 +- .../BroadphaseCollision/btSimpleBroadphase.h | 6 +- src/BulletCollision/CMakeLists.txt | 2 - .../CollisionDispatch/btCollisionWorld.cpp | 5 +- .../CollisionDispatch/btCollisionWorld.h | 14 +- .../btCollisionWorldImporter.cpp | 4 +- .../btConvexConcaveCollisionAlgorithm.cpp | 4 +- .../btKinematicCharacterController.cpp | 4 +- .../btSequentialImpulseConstraintSolver.cpp | 10 +- .../Dynamics/btDiscreteDynamicsWorld.cpp | 8 +- .../Dynamics/btDiscreteDynamicsWorld.h | 4 +- src/BulletDynamics/Dynamics/btDynamicsWorld.h | 2 +- .../Dynamics/btSimpleDynamicsWorld.cpp | 2 +- .../Dynamics/btSimpleDynamicsWorld.h | 2 +- .../Featherstone/btMultiBody.cpp | 4 +- .../btMultiBodyConstraintSolver.cpp | 3 +- .../Featherstone/btMultiBodyDynamicsWorld.cpp | 2 +- .../Featherstone/btMultiBodyDynamicsWorld.h | 2 +- src/BulletSoftBody/btSoftBodyHelpers.cpp | 4 +- src/BulletSoftBody/btSoftBodyInternals.h | 39 +- .../btSoftMultiBodyDynamicsWorld.cpp | 2 +- .../btSoftMultiBodyDynamicsWorld.h | 2 +- .../btSoftRigidCollisionAlgorithm.h | 4 +- .../btSoftRigidDynamicsWorld.cpp | 2 +- src/BulletSoftBody/btSoftRigidDynamicsWorld.h | 2 +- .../btSoftSoftCollisionAlgorithm.h | 4 +- src/BulletSoftBody/btSparseSDF.h | 2 +- src/btBulletCollisionCommon.h | 1 - .../test_invdyn_kinematics.cpp | 5 +- 146 files changed, 830 insertions(+), 1431 deletions(-) delete mode 100644 src/BulletCollision/BroadphaseCollision/btMultiSapBroadphase.cpp delete mode 100644 src/BulletCollision/BroadphaseCollision/btMultiSapBroadphase.h diff --git a/Extras/ConvexDecomposition/concavity.cpp b/Extras/ConvexDecomposition/concavity.cpp index f1a466001..5827da293 100644 --- a/Extras/ConvexDecomposition/concavity.cpp +++ b/Extras/ConvexDecomposition/concavity.cpp @@ -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; } diff --git a/Extras/Serialize/BulletFileLoader/bDNA.cpp b/Extras/Serialize/BulletFileLoader/bDNA.cpp index 86d15cfdd..7b42062b3 100644 --- a/Extras/Serialize/BulletFileLoader/bDNA.cpp +++ b/Extras/Serialize/BulletFileLoader/bDNA.cpp @@ -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; /* diff --git a/Extras/Serialize/BulletFileLoader/bFile.cpp b/Extras/Serialize/BulletFileLoader/bFile.cpp index cb8010dc2..1137a3fd6 100644 --- a/Extras/Serialize/BulletFileLoader/bFile.cpp +++ b/Extras/Serialize/BulletFileLoader/bFile.cpp @@ -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("\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("\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); diff --git a/Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.cpp b/Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.cpp index cc8172be2..3605863ec 100644 --- a/Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.cpp +++ b/Extras/Serialize/BulletWorldImporter/btBulletWorldImporter.cpp @@ -307,8 +307,6 @@ bool btBulletWorldImporter::convertAllObjects( bParse::btBulletFile* bulletFile for (i=0;im_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); diff --git a/Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp b/Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp index 174e9ed49..ff90dd3f6 100644 --- a/Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp +++ b/Extras/Serialize/BulletWorldImporter/btWorldImporter.cpp @@ -468,14 +468,11 @@ btCollisionShape* btWorldImporter::convertCollisionShape( btCollisionShapeData* btCompoundShapeData* compoundData = (btCompoundShapeData*)shapeData; btCompoundShape* compoundShape = createCompoundShape(); - btCompoundShapeChildData* childShapeDataArray = &compoundData->m_childShapePtr[0]; - - + btAlignedObjectArray childShapes; for (int i=0;im_numChildShapes;i++) { - btCompoundShapeChildData* ptr = &compoundData->m_childShapePtr[i]; - + btCollisionShapeData* cd = compoundData->m_childShapePtr[i].m_childShape; btCollisionShape* childShape = convertCollisionShape(cd); diff --git a/Extras/Serialize/BulletXmlWorldImporter/btBulletXmlWorldImporter.cpp b/Extras/Serialize/BulletXmlWorldImporter/btBulletXmlWorldImporter.cpp index f3615d6aa..e58dbc1f9 100644 --- a/Extras/Serialize/BulletXmlWorldImporter/btBulletXmlWorldImporter.cpp +++ b/Extras/Serialize/BulletXmlWorldImporter/btBulletXmlWorldImporter.cpp @@ -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* compoundChildArrayPtr = new btAlignedObjectArray; @@ -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 v; deSerializeVector3FloatData(pChild,v); @@ -651,7 +683,7 @@ void btBulletXmlWorldImporter::auto_serialize_root_level_children(TiXmlNode* pPa for (int i=0;i 1 1 1 - meshes/coarse/link_0.stl + meshes/link_0.stl @@ -60,7 +60,7 @@ 1 1 1 - meshes/coarse/link_1.stl + meshes/link_1.stl @@ -119,7 +119,7 @@ 1 1 1 - meshes/coarse/link_2.stl + meshes/link_2.stl @@ -178,7 +178,7 @@ 1 1 1 - meshes/coarse/link_3.stl + meshes/link_3.stl @@ -237,7 +237,7 @@ 1 1 1 - meshes/coarse/link_4.stl + meshes/link_4.stl @@ -296,7 +296,7 @@ 1 1 1 - meshes/coarse/link_5.stl + meshes/link_5.stl @@ -355,7 +355,7 @@ 1 1 1 - meshes/coarse/link_6.stl + meshes/link_6.stl @@ -414,7 +414,7 @@ 1 1 1 - meshes/coarse/link_7.stl + meshes/link_7.stl diff --git a/data/multibody.bullet b/data/multibody.bullet index 90aa451573fd7c8611a929f7947ef633b70b227f..4cb146f2f271443a0a269fc243ee2c4cd8ad23ee 100644 GIT binary patch delta 456 zcmajbyGjE=6b9g#y=AjT-Oa^ZjEMwnWU(_SxQP;w-~|F&i3(QHLS2GFIyuf4ziHFHjW7N{(R*W%rRNbj;1cAPV9gaY(=dBq0T9 z$iO0GVF_}O#|v{bFdX^{H&5%AFWrxo+wwztyM!kDFSl;?%h7)9?KAbe|F4WM%XbEb GxAp@E;%Qa@ delta 663 zcmexS^rL7($>bD9p^0tpSW1f0k|rlIN@)l&Ot5pT`Crcf27lNYE-)}}s|4`_yq%!p z5)22JC+}jEVk^ljN@K7D>XT5Fz|gm0O0?8D6nz4d#hI*C<-jT-<})yWY-m7I2@w~V zT+U?8s4}^qMSSupCM7qyHS9A%ZrHOILZ4xl2J>%1X_#qHx&cOuf*6)ip5^3+OhuEI zFe|ADfCV=^fH)8;4W|;5^K&4+;$VaN3g|_p$vP}NjEtKtS?rk@6($R^3Qz7~6A?UD z&&Ck!;TT{6)XoXQlNs6V8FMCoWK(DP4+N8C*nJpzLCQtXp7F6;Qn1(V?3purL6(8| z;*%$`w>jHFxqH#1LHvC%0!4U>;>RQLhSwS^i) zw888^lRy?QG9U~NsEUCYoW}IOe)1>Is<@|yBKsV}uG{+QZ3mjn!Z0H|d~fr5RlAwt z*KI*jec_ms-By)aua)#TgetAppInterface()), 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; diff --git a/examples/Collision/Internal/Bullet2CollisionSdk.cpp b/examples/Collision/Internal/Bullet2CollisionSdk.cpp index a11e6efad..ec7a689c2 100644 --- a/examples/Collision/Internal/Bullet2CollisionSdk.cpp +++ b/examples/Collision/Internal/Bullet2CollisionSdk.cpp @@ -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) { } }; diff --git a/examples/Collision/Internal/RealTimeBullet3CollisionSdk.cpp b/examples/Collision/Internal/RealTimeBullet3CollisionSdk.cpp index 34b8e7eb0..1c57c1af7 100644 --- a/examples/Collision/Internal/RealTimeBullet3CollisionSdk.cpp +++ b/examples/Collision/Internal/RealTimeBullet3CollisionSdk.cpp @@ -53,13 +53,19 @@ struct RTB3CollisionWorld b3AlignedObjectArray m_worldSpaceAabbs; b3AlignedObjectArray m_planeFaces; b3AlignedObjectArray 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; } diff --git a/examples/Constraints/ConstraintDemo.cpp b/examples/Constraints/ConstraintDemo.cpp index 8c5fced4a..41a888cd4 100644 --- a/examples/Constraints/ConstraintDemo.cpp +++ b/examples/Constraints/ConstraintDemo.cpp @@ -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) diff --git a/examples/Constraints/Dof6Spring2Setup.cpp b/examples/Constraints/Dof6Spring2Setup.cpp index ba96cc010..0fd8975d4 100644 --- a/examples/Constraints/Dof6Spring2Setup.cpp +++ b/examples/Constraints/Dof6Spring2Setup.cpp @@ -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; diff --git a/examples/Constraints/TestHingeTorque.cpp b/examples/Constraints/TestHingeTorque.cpp index bdc9c2f6a..86217de3f 100644 --- a/examples/Constraints/TestHingeTorque.cpp +++ b/examples/Constraints/TestHingeTorque.cpp @@ -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; diff --git a/examples/Evolution/NN3DWalkers.cpp b/examples/Evolution/NN3DWalkers.cpp index 9b1a0f4da..8e1afca90 100755 --- a/examples/Evolution/NN3DWalkers.cpp +++ b/examples/Evolution/NN3DWalkers.cpp @@ -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; diff --git a/examples/Evolution/NN3DWalkersTimeWarpBase.h b/examples/Evolution/NN3DWalkersTimeWarpBase.h index a7a9a2a7d..0c97c3850 100644 --- a/examples/Evolution/NN3DWalkersTimeWarpBase.h +++ b/examples/Evolution/NN3DWalkersTimeWarpBase.h @@ -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(); diff --git a/examples/ExampleBrowser/GwenGUISupport/GwenParameterInterface.cpp b/examples/ExampleBrowser/GwenGUISupport/GwenParameterInterface.cpp index aa8c0b871..d4e98a7fc 100644 --- a/examples/ExampleBrowser/GwenGUISupport/GwenParameterInterface.cpp +++ b/examples/ExampleBrowser/GwenGUISupport/GwenParameterInterface.cpp @@ -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); } diff --git a/examples/ExampleBrowser/InProcessExampleBrowser.cpp b/examples/ExampleBrowser/InProcessExampleBrowser.cpp index 3060eaaee..0b979b361 100644 --- a/examples/ExampleBrowser/InProcessExampleBrowser.cpp +++ b/examples/ExampleBrowser/InProcessExampleBrowser.cpp @@ -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; } diff --git a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp index ee27e72e7..1bac82724 100644 --- a/examples/ExampleBrowser/OpenGLExampleBrowser.cpp +++ b/examples/ExampleBrowser/OpenGLExampleBrowser.cpp @@ -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) { diff --git a/examples/ForkLift/ForkLiftDemo.cpp b/examples/ForkLift/ForkLiftDemo.cpp index f315daa48..e993462ef 100644 --- a/examples/ForkLift/ForkLiftDemo.cpp +++ b/examples/ForkLift/ForkLiftDemo.cpp @@ -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 diff --git a/examples/FractureDemo/btFractureDynamicsWorld.cpp b/examples/FractureDemo/btFractureDynamicsWorld.cpp index 0d44c53d2..d037d11cf 100644 --- a/examples/FractureDemo/btFractureDynamicsWorld.cpp +++ b/examples/FractureDemo/btFractureDynamicsWorld.cpp @@ -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; diff --git a/examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp b/examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp index 8b47f5552..8a99da00f 100644 --- a/examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp +++ b/examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp @@ -336,7 +336,7 @@ void readLibraryGeometries(TiXmlDocument& doc, btAlignedObjectArray& name2Shape, btAlignedObjectArray& visualShapeInstances, const btMatrix4x4& parentTransMat) { - const char* nodeName = node->Attribute("id"); + //const char* nodeName = node->Attribute("id"); //printf("processing node %s\n", nodeName); diff --git a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp index 103e49945..3b06259f9 100644 --- a/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp +++ b/examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp @@ -157,7 +157,6 @@ struct BulletMJCFImporterInternalData //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()) { - bool handled = false; std::string n = child_xml->Value(); if (n=="inertial") { @@ -412,7 +411,7 @@ struct BulletMJCFImporterInternalData - 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"); @@ -713,7 +712,7 @@ struct BulletMJCFImporterInternalData const char* bodyName = link_xml->Attribute("name"); int orgChildLinkIndex = createBody(modelIndex,bodyName); - int curChildLinkIndex = orgChildLinkIndex; +// int curChildLinkIndex = orgChildLinkIndex; std::string bodyN; if (bodyName) @@ -727,7 +726,7 @@ struct BulletMJCFImporterInternalData } - btTransform orgLinkTransform = parseTransform(link_xml,logger); +// btTransform orgLinkTransform = parseTransform(link_xml,logger); btTransform linkTransform = parseTransform(link_xml,logger); UrdfLink* linkPtr = getLink(modelIndex,orgChildLinkIndex); @@ -739,7 +738,7 @@ struct BulletMJCFImporterInternalData 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(); @@ -1331,7 +1330,7 @@ class btCompoundShape* BulletMJCFImporter::convertLinkCollisionShapes(int linkIn 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; + //btVector3 c = (f+t)*0.5; //f-=c; //t-=c; btVector3 fromto[2] = {f,t}; diff --git a/examples/Importers/ImportMJCFDemo/ImportMJCFSetup.cpp b/examples/Importers/ImportMJCFDemo/ImportMJCFSetup.cpp index cf1def58d..481c0a1c3 100644 --- a/examples/Importers/ImportMJCFDemo/ImportMJCFSetup.cpp +++ b/examples/Importers/ImportMJCFDemo/ImportMJCFSetup.cpp @@ -147,25 +147,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); @@ -229,7 +212,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); diff --git a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp index 313ae041a..2466c63d9 100644 --- a/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp +++ b/examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp @@ -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