#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 = 0; 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= numJoints) || (jointIndex < 0)) { PyErr_SetString(SpamError, "Joint index out-of-range."); return NULL; } if ((controlMode != CONTROL_MODE_VELOCITY) && (controlMode != CONTROL_MODE_TORQUE) && (controlMode != CONTROL_MODE_POSITION_VELOCITY_PD)) { PyErr_SetString(SpamError, "Illegral control mode."); return NULL; } commandHandle = b3JointControlCommandInit2(sm, bodyIndex,controlMode); b3GetJointInfo(sm, bodyIndex, jointIndex, &info); switch (controlMode) { case CONTROL_MODE_VELOCITY: { b3JointControlSetDesiredVelocity(commandHandle, info.m_uIndex, targetValue); b3JointControlSetKd(commandHandle,info.m_uIndex,1); b3JointControlSetMaximumForce(commandHandle,info.m_uIndex,10000); break; } case CONTROL_MODE_TORQUE: { b3JointControlSetDesiredForceTorque(commandHandle, info.m_uIndex, targetValue); break; } case CONTROL_MODE_POSITION_VELOCITY_PD: { b3JointControlSetDesiredPosition( commandHandle, info.m_qIndex, targetValue); b3JointControlSetKp(commandHandle,info.m_uIndex,1); b3JointControlSetMaximumForce(commandHandle,info.m_uIndex,10000); break; } default: { } }; statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); Py_INCREF(Py_None); return Py_None; } } PyErr_SetString(SpamError, "error in setJointControl."); return NULL; } // Set the gravity of the world with (x, y, z) arguments static PyObject * pybullet_setGravity(PyObject* self, PyObject* args) { if (0==sm) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } { float gravX=0; float gravY=0; float gravZ=-10; int ret; b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm); b3SharedMemoryStatusHandle statusHandle; if (!PyArg_ParseTuple(args, "fff", &gravX,&gravY,&gravZ)) { PyErr_SetString(SpamError, "setGravity expected (x,y,z) values."); return NULL; } ret = b3PhysicsParamSetGravity(command, gravX,gravY, gravZ); //ret = b3PhysicsParamSetTimeStep(command, timeStep); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command); //ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED); } Py_INCREF(Py_None); return Py_None; } // Internal function used to get the base position and orientation // Orientation is returned in quaternions static void pybullet_internalGetBasePositionAndOrientation(int bodyIndex, double basePosition[3],double baseOrientation[3]) { basePosition[0] = 0.; basePosition[1] = 0.; basePosition[2] = 0.; baseOrientation[0] = 0.; baseOrientation[1] = 0.; baseOrientation[2] = 0.; baseOrientation[3] = 1.; { { b3SharedMemoryCommandHandle cmd_handle = b3RequestActualStateCommandInit(sm, bodyIndex); b3SharedMemoryStatusHandle status_handle = b3SubmitClientCommandAndWaitStatus(sm, cmd_handle); const int status_type = b3GetStatusType(status_handle); const double* actualStateQ; // const double* jointReactionForces[]; int i; b3GetStatusActualState(status_handle, 0/* body_unique_id */, 0/* num_degree_of_freedom_q */, 0/* num_degree_of_freedom_u */, 0 /*root_local_inertial_frame*/, &actualStateQ , 0 /* actual_state_q_dot */, 0 /* joint_reaction_forces */); // printf("joint reaction forces="); // for (i=0; i < (sizeof(jointReactionForces)/sizeof(double)); i++) { // printf("%f ", jointReactionForces[i]); // } //now, position x,y,z = actualStateQ[0],actualStateQ[1],actualStateQ[2] //and orientation x,y,z,w = actualStateQ[3],actualStateQ[4],actualStateQ[5],actualStateQ[6] basePosition[0] = actualStateQ[0]; basePosition[1] = actualStateQ[1]; basePosition[2] = actualStateQ[2]; baseOrientation[0] = actualStateQ[3]; baseOrientation[1] = actualStateQ[4]; baseOrientation[2] = actualStateQ[5]; baseOrientation[3] = actualStateQ[6]; } } } // Get the positions (x,y,z) and orientation (x,y,z,w) in quaternion // values for the base link of your object // Object is retrieved based on body index, which is the order // the object was loaded into the simulation (0-based) static PyObject * pybullet_getBasePositionAndOrientation(PyObject* self, PyObject* args) { int bodyIndex = -1; double basePosition[3]; double baseOrientation[4]; PyObject *pylistPos; PyObject *pylistOrientation; if (0==sm) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } if (!PyArg_ParseTuple(args, "i", &bodyIndex )) { PyErr_SetString(SpamError, "Expected a body index (integer)."); return NULL; } pybullet_internalGetBasePositionAndOrientation(bodyIndex,basePosition,baseOrientation); { PyObject *item; int i; int num=3; pylistPos = PyTuple_New(num); for (i = 0; i < num; i++) { item = PyFloat_FromDouble(basePosition[i]); PyTuple_SetItem(pylistPos, i, item); } } { PyObject *item; int i; int num=4; pylistOrientation = PyTuple_New(num); for (i = 0; i < num; i++) { item = PyFloat_FromDouble(baseOrientation[i]); PyTuple_SetItem(pylistOrientation, i, item); } } { PyObject *pylist; pylist = PyTuple_New(2); PyTuple_SetItem(pylist,0,pylistPos); PyTuple_SetItem(pylist,1,pylistOrientation); return pylist; } } // Return the number of joints in an object based on // body index; body index is based on order of sequence // the object is loaded into simulation static PyObject * pybullet_getNumJoints(PyObject* self, PyObject* args) { if (0==sm) { PyErr_SetString(SpamError, "Not connected to physics server."); return NULL; } { int bodyIndex = -1; int numJoints=0; if (!PyArg_ParseTuple(args, "i", &bodyIndex )) { PyErr_SetString(SpamError, "Expected a body index (integer)."); return NULL; } numJoints = b3GetNumJoints(sm,bodyIndex); #if PY_MAJOR_VERSION >= 3 return PyLong_FromLong(numJoints); #else return PyInt_FromLong(numJoints); #endif } } // Initalize all joint positions given a list of values static PyObject* pybullet_resetJointState(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==3) { int bodyIndex; int jointIndex; double targetValue; if (PyArg_ParseTuple(args, "iid", &bodyIndex, &jointIndex, &targetValue)) { b3SharedMemoryCommandHandle commandHandle; b3SharedMemoryStatusHandle statusHandle; int numJoints; numJoints = b3GetNumJoints(sm,bodyIndex); if ((jointIndex >= numJoints) || (jointIndex < 0)) { PyErr_SetString(SpamError, "Joint index out-of-range."); return NULL; } commandHandle = b3CreatePoseCommandInit(sm, bodyIndex); b3CreatePoseCommandSetJointPosition(sm, commandHandle, jointIndex, targetValue); statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle); Py_INCREF(Py_None); return Py_None; } } PyErr_SetString(SpamError, "error in resetJointState."); return NULL; } // CURRENTLY NOT SUPPORTED // Initalize a single joint position for a specific body index // // This method skips any physics simulation and // teleports all joints to the new positions. // TODO(hellojas): initializing one joint currently not supported // static PyObject* // pybullet_initializeJointPosition(PyObject* self, PyObject* args) // { // if (0==sm) // { // PyErr_SetString(SpamError, "Not connected to physics server."); // return NULL; // } // // int i; // int bodyIndex = -1; // int jointIndex = -1; // double jointPos = 0.0; // // int size= PySequence_Size(args); // // if (size==3) // get body index, joint index, and joint position value // { // if (PyArg_ParseTuple(args, "iid", &bodyIndex, &jointIndex, &jointPos)) // { // b3SharedMemoryCommandHandle cmd_handle = b3CreatePoseCommandInit(sm, bodyIndex); // // // printf("initializing joint %d at %f\n", jointIndex, jointPos); // b3CreatePoseCommandSetJointPosition(sm, cmd_handle, jointIndex, jointPos); // // b3SharedMemoryStatusHandle status_handle = // b3SubmitClientCommandAndWaitStatus(sm, cmd_handle); // // const int status_type = b3GetStatusType(status_handle); // // } // } // // Py_INCREF(Py_None); // return Py_None; // } #if 0 static void pybullet_internalGetJointPositions(int bodyIndex, int numJoints, double jointPositions[]) { int i, j; int numDegreeQ; int numDegreeU; int arrSizeOfPosAndOrn = 7; for (i =0;i = 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 }