fix many warnings
remove btMultiSapBroadphase.* make collisionFilterGroup/collisionFilterMark int (instead of short int)
This commit is contained in:
@@ -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);
|
||||
|
||||
Reference in New Issue
Block a user