#include "../SharedMemory/PhysicsClientC_API.h" #include "../SharedMemory/PhysicsDirectC_API.h" #include "../SharedMemory/SharedMemoryInProcessPhysicsC_API.h" #ifdef __APPLE__ #include #else #include #endif #if PY_MAJOR_VERSION >= 3 #define PyInt_FromLong PyLong_FromLong #define PyString_FromString PyBytes_FromString #endif enum eCONNECT_METHOD { eCONNECT_GUI=1, eCONNECT_DIRECT=2, eCONNECT_SHARED_MEMORY=3, }; static PyObject *SpamError; static b3PhysicsClientHandle sm=0; // Step through one timestep of the simulation static PyObject * pybullet_stepSimulation(PyObject *self, PyObject *args) { if (0==sm) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } { b3SharedMemoryStatusHandle statusHandle; int statusType; if (b3CanSubmitCommand(sm)) { statusHandle = b3SubmitClientCommandAndWaitStatus(sm, b3InitStepSimulationCommand(sm)); statusType = b3GetStatusType(statusHandle); } } Py_INCREF(Py_None); return Py_None; } static PyObject * pybullet_connectPhysicsServer(PyObject *self, PyObject *args) { if (0!=sm) { PyErr_SetString(SpamError, "Already connected to physics server, disconnect first."); return NULL; } { int method=eCONNECT_GUI; if (!PyArg_ParseTuple(args, "i", &method)) { PyErr_SetString(SpamError, "connectPhysicsServer expected argument eCONNECT_GUI, eCONNECT_DIRECT or eCONNECT_SHARED_MEMORY"); return NULL; } switch (method) { case eCONNECT_GUI: { int argc=0; char* argv[1]={0}; #ifdef __APPLE__ sm = b3CreateInProcessPhysicsServerAndConnectMainThread(argc, argv); #else sm = b3CreateInProcessPhysicsServerAndConnect(argc, argv); #endif break; } case eCONNECT_DIRECT: { sm = b3ConnectPhysicsDirect(); break; } case eCONNECT_SHARED_MEMORY: { sm = b3ConnectSharedMemory(SHARED_MEMORY_KEY); break; } default: { PyErr_SetString(SpamError, "connectPhysicsServer unexpected argument"); return NULL; } }; } Py_INCREF(Py_None); return Py_None; } static PyObject * pybullet_disconnectPhysicsServer(PyObject *self, PyObject *args) { if (0==sm) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } { b3DisconnectSharedMemory(sm); sm = 0; } Py_INCREF(Py_None); return Py_None; } // Load a URDF file indicating the links and joints of an object // function can be called without arguments and will default // to position (0,0,1) with orientation(0,0,0,1) // els(x,y,z) or // loadURDF(pos_x, pos_y, pos_z, orn_x, orn_y, orn_z, orn_w) static PyObject * pybullet_loadURDF(PyObject* self, PyObject* args) { int size= PySequence_Size(args); int bodyIndex = -1; const char* urdfFileName=""; float startPosX =0; float startPosY =0; float startPosZ = 1; float startOrnX = 0; float startOrnY = 0; float startOrnZ = 0; float startOrnW = 1; if (0==sm) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } if (size==1) { if (!PyArg_ParseTuple(args, "s", &urdfFileName)) return NULL; } if (size == 4) { if (!PyArg_ParseTuple(args, "sfff", &urdfFileName, &startPosX,&startPosY,&startPosZ)) return NULL; } if (size==8) { if (!PyArg_ParseTuple(args, "sfffffff", &urdfFileName, &startPosX,&startPosY,&startPosZ, &startOrnX,&startOrnY,&startOrnZ, &startOrnW)) return NULL; } { b3SharedMemoryStatusHandle statusHandle; int statusType; b3SharedMemoryCommandHandle command = b3LoadUrdfCommandInit(sm, urdfFileName); //setting the initial position, orientation and other arguments are optional b3LoadUrdfCommandSetStartPosition(command, startPosX,startPosY,startPosZ); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); statusType = b3GetStatusType(statusHandle); if (statusType!=CMD_URDF_LOADING_COMPLETED) { PyErr_SetString(SpamError, "Cannot load URDF file."); return NULL; } bodyIndex = b3GetStatusBodyIndex(statusHandle); } return PyLong_FromLong(bodyIndex); } static float pybullet_internalGetFloatFromSequence(PyObject* seq, int index) { float v = 0.f; PyObject* item; if (PyList_Check(seq)) { item = PyList_GET_ITEM(seq, index); v = PyFloat_AsDouble(item); } else { item = PyTuple_GET_ITEM(seq,index); v = PyFloat_AsDouble(item); } return v; } #define MAX_SDF_BODIES 512 static PyObject* pybullet_loadSDF(PyObject* self, PyObject* args) { const char* sdfFileName=""; int size= PySequence_Size(args); int numBodies = 0; int i; int bodyIndicesOut[MAX_SDF_BODIES]; PyObject* pylist=0; b3SharedMemoryStatusHandle statusHandle; int statusType; b3SharedMemoryCommandHandle commandHandle; if (0==sm) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } if (size==1) { if (!PyArg_ParseTuple(args, "s", &sdfFileName)) return NULL; } commandHandle = b3LoadSdfCommandInit(sm, sdfFileName); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); statusType = b3GetStatusType(statusHandle); if (statusType!=CMD_SDF_LOADING_COMPLETED) { PyErr_SetString(SpamError, "Cannot load SDF file."); return NULL; } numBodies = b3GetStatusBodyIndices(statusHandle, bodyIndicesOut, MAX_SDF_BODIES); if (numBodies > MAX_SDF_BODIES) { PyErr_SetString(SpamError, "SDF exceeds body capacity"); return NULL; } pylist = PyTuple_New(numBodies); if (numBodies >0 && numBodies <= MAX_SDF_BODIES) { for (i=0;i= 3 return PyLong_FromLong(numJoints); #else return PyInt_FromLong(numJoints); #endif } } // Initalize all joint positions given a list of values static PyObject* pybullet_initializeJointPositions(PyObject* self, PyObject* args) { int size; if (0==sm) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } size= PySequence_Size(args); if (size==2) { int bodyIndex; PyObject* targetValues; if (PyArg_ParseTuple(args, "iO", &bodyIndex, &targetValues)) { PyObject* seq; int numJoints, len; seq = PySequence_Fast(targetValues, "expected a sequence"); len = PySequence_Size(targetValues); numJoints = b3GetNumJoints(sm,bodyIndex); b3SharedMemoryCommandHandle commandHandle; b3SharedMemoryStatusHandle statusHandle; int qIndex; if (len!=numJoints) { PyErr_SetString(SpamError, "Number of joint position values doesn't match the number of joints."); Py_DECREF(seq); return NULL; } commandHandle = b3CreatePoseCommandInit(sm, bodyIndex); for (qIndex=0;qIndex= 3 static struct PyModuleDef moduledef = { PyModuleDef_HEAD_INIT, "pybullet", /* m_name */ "Python bindings for Bullet", /* m_doc */ -1, /* m_size */ SpamMethods, /* m_methods */ NULL, /* m_reload */ NULL, /* m_traverse */ NULL, /* m_clear */ NULL, /* m_free */ }; #endif PyMODINIT_FUNC #if PY_MAJOR_VERSION >= 3 PyInit_pybullet(void) #else initpybullet(void) #endif { PyObject *m; #if PY_MAJOR_VERSION >= 3 m = PyModule_Create(&moduledef); #else m = Py_InitModule3("pybullet", SpamMethods, "Python bindings for Bullet"); #endif #if PY_MAJOR_VERSION >= 3 if (m == NULL) return m; #else if (m == NULL) return; #endif PyModule_AddIntConstant (m, "SHARED_MEMORY", eCONNECT_SHARED_MEMORY); // user read PyModule_AddIntConstant (m, "DIRECT", eCONNECT_DIRECT); // user read PyModule_AddIntConstant (m, "GUI", eCONNECT_GUI); // user read PyModule_AddIntConstant (m, "TORQUE_CONTROL", CONTROL_MODE_TORQUE); PyModule_AddIntConstant (m, "VELOCITY_CONTROL", CONTROL_MODE_VELOCITY); // user read PyModule_AddIntConstant (m, "POSITION_CONTROL", CONTROL_MODE_POSITION_VELOCITY_PD); // user read SpamError = PyErr_NewException("pybullet.error", NULL, NULL); Py_INCREF(SpamError); PyModule_AddObject(m, "error", SpamError); #if PY_MAJOR_VERSION >= 3 return m; #endif }