fix many warnings

remove btMultiSapBroadphase.*
make collisionFilterGroup/collisionFilterMark int (instead of short int)
This commit is contained in:
Erwin Coumans
2017-01-15 22:26:11 -08:00
parent e3df00d5f1
commit c0c4c8ba3f
146 changed files with 830 additions and 1431 deletions

View File

@@ -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(

View File

@@ -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
{

View File

@@ -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;

View File

@@ -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)
{
}
};

View File

@@ -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;
}

View File

@@ -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)

View File

@@ -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;

View File

@@ -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;

View File

@@ -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;

View File

@@ -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();

View File

@@ -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);
}

View File

@@ -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;
}

View File

@@ -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)
{

View File

@@ -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

View File

@@ -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;

View File

@@ -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);

View File

@@ -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};

View File

@@ -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);

View File

@@ -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++)
{

View File

@@ -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);

View File

@@ -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);

View File

@@ -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] =
@@ -446,8 +446,8 @@ 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);

View File

@@ -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
}
}

View File

@@ -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);

View File

@@ -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);

View File

@@ -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);

View File

@@ -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);

View File

@@ -242,7 +242,7 @@ void MultiDofDemo::initPhysics()
if (multibodyConstraint) {
btVector3 pointInA = -linkHalfExtents;
btVector3 pointInB = halfExtents;
// btVector3 pointInB = halfExtents;
btMatrix3x3 frameInA;
btMatrix3x3 frameInB;
frameInA.setIdentity();

View File

@@ -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);

View File

@@ -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)
{

View File

@@ -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();
}

View File

@@ -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);

View File

@@ -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;

View File

@@ -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;

View File

@@ -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);

View File

@@ -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;

View File

@@ -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);

View File

@@ -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];

View File

@@ -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];

View File

@@ -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);

View File

@@ -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++)

View File

@@ -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;

View File

@@ -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);

View File

@@ -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)
{
}

View File

@@ -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));

View File

@@ -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()

View File

@@ -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)
{

View File

@@ -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);

View File

@@ -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)
{
}
@@ -695,7 +696,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 +844,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 +867,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 +890,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)
@@ -912,7 +910,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;
}

View File

@@ -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");

View File

@@ -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) {

View File

@@ -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();

View File

@@ -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;
}

View File

@@ -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;
}

View File

@@ -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;
}

View File

@@ -438,7 +438,7 @@ struct PhysicsServerCommandProcessorInternalData
if (m_firstFreeHandle<0)
{
int curCapacity = m_bodyHandles.size();
//int curCapacity = m_bodyHandles.size();
int additionalCapacity= m_bodyHandles.size();
increaseHandleCapacity(additionalCapacity);
@@ -541,14 +541,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),
@@ -1336,7 +1337,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;
@@ -2920,9 +2921,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 +3134,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;
@@ -3789,8 +3788,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;
@@ -4084,7 +4083,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
return hasStatus;
}
static int skip=1;
//static int skip=1;
void PhysicsServerCommandProcessor::renderScene()
{

View File

@@ -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);
@@ -1507,8 +1510,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 +1637,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();

View File

@@ -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;

View File

@@ -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)
{

View File

@@ -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;

View File

@@ -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

View File

@@ -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. };

View File

@@ -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)

View File

@@ -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)

View File

@@ -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);

View File

@@ -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);

View File

@@ -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)),

View File

@@ -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;
@@ -614,7 +610,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 +748,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 +1571,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 +2121,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 +2189,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 +2693,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 +2755,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 +2957,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 +2968,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 };
@@ -3111,9 +3096,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 +3117,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 +3199,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 +3206,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 +3252,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 +3830,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 +4133,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);