pybullet.c 73 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415141614171418141914201421142214231424142514261427142814291430143114321433143414351436143714381439144014411442144314441445144614471448144914501451145214531454145514561457145814591460146114621463146414651466146714681469147014711472147314741475147614771478147914801481148214831484148514861487148814891490149114921493149414951496149714981499150015011502150315041505150615071508150915101511151215131514151515161517151815191520152115221523152415251526152715281529153015311532153315341535153615371538153915401541154215431544154515461547154815491550155115521553155415551556155715581559156015611562156315641565156615671568156915701571157215731574157515761577157815791580158115821583158415851586158715881589159015911592159315941595159615971598159916001601160216031604160516061607160816091610161116121613161416151616161716181619162016211622162316241625162616271628162916301631163216331634163516361637163816391640164116421643164416451646164716481649165016511652165316541655165616571658165916601661166216631664166516661667166816691670167116721673167416751676167716781679168016811682168316841685168616871688168916901691169216931694169516961697169816991700170117021703170417051706170717081709171017111712171317141715171617171718171917201721172217231724172517261727172817291730173117321733173417351736173717381739174017411742174317441745174617471748174917501751175217531754175517561757175817591760176117621763176417651766176717681769177017711772177317741775177617771778177917801781178217831784178517861787178817891790179117921793179417951796179717981799180018011802180318041805180618071808180918101811181218131814181518161817181818191820182118221823182418251826182718281829183018311832183318341835183618371838183918401841184218431844184518461847184818491850185118521853185418551856185718581859186018611862186318641865186618671868186918701871187218731874187518761877187818791880188118821883188418851886188718881889189018911892189318941895189618971898189919001901190219031904190519061907190819091910191119121913191419151916191719181919192019211922192319241925192619271928192919301931193219331934193519361937193819391940194119421943194419451946194719481949195019511952195319541955195619571958195919601961196219631964196519661967196819691970197119721973197419751976197719781979198019811982198319841985198619871988198919901991199219931994199519961997199819992000200120022003200420052006200720082009201020112012201320142015201620172018201920202021202220232024202520262027202820292030203120322033203420352036203720382039204020412042204320442045204620472048204920502051205220532054205520562057205820592060206120622063206420652066206720682069207020712072207320742075207620772078207920802081208220832084208520862087208820892090209120922093209420952096209720982099210021012102210321042105210621072108210921102111211221132114211521162117211821192120212121222123212421252126212721282129213021312132213321342135213621372138213921402141214221432144214521462147214821492150215121522153215421552156215721582159216021612162216321642165216621672168216921702171217221732174217521762177217821792180218121822183218421852186218721882189219021912192219321942195219621972198219922002201220222032204220522062207220822092210221122122213221422152216221722182219222022212222222322242225222622272228222922302231223222332234223522362237223822392240224122422243224422452246224722482249225022512252225322542255225622572258225922602261226222632264226522662267226822692270227122722273227422752276227722782279228022812282228322842285228622872288
  1. #include "../SharedMemory/PhysicsClientC_API.h"
  2. #include "../SharedMemory/PhysicsDirectC_API.h"
  3. #include "../SharedMemory/SharedMemoryInProcessPhysicsC_API.h"
  4. #ifdef __APPLE__
  5. #include <Python/Python.h>
  6. #else
  7. #include <Python.h>
  8. #endif
  9. #ifdef PYBULLET_USE_NUMPY
  10. #include <numpy/arrayobject.h>
  11. #endif
  12. #if PY_MAJOR_VERSION >= 3
  13. #define PyInt_FromLong PyLong_FromLong
  14. #define PyString_FromString PyBytes_FromString
  15. #endif
  16. enum eCONNECT_METHOD {
  17. eCONNECT_GUI = 1,
  18. eCONNECT_DIRECT = 2,
  19. eCONNECT_SHARED_MEMORY = 3,
  20. };
  21. static PyObject* SpamError;
  22. static b3PhysicsClientHandle sm = 0;
  23. // Step through one timestep of the simulation
  24. static PyObject* pybullet_stepSimulation(PyObject* self, PyObject* args) {
  25. if (0 == sm) {
  26. PyErr_SetString(SpamError, "Not connected to physics server.");
  27. return NULL;
  28. }
  29. {
  30. b3SharedMemoryStatusHandle statusHandle;
  31. int statusType;
  32. if (b3CanSubmitCommand(sm)) {
  33. statusHandle = b3SubmitClientCommandAndWaitStatus(
  34. sm, b3InitStepSimulationCommand(sm));
  35. statusType = b3GetStatusType(statusHandle);
  36. }
  37. }
  38. Py_INCREF(Py_None);
  39. return Py_None;
  40. }
  41. static PyObject* pybullet_connectPhysicsServer(PyObject* self, PyObject* args) {
  42. if (0 != sm) {
  43. PyErr_SetString(SpamError,
  44. "Already connected to physics server, disconnect first.");
  45. return NULL;
  46. }
  47. {
  48. int method = eCONNECT_GUI;
  49. if (!PyArg_ParseTuple(args, "i", &method)) {
  50. PyErr_SetString(SpamError,
  51. "connectPhysicsServer expected argument eCONNECT_GUI, "
  52. "eCONNECT_DIRECT or eCONNECT_SHARED_MEMORY");
  53. return NULL;
  54. }
  55. switch (method) {
  56. case eCONNECT_GUI: {
  57. int argc = 0;
  58. char* argv[1] = {0};
  59. #ifdef __APPLE__
  60. sm = b3CreateInProcessPhysicsServerAndConnectMainThread(argc, argv);
  61. #else
  62. sm = b3CreateInProcessPhysicsServerAndConnect(argc, argv);
  63. #endif
  64. break;
  65. }
  66. case eCONNECT_DIRECT: {
  67. sm = b3ConnectPhysicsDirect();
  68. break;
  69. }
  70. case eCONNECT_SHARED_MEMORY: {
  71. sm = b3ConnectSharedMemory(SHARED_MEMORY_KEY);
  72. break;
  73. }
  74. default: {
  75. PyErr_SetString(SpamError, "connectPhysicsServer unexpected argument");
  76. return NULL;
  77. }
  78. };
  79. }
  80. Py_INCREF(Py_None);
  81. return Py_None;
  82. }
  83. static PyObject* pybullet_disconnectPhysicsServer(PyObject* self,
  84. PyObject* args) {
  85. if (0 == sm) {
  86. PyErr_SetString(SpamError, "Not connected to physics server.");
  87. return NULL;
  88. }
  89. {
  90. b3DisconnectSharedMemory(sm);
  91. sm = 0;
  92. }
  93. Py_INCREF(Py_None);
  94. return Py_None;
  95. }
  96. static PyObject* pybullet_saveWorld(PyObject* self, PyObject* args) {
  97. int size = PySequence_Size(args);
  98. const char* worldFileName = "";
  99. if (0 == sm) {
  100. PyErr_SetString(SpamError, "Not connected to physics server.");
  101. return NULL;
  102. }
  103. if (size == 1) {
  104. if (!PyArg_ParseTuple(args, "s", &worldFileName))
  105. {
  106. return NULL;
  107. }
  108. else
  109. {
  110. b3SharedMemoryCommandHandle command;
  111. b3SharedMemoryStatusHandle statusHandle;
  112. int statusType;
  113. command = b3SaveWorldCommandInit(sm, worldFileName);
  114. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
  115. statusType = b3GetStatusType(statusHandle);
  116. if (statusType != CMD_SAVE_WORLD_COMPLETED) {
  117. PyErr_SetString(SpamError, "saveWorld command execution failed.");
  118. return NULL;
  119. }
  120. Py_INCREF(Py_None);
  121. return Py_None;
  122. }
  123. }
  124. PyErr_SetString(SpamError, "Cannot execute saveWorld command.");
  125. return NULL;
  126. return NULL;
  127. }
  128. // Load a URDF file indicating the links and joints of an object
  129. // function can be called without arguments and will default
  130. // to position (0,0,1) with orientation(0,0,0,1)
  131. // els(x,y,z) or
  132. // loadURDF(pos_x, pos_y, pos_z, orn_x, orn_y, orn_z, orn_w)
  133. static PyObject* pybullet_loadURDF(PyObject* self, PyObject* args) {
  134. int size = PySequence_Size(args);
  135. int bodyIndex = -1;
  136. const char* urdfFileName = "";
  137. double startPosX = 0.0;
  138. double startPosY = 0.0;
  139. double startPosZ = 0.0;
  140. double startOrnX = 0.0;
  141. double startOrnY = 0.0;
  142. double startOrnZ = 0.0;
  143. double startOrnW = 1.0;
  144. if (0 == sm) {
  145. PyErr_SetString(SpamError, "Not connected to physics server.");
  146. return NULL;
  147. }
  148. if (size == 1) {
  149. if (!PyArg_ParseTuple(args, "s", &urdfFileName)) return NULL;
  150. }
  151. if (size == 4) {
  152. if (!PyArg_ParseTuple(args, "sddd", &urdfFileName, &startPosX, &startPosY,
  153. &startPosZ))
  154. return NULL;
  155. }
  156. if (size == 8) {
  157. if (!PyArg_ParseTuple(args, "sddddddd", &urdfFileName, &startPosX,
  158. &startPosY, &startPosZ, &startOrnX, &startOrnY,
  159. &startOrnZ, &startOrnW))
  160. return NULL;
  161. }
  162. if (strlen(urdfFileName)) {
  163. // printf("(%f, %f, %f) (%f, %f, %f, %f)\n",
  164. // startPosX,startPosY,startPosZ,startOrnX, startOrnY,startOrnZ, startOrnW);
  165. b3SharedMemoryStatusHandle statusHandle;
  166. int statusType;
  167. b3SharedMemoryCommandHandle command =
  168. b3LoadUrdfCommandInit(sm, urdfFileName);
  169. // setting the initial position, orientation and other arguments are
  170. // optional
  171. b3LoadUrdfCommandSetStartPosition(command, startPosX, startPosY, startPosZ);
  172. b3LoadUrdfCommandSetStartOrientation(command, startOrnX, startOrnY,
  173. startOrnZ, startOrnW);
  174. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
  175. statusType = b3GetStatusType(statusHandle);
  176. if (statusType != CMD_URDF_LOADING_COMPLETED) {
  177. PyErr_SetString(SpamError, "Cannot load URDF file.");
  178. return NULL;
  179. }
  180. bodyIndex = b3GetStatusBodyIndex(statusHandle);
  181. } else {
  182. PyErr_SetString(SpamError,
  183. "Empty filename, method expects 1, 4 or 8 arguments.");
  184. return NULL;
  185. }
  186. return PyLong_FromLong(bodyIndex);
  187. }
  188. static double pybullet_internalGetFloatFromSequence(PyObject* seq, int index) {
  189. double v = 0.0;
  190. PyObject* item;
  191. if (PyList_Check(seq)) {
  192. item = PyList_GET_ITEM(seq, index);
  193. v = PyFloat_AsDouble(item);
  194. } else {
  195. item = PyTuple_GET_ITEM(seq, index);
  196. v = PyFloat_AsDouble(item);
  197. }
  198. return v;
  199. }
  200. #define MAX_SDF_BODIES 512
  201. static PyObject* pybullet_loadSDF(PyObject* self, PyObject* args) {
  202. const char* sdfFileName = "";
  203. int size = PySequence_Size(args);
  204. int numBodies = 0;
  205. int i;
  206. int bodyIndicesOut[MAX_SDF_BODIES];
  207. PyObject* pylist = 0;
  208. b3SharedMemoryStatusHandle statusHandle;
  209. int statusType;
  210. b3SharedMemoryCommandHandle commandHandle;
  211. if (0 == sm) {
  212. PyErr_SetString(SpamError, "Not connected to physics server.");
  213. return NULL;
  214. }
  215. if (size == 1) {
  216. if (!PyArg_ParseTuple(args, "s", &sdfFileName)) return NULL;
  217. }
  218. commandHandle = b3LoadSdfCommandInit(sm, sdfFileName);
  219. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
  220. statusType = b3GetStatusType(statusHandle);
  221. if (statusType != CMD_SDF_LOADING_COMPLETED) {
  222. PyErr_SetString(SpamError, "Cannot load SDF file.");
  223. return NULL;
  224. }
  225. numBodies =
  226. b3GetStatusBodyIndices(statusHandle, bodyIndicesOut, MAX_SDF_BODIES);
  227. if (numBodies > MAX_SDF_BODIES) {
  228. PyErr_SetString(SpamError, "SDF exceeds body capacity");
  229. return NULL;
  230. }
  231. pylist = PyTuple_New(numBodies);
  232. if (numBodies > 0 && numBodies <= MAX_SDF_BODIES) {
  233. for (i = 0; i < numBodies; i++) {
  234. PyTuple_SetItem(pylist, i, PyInt_FromLong(bodyIndicesOut[i]));
  235. }
  236. }
  237. return pylist;
  238. }
  239. // Reset the simulation to remove all loaded objects
  240. static PyObject* pybullet_resetSimulation(PyObject* self, PyObject* args) {
  241. if (0 == sm) {
  242. PyErr_SetString(SpamError, "Not connected to physics server.");
  243. return NULL;
  244. }
  245. {
  246. b3SharedMemoryStatusHandle statusHandle;
  247. statusHandle = b3SubmitClientCommandAndWaitStatus(
  248. sm, b3InitResetSimulationCommand(sm));
  249. }
  250. Py_INCREF(Py_None);
  251. return Py_None;
  252. }
  253. static PyObject* pybullet_setJointMotorControl(PyObject* self, PyObject* args) {
  254. int size;
  255. int bodyIndex, jointIndex, controlMode;
  256. double targetPosition = 0.0;
  257. double targetVelocity = 0.0;
  258. double maxForce = 100000.0;
  259. double appliedForce = 0.0;
  260. double kp = 0.1;
  261. double kd = 1.0;
  262. int valid = 0;
  263. if (0 == sm) {
  264. PyErr_SetString(SpamError, "Not connected to physics server.");
  265. return NULL;
  266. }
  267. size = PySequence_Size(args);
  268. if (size == 4) {
  269. double targetValue = 0.0;
  270. // see switch statement below for convertsions dependent on controlMode
  271. if (!PyArg_ParseTuple(args, "iiid", &bodyIndex, &jointIndex, &controlMode,
  272. &targetValue)) {
  273. PyErr_SetString(SpamError, "Error parsing arguments");
  274. return NULL;
  275. }
  276. valid = 1;
  277. switch (controlMode) {
  278. case CONTROL_MODE_POSITION_VELOCITY_PD: {
  279. targetPosition = targetValue;
  280. break;
  281. }
  282. case CONTROL_MODE_VELOCITY: {
  283. targetVelocity = targetValue;
  284. break;
  285. }
  286. case CONTROL_MODE_TORQUE: {
  287. appliedForce = targetValue;
  288. break;
  289. }
  290. default: { valid = 0; }
  291. }
  292. }
  293. if (size == 5) {
  294. double targetValue = 0.0;
  295. // See switch statement for conversions
  296. if (!PyArg_ParseTuple(args, "iiidd", &bodyIndex, &jointIndex, &controlMode,
  297. &targetValue, &maxForce)) {
  298. PyErr_SetString(SpamError, "Error parsing arguments");
  299. return NULL;
  300. }
  301. valid = 1;
  302. switch (controlMode) {
  303. case CONTROL_MODE_POSITION_VELOCITY_PD: {
  304. targetPosition = targetValue;
  305. break;
  306. }
  307. case CONTROL_MODE_VELOCITY: {
  308. targetVelocity = targetValue;
  309. break;
  310. }
  311. case CONTROL_MODE_TORQUE: {
  312. valid = 0;
  313. break;
  314. }
  315. default: { valid = 0; }
  316. }
  317. }
  318. if (size == 6) {
  319. double gain = 0.0;
  320. double targetValue = 0.0;
  321. if (!PyArg_ParseTuple(args, "iiiddd", &bodyIndex, &jointIndex, &controlMode,
  322. &targetValue, &maxForce, &gain)) {
  323. PyErr_SetString(SpamError, "Error parsing arguments");
  324. return NULL;
  325. }
  326. valid = 1;
  327. switch (controlMode) {
  328. case CONTROL_MODE_POSITION_VELOCITY_PD: {
  329. targetPosition = targetValue;
  330. kp = gain;
  331. break;
  332. }
  333. case CONTROL_MODE_VELOCITY: {
  334. targetVelocity = targetValue;
  335. kd = gain;
  336. break;
  337. }
  338. case CONTROL_MODE_TORQUE: {
  339. valid = 0;
  340. break;
  341. }
  342. default: { valid = 0; }
  343. }
  344. }
  345. if (size == 8) {
  346. // only applicable for CONTROL_MODE_POSITION_VELOCITY_PD.
  347. if (!PyArg_ParseTuple(args, "iiiddddd", &bodyIndex, &jointIndex,
  348. &controlMode, &targetPosition, &targetVelocity,
  349. &maxForce, &kp, &kd)) {
  350. PyErr_SetString(SpamError, "Error parsing arguments");
  351. return NULL;
  352. }
  353. valid = 1;
  354. }
  355. if (valid) {
  356. int numJoints;
  357. b3SharedMemoryCommandHandle commandHandle;
  358. b3SharedMemoryStatusHandle statusHandle;
  359. struct b3JointInfo info;
  360. numJoints = b3GetNumJoints(sm, bodyIndex);
  361. if ((jointIndex >= numJoints) || (jointIndex < 0)) {
  362. PyErr_SetString(SpamError, "Joint index out-of-range.");
  363. return NULL;
  364. }
  365. if ((controlMode != CONTROL_MODE_VELOCITY) &&
  366. (controlMode != CONTROL_MODE_TORQUE) &&
  367. (controlMode != CONTROL_MODE_POSITION_VELOCITY_PD)) {
  368. PyErr_SetString(SpamError, "Illegral control mode.");
  369. return NULL;
  370. }
  371. commandHandle = b3JointControlCommandInit2(sm, bodyIndex, controlMode);
  372. b3GetJointInfo(sm, bodyIndex, jointIndex, &info);
  373. switch (controlMode) {
  374. case CONTROL_MODE_VELOCITY: {
  375. b3JointControlSetDesiredVelocity(commandHandle, info.m_uIndex,
  376. targetVelocity);
  377. b3JointControlSetKd(commandHandle, info.m_uIndex, kd);
  378. b3JointControlSetMaximumForce(commandHandle, info.m_uIndex, maxForce);
  379. break;
  380. }
  381. case CONTROL_MODE_TORQUE: {
  382. b3JointControlSetDesiredForceTorque(commandHandle, info.m_uIndex,
  383. appliedForce);
  384. break;
  385. }
  386. case CONTROL_MODE_POSITION_VELOCITY_PD: {
  387. b3JointControlSetDesiredPosition(commandHandle, info.m_qIndex,
  388. targetPosition);
  389. b3JointControlSetKp(commandHandle, info.m_uIndex, kp);
  390. b3JointControlSetDesiredVelocity(commandHandle, info.m_uIndex,
  391. targetVelocity);
  392. b3JointControlSetKd(commandHandle, info.m_uIndex, kd);
  393. b3JointControlSetMaximumForce(commandHandle, info.m_uIndex, maxForce);
  394. break;
  395. }
  396. default: {}
  397. };
  398. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
  399. Py_INCREF(Py_None);
  400. return Py_None;
  401. }
  402. PyErr_SetString(SpamError, "Error parsing arguments in setJointControl.");
  403. return NULL;
  404. }
  405. static PyObject* pybullet_setRealTimeSimulation(PyObject* self,
  406. PyObject* args) {
  407. if (0 == sm) {
  408. PyErr_SetString(SpamError, "Not connected to physics server.");
  409. return NULL;
  410. }
  411. {
  412. int enableRealTimeSimulation = 0;
  413. int ret;
  414. b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm);
  415. b3SharedMemoryStatusHandle statusHandle;
  416. if (!PyArg_ParseTuple(args, "i", &enableRealTimeSimulation)) {
  417. PyErr_SetString(
  418. SpamError,
  419. "setRealTimeSimulation expected a single value (integer).");
  420. return NULL;
  421. }
  422. ret =
  423. b3PhysicsParamSetRealTimeSimulation(command, enableRealTimeSimulation);
  424. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
  425. // ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED);
  426. }
  427. Py_INCREF(Py_None);
  428. return Py_None;
  429. }
  430. // Set the gravity of the world with (x, y, z) arguments
  431. static PyObject* pybullet_setGravity(PyObject* self, PyObject* args) {
  432. if (0 == sm) {
  433. PyErr_SetString(SpamError, "Not connected to physics server.");
  434. return NULL;
  435. }
  436. {
  437. double gravX = 0.0;
  438. double gravY = 0.0;
  439. double gravZ = -10.0;
  440. int ret;
  441. b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm);
  442. b3SharedMemoryStatusHandle statusHandle;
  443. if (!PyArg_ParseTuple(args, "ddd", &gravX, &gravY, &gravZ)) {
  444. PyErr_SetString(SpamError, "setGravity expected (x,y,z) values.");
  445. return NULL;
  446. }
  447. ret = b3PhysicsParamSetGravity(command, gravX, gravY, gravZ);
  448. // ret = b3PhysicsParamSetTimeStep(command, timeStep);
  449. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
  450. // ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED);
  451. }
  452. Py_INCREF(Py_None);
  453. return Py_None;
  454. }
  455. static PyObject* pybullet_setTimeStep(PyObject* self, PyObject* args) {
  456. if (0 == sm) {
  457. PyErr_SetString(SpamError, "Not connected to physics server.");
  458. return NULL;
  459. }
  460. {
  461. double timeStep = 0.001;
  462. int ret;
  463. b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm);
  464. b3SharedMemoryStatusHandle statusHandle;
  465. if (!PyArg_ParseTuple(args, "d", &timeStep)) {
  466. PyErr_SetString(SpamError,
  467. "setTimeStep expected a single value (double).");
  468. return NULL;
  469. }
  470. ret = b3PhysicsParamSetTimeStep(command, timeStep);
  471. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
  472. // ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED);
  473. }
  474. Py_INCREF(Py_None);
  475. return Py_None;
  476. }
  477. static PyObject *
  478. pybullet_setDefaultContactERP(PyObject* self, PyObject* args)
  479. {
  480. if (0==sm)
  481. {
  482. PyErr_SetString(SpamError, "Not connected to physics server.");
  483. return NULL;
  484. }
  485. {
  486. double defaultContactERP=0.005;
  487. int ret;
  488. b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm);
  489. b3SharedMemoryStatusHandle statusHandle;
  490. if (!PyArg_ParseTuple(args, "d", &defaultContactERP))
  491. {
  492. PyErr_SetString(SpamError, "default Contact ERP expected a single value (double).");
  493. return NULL;
  494. }
  495. ret = b3PhysicsParamSetDefaultContactERP(command, defaultContactERP);
  496. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
  497. }
  498. Py_INCREF(Py_None);
  499. return Py_None;
  500. }
  501. // Internal function used to get the base position and orientation
  502. // Orientation is returned in quaternions
  503. static int pybullet_internalGetBasePositionAndOrientation(
  504. int bodyIndex, double basePosition[3], double baseOrientation[3]) {
  505. basePosition[0] = 0.;
  506. basePosition[1] = 0.;
  507. basePosition[2] = 0.;
  508. baseOrientation[0] = 0.;
  509. baseOrientation[1] = 0.;
  510. baseOrientation[2] = 0.;
  511. baseOrientation[3] = 1.;
  512. {
  513. {
  514. b3SharedMemoryCommandHandle cmd_handle =
  515. b3RequestActualStateCommandInit(sm, bodyIndex);
  516. b3SharedMemoryStatusHandle status_handle =
  517. b3SubmitClientCommandAndWaitStatus(sm, cmd_handle);
  518. const int status_type = b3GetStatusType(status_handle);
  519. const double* actualStateQ;
  520. // const double* jointReactionForces[];
  521. if (status_type != CMD_ACTUAL_STATE_UPDATE_COMPLETED) {
  522. PyErr_SetString(SpamError, "getBasePositionAndOrientation failed.");
  523. return 0;
  524. }
  525. b3GetStatusActualState(
  526. status_handle, 0 /* body_unique_id */,
  527. 0 /* num_degree_of_freedom_q */, 0 /* num_degree_of_freedom_u */,
  528. 0 /*root_local_inertial_frame*/, &actualStateQ,
  529. 0 /* actual_state_q_dot */, 0 /* joint_reaction_forces */);
  530. // printf("joint reaction forces=");
  531. // for (i=0; i < (sizeof(jointReactionForces)/sizeof(double)); i++) {
  532. // printf("%f ", jointReactionForces[i]);
  533. // }
  534. // now, position x,y,z = actualStateQ[0],actualStateQ[1],actualStateQ[2]
  535. // and orientation x,y,z,w =
  536. // actualStateQ[3],actualStateQ[4],actualStateQ[5],actualStateQ[6]
  537. basePosition[0] = actualStateQ[0];
  538. basePosition[1] = actualStateQ[1];
  539. basePosition[2] = actualStateQ[2];
  540. baseOrientation[0] = actualStateQ[3];
  541. baseOrientation[1] = actualStateQ[4];
  542. baseOrientation[2] = actualStateQ[5];
  543. baseOrientation[3] = actualStateQ[6];
  544. }
  545. }
  546. return 1;
  547. }
  548. // Get the positions (x,y,z) and orientation (x,y,z,w) in quaternion
  549. // values for the base link of your object
  550. // Object is retrieved based on body index, which is the order
  551. // the object was loaded into the simulation (0-based)
  552. static PyObject* pybullet_getBasePositionAndOrientation(PyObject* self,
  553. PyObject* args) {
  554. int bodyIndex = -1;
  555. double basePosition[3];
  556. double baseOrientation[4];
  557. PyObject* pylistPos;
  558. PyObject* pylistOrientation;
  559. if (0 == sm) {
  560. PyErr_SetString(SpamError, "Not connected to physics server.");
  561. return NULL;
  562. }
  563. if (!PyArg_ParseTuple(args, "i", &bodyIndex)) {
  564. PyErr_SetString(SpamError, "Expected a body index (integer).");
  565. return NULL;
  566. }
  567. if (0 == pybullet_internalGetBasePositionAndOrientation(
  568. bodyIndex, basePosition, baseOrientation)) {
  569. PyErr_SetString(SpamError,
  570. "GetBasePositionAndOrientation failed (#joints/links "
  571. "exceeds maximum?).");
  572. return NULL;
  573. }
  574. {
  575. PyObject* item;
  576. int i;
  577. int num = 3;
  578. pylistPos = PyTuple_New(num);
  579. for (i = 0; i < num; i++) {
  580. item = PyFloat_FromDouble(basePosition[i]);
  581. PyTuple_SetItem(pylistPos, i, item);
  582. }
  583. }
  584. {
  585. PyObject* item;
  586. int i;
  587. int num = 4;
  588. pylistOrientation = PyTuple_New(num);
  589. for (i = 0; i < num; i++) {
  590. item = PyFloat_FromDouble(baseOrientation[i]);
  591. PyTuple_SetItem(pylistOrientation, i, item);
  592. }
  593. }
  594. {
  595. PyObject* pylist;
  596. pylist = PyTuple_New(2);
  597. PyTuple_SetItem(pylist, 0, pylistPos);
  598. PyTuple_SetItem(pylist, 1, pylistOrientation);
  599. return pylist;
  600. }
  601. }
  602. static PyObject* pybullet_getNumBodies(PyObject* self, PyObject* args)
  603. {
  604. if (0 == sm) {
  605. PyErr_SetString(SpamError, "Not connected to physics server.");
  606. return NULL;
  607. }
  608. {
  609. int numBodies = b3GetNumBodies(sm);
  610. #if PY_MAJOR_VERSION >= 3
  611. return PyLong_FromLong(numBodies);
  612. #else
  613. return PyInt_FromLong(numBodies);
  614. #endif
  615. }
  616. }
  617. static PyObject* pybullet_getBodyUniqueId(PyObject* self, PyObject* args)
  618. {
  619. if (0 == sm) {
  620. PyErr_SetString(SpamError, "Not connected to physics server.");
  621. return NULL;
  622. }
  623. {
  624. int serialIndex = -1;
  625. int bodyUniqueId = -1;
  626. if (!PyArg_ParseTuple(args, "i", &serialIndex)) {
  627. PyErr_SetString(SpamError, "Expected a serialIndex in range [0..number of bodies).");
  628. return NULL;
  629. }
  630. bodyUniqueId = b3GetBodyUniqueId(sm, serialIndex);
  631. #if PY_MAJOR_VERSION >= 3
  632. return PyLong_FromLong(bodyUniqueId);
  633. #else
  634. return PyInt_FromLong(bodyUniqueId);
  635. #endif
  636. }
  637. }
  638. static PyObject* pybullet_getBodyInfo(PyObject* self, PyObject* args)
  639. {
  640. if (0 == sm) {
  641. PyErr_SetString(SpamError, "Not connected to physics server.");
  642. return NULL;
  643. }
  644. {
  645. int bodyUniqueId= -1;
  646. int numJoints = 0;
  647. if (!PyArg_ParseTuple(args, "i", &bodyUniqueId))
  648. {
  649. PyErr_SetString(SpamError, "Expected a body unique id (integer).");
  650. return NULL;
  651. }
  652. {
  653. struct b3BodyInfo info;
  654. if (b3GetBodyInfo(sm,bodyUniqueId,&info))
  655. {
  656. PyObject* pyListJointInfo = PyTuple_New(1);
  657. PyTuple_SetItem(pyListJointInfo, 0, PyString_FromString(info.m_baseName));
  658. return pyListJointInfo;
  659. } else
  660. {
  661. PyErr_SetString(SpamError, "Couldn't get body info");
  662. return NULL;
  663. }
  664. }
  665. }
  666. PyErr_SetString(SpamError, "error in getBodyInfo.");
  667. return NULL;
  668. }
  669. // Return the number of joints in an object based on
  670. // body index; body index is based on order of sequence
  671. // the object is loaded into simulation
  672. static PyObject* pybullet_getNumJoints(PyObject* self, PyObject* args)
  673. {
  674. if (0 == sm) {
  675. PyErr_SetString(SpamError, "Not connected to physics server.");
  676. return NULL;
  677. }
  678. {
  679. int bodyIndex = -1;
  680. int numJoints = 0;
  681. if (!PyArg_ParseTuple(args, "i", &bodyIndex)) {
  682. PyErr_SetString(SpamError, "Expected a body index (integer).");
  683. return NULL;
  684. }
  685. numJoints = b3GetNumJoints(sm, bodyIndex);
  686. #if PY_MAJOR_VERSION >= 3
  687. return PyLong_FromLong(numJoints);
  688. #else
  689. return PyInt_FromLong(numJoints);
  690. #endif
  691. }
  692. }
  693. // Initalize all joint positions given a list of values
  694. static PyObject* pybullet_resetJointState(PyObject* self, PyObject* args) {
  695. int size;
  696. if (0 == sm) {
  697. PyErr_SetString(SpamError, "Not connected to physics server.");
  698. return NULL;
  699. }
  700. size = PySequence_Size(args);
  701. if (size == 3) {
  702. int bodyIndex;
  703. int jointIndex;
  704. double targetValue;
  705. if (PyArg_ParseTuple(args, "iid", &bodyIndex, &jointIndex, &targetValue)) {
  706. b3SharedMemoryCommandHandle commandHandle;
  707. b3SharedMemoryStatusHandle statusHandle;
  708. int numJoints;
  709. numJoints = b3GetNumJoints(sm, bodyIndex);
  710. if ((jointIndex >= numJoints) || (jointIndex < 0)) {
  711. PyErr_SetString(SpamError, "Joint index out-of-range.");
  712. return NULL;
  713. }
  714. commandHandle = b3CreatePoseCommandInit(sm, bodyIndex);
  715. b3CreatePoseCommandSetJointPosition(sm, commandHandle, jointIndex,
  716. targetValue);
  717. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
  718. Py_INCREF(Py_None);
  719. return Py_None;
  720. }
  721. }
  722. PyErr_SetString(SpamError, "error in resetJointState.");
  723. return NULL;
  724. }
  725. // Reset the position and orientation of the base/root link, position [x,y,z]
  726. // and orientation quaternion [x,y,z,w]
  727. static PyObject* pybullet_resetBasePositionAndOrientation(PyObject* self,
  728. PyObject* args) {
  729. int size;
  730. if (0 == sm) {
  731. PyErr_SetString(SpamError, "Not connected to physics server.");
  732. return NULL;
  733. }
  734. size = PySequence_Size(args);
  735. if (size == 3) {
  736. int bodyIndex;
  737. PyObject* posObj;
  738. PyObject* ornObj;
  739. double pos[3];
  740. double orn[4]; // as a quaternion
  741. if (PyArg_ParseTuple(args, "iOO", &bodyIndex, &posObj, &ornObj)) {
  742. b3SharedMemoryCommandHandle commandHandle;
  743. b3SharedMemoryStatusHandle statusHandle;
  744. {
  745. PyObject* seq;
  746. int len, i;
  747. seq = PySequence_Fast(posObj, "expected a sequence");
  748. len = PySequence_Size(posObj);
  749. if (len == 3) {
  750. for (i = 0; i < 3; i++) {
  751. pos[i] = pybullet_internalGetFloatFromSequence(seq, i);
  752. }
  753. } else {
  754. PyErr_SetString(SpamError, "position needs a 3 coordinates [x,y,z].");
  755. Py_DECREF(seq);
  756. return NULL;
  757. }
  758. Py_DECREF(seq);
  759. }
  760. {
  761. PyObject* seq;
  762. int len, i;
  763. seq = PySequence_Fast(ornObj, "expected a sequence");
  764. len = PySequence_Size(ornObj);
  765. if (len == 4) {
  766. for (i = 0; i < 4; i++) {
  767. orn[i] = pybullet_internalGetFloatFromSequence(seq, i);
  768. }
  769. } else {
  770. PyErr_SetString(
  771. SpamError,
  772. "orientation needs a 4 coordinates, quaternion [x,y,z,w].");
  773. Py_DECREF(seq);
  774. return NULL;
  775. }
  776. Py_DECREF(seq);
  777. }
  778. commandHandle = b3CreatePoseCommandInit(sm, bodyIndex);
  779. b3CreatePoseCommandSetBasePosition(commandHandle, pos[0], pos[1], pos[2]);
  780. b3CreatePoseCommandSetBaseOrientation(commandHandle, orn[0], orn[1],
  781. orn[2], orn[3]);
  782. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
  783. Py_INCREF(Py_None);
  784. return Py_None;
  785. }
  786. }
  787. PyErr_SetString(SpamError, "error in resetJointState.");
  788. return NULL;
  789. }
  790. // Get the a single joint info for a specific bodyIndex
  791. //
  792. // Args:
  793. // bodyIndex - integer indicating body in simulation
  794. // jointIndex - integer indicating joint for a specific body
  795. //
  796. // Joint information includes:
  797. // index, name, type, q-index, u-index,
  798. // flags, joint damping, joint friction
  799. //
  800. // The format of the returned list is
  801. // [int, str, int, int, int, int, float, float]
  802. //
  803. // TODO(hellojas): get joint positions for a body
  804. static PyObject* pybullet_getJointInfo(PyObject* self, PyObject* args) {
  805. PyObject* pyListJointInfo;
  806. struct b3JointInfo info;
  807. int bodyIndex = -1;
  808. int jointIndex = -1;
  809. int jointInfoSize = 8; // size of struct b3JointInfo
  810. int size = PySequence_Size(args);
  811. if (0 == sm) {
  812. PyErr_SetString(SpamError, "Not connected to physics server.");
  813. return NULL;
  814. }
  815. if (size == 2) // get body index and joint index
  816. {
  817. if (PyArg_ParseTuple(args, "ii", &bodyIndex, &jointIndex)) {
  818. // printf("body index = %d, joint index =%d\n", bodyIndex, jointIndex);
  819. pyListJointInfo = PyTuple_New(jointInfoSize);
  820. if (b3GetJointInfo(sm, bodyIndex, jointIndex, &info)) {
  821. // printf("Joint%d %s, type %d, at q-index %d and u-index %d\n",
  822. // info.m_jointIndex,
  823. // info.m_jointName,
  824. // info.m_jointType,
  825. // info.m_qIndex,
  826. // info.m_uIndex);
  827. // printf(" flags=%d jointDamping=%f jointFriction=%f\n",
  828. // info.m_flags,
  829. // info.m_jointDamping,
  830. // info.m_jointFriction);
  831. PyTuple_SetItem(pyListJointInfo, 0, PyInt_FromLong(info.m_jointIndex));
  832. PyTuple_SetItem(pyListJointInfo, 1,
  833. PyString_FromString(info.m_jointName));
  834. PyTuple_SetItem(pyListJointInfo, 2, PyInt_FromLong(info.m_jointType));
  835. PyTuple_SetItem(pyListJointInfo, 3, PyInt_FromLong(info.m_qIndex));
  836. PyTuple_SetItem(pyListJointInfo, 4, PyInt_FromLong(info.m_uIndex));
  837. PyTuple_SetItem(pyListJointInfo, 5, PyInt_FromLong(info.m_flags));
  838. PyTuple_SetItem(pyListJointInfo, 6,
  839. PyFloat_FromDouble(info.m_jointDamping));
  840. PyTuple_SetItem(pyListJointInfo, 7,
  841. PyFloat_FromDouble(info.m_jointFriction));
  842. return pyListJointInfo;
  843. } else {
  844. PyErr_SetString(SpamError, "GetJointInfo failed.");
  845. return NULL;
  846. }
  847. }
  848. }
  849. Py_INCREF(Py_None);
  850. return Py_None;
  851. }
  852. // Returns the state of a specific joint in a given bodyIndex
  853. //
  854. // Args:
  855. // bodyIndex - integer indicating body in simulation
  856. // jointIndex - integer indicating joint for a specific body
  857. //
  858. // The state of a joint includes the following:
  859. // position, velocity, force torque (6 values), and motor torque
  860. // The returned pylist is an array of [float, float, float[6], float]
  861. // TODO(hellojas): check accuracy of position and velocity
  862. // TODO(hellojas): check force torque values
  863. static PyObject* pybullet_getJointState(PyObject* self, PyObject* args) {
  864. PyObject* pyListJointForceTorque;
  865. PyObject* pyListJointState;
  866. struct b3JointSensorState sensorState;
  867. int bodyIndex = -1;
  868. int jointIndex = -1;
  869. int sensorStateSize = 4; // size of struct b3JointSensorState
  870. int forceTorqueSize = 6; // size of force torque list from b3JointSensorState
  871. int j;
  872. int size = PySequence_Size(args);
  873. if (0 == sm) {
  874. PyErr_SetString(SpamError, "Not connected to physics server.");
  875. return NULL;
  876. }
  877. if (size == 2) // get body index and joint index
  878. {
  879. if (PyArg_ParseTuple(args, "ii", &bodyIndex, &jointIndex)) {
  880. int status_type = 0;
  881. b3SharedMemoryCommandHandle cmd_handle;
  882. b3SharedMemoryStatusHandle status_handle;
  883. if (bodyIndex < 0) {
  884. PyErr_SetString(SpamError, "getJointState failed; invalid bodyIndex");
  885. return NULL;
  886. }
  887. if (jointIndex < 0) {
  888. PyErr_SetString(SpamError, "getJointState failed; invalid jointIndex");
  889. return NULL;
  890. }
  891. cmd_handle =
  892. b3RequestActualStateCommandInit(sm, bodyIndex);
  893. status_handle =
  894. b3SubmitClientCommandAndWaitStatus(sm, cmd_handle);
  895. status_type = b3GetStatusType(status_handle);
  896. if (status_type != CMD_ACTUAL_STATE_UPDATE_COMPLETED) {
  897. PyErr_SetString(SpamError, "getJointState failed.");
  898. return NULL;
  899. }
  900. pyListJointState = PyTuple_New(sensorStateSize);
  901. pyListJointForceTorque = PyTuple_New(forceTorqueSize);
  902. b3GetJointState(sm, status_handle, jointIndex, &sensorState);
  903. PyTuple_SetItem(pyListJointState, 0,
  904. PyFloat_FromDouble(sensorState.m_jointPosition));
  905. PyTuple_SetItem(pyListJointState, 1,
  906. PyFloat_FromDouble(sensorState.m_jointVelocity));
  907. for (j = 0; j < forceTorqueSize; j++) {
  908. PyTuple_SetItem(pyListJointForceTorque, j,
  909. PyFloat_FromDouble(sensorState.m_jointForceTorque[j]));
  910. }
  911. PyTuple_SetItem(pyListJointState, 2, pyListJointForceTorque);
  912. PyTuple_SetItem(pyListJointState, 3,
  913. PyFloat_FromDouble(sensorState.m_jointMotorTorque));
  914. return pyListJointState;
  915. }
  916. } else {
  917. PyErr_SetString(
  918. SpamError,
  919. "getJointState expects 2 arguments (objectUniqueId and joint index).");
  920. return NULL;
  921. }
  922. Py_INCREF(Py_None);
  923. return Py_None;
  924. }
  925. static PyObject* pybullet_getLinkState(PyObject* self, PyObject* args) {
  926. PyObject* pyLinkState;
  927. PyObject* pyLinkStateWorldPosition;
  928. PyObject* pyLinkStateWorldOrientation;
  929. PyObject* pyLinkStateLocalInertialPosition;
  930. PyObject* pyLinkStateLocalInertialOrientation;
  931. struct b3LinkState linkState;
  932. int bodyIndex = -1;
  933. int linkIndex = -1;
  934. int i;
  935. if (0 == sm) {
  936. PyErr_SetString(SpamError, "Not connected to physics server.");
  937. return NULL;
  938. }
  939. if (PySequence_Size(args) == 2) // body index and link index
  940. {
  941. if (PyArg_ParseTuple(args, "ii", &bodyIndex, &linkIndex)) {
  942. int status_type = 0;
  943. b3SharedMemoryCommandHandle cmd_handle;
  944. b3SharedMemoryStatusHandle status_handle;
  945. if (bodyIndex < 0) {
  946. PyErr_SetString(SpamError, "getLinkState failed; invalid bodyIndex");
  947. return NULL;
  948. }
  949. if (linkIndex < 0) {
  950. PyErr_SetString(SpamError, "getLinkState failed; invalid jointIndex");
  951. return NULL;
  952. }
  953. cmd_handle =
  954. b3RequestActualStateCommandInit(sm, bodyIndex);
  955. status_handle =
  956. b3SubmitClientCommandAndWaitStatus(sm, cmd_handle);
  957. status_type = b3GetStatusType(status_handle);
  958. if (status_type != CMD_ACTUAL_STATE_UPDATE_COMPLETED) {
  959. PyErr_SetString(SpamError, "getLinkState failed.");
  960. return NULL;
  961. }
  962. b3GetLinkState(sm, status_handle, linkIndex, &linkState);
  963. pyLinkStateWorldPosition = PyTuple_New(3);
  964. for (i = 0; i < 3; ++i) {
  965. PyTuple_SetItem(pyLinkStateWorldPosition, i,
  966. PyFloat_FromDouble(linkState.m_worldPosition[i]));
  967. }
  968. pyLinkStateWorldOrientation = PyTuple_New(4);
  969. for (i = 0; i < 4; ++i) {
  970. PyTuple_SetItem(pyLinkStateWorldOrientation, i,
  971. PyFloat_FromDouble(linkState.m_worldOrientation[i]));
  972. }
  973. pyLinkStateLocalInertialPosition = PyTuple_New(3);
  974. for (i = 0; i < 3; ++i) {
  975. PyTuple_SetItem(pyLinkStateLocalInertialPosition, i,
  976. PyFloat_FromDouble(linkState.m_localInertialPosition[i]));
  977. }
  978. pyLinkStateLocalInertialOrientation = PyTuple_New(4);
  979. for (i = 0; i < 4; ++i) {
  980. PyTuple_SetItem(pyLinkStateLocalInertialOrientation, i,
  981. PyFloat_FromDouble(linkState.m_localInertialOrientation[i]));
  982. }
  983. pyLinkState = PyTuple_New(4);
  984. PyTuple_SetItem(pyLinkState, 0, pyLinkStateWorldPosition);
  985. PyTuple_SetItem(pyLinkState, 1, pyLinkStateWorldOrientation);
  986. PyTuple_SetItem(pyLinkState, 2, pyLinkStateLocalInertialPosition);
  987. PyTuple_SetItem(pyLinkState, 3, pyLinkStateLocalInertialOrientation);
  988. return pyLinkState;
  989. }
  990. } else {
  991. PyErr_SetString(
  992. SpamError,
  993. "getLinkState expects 2 arguments (objectUniqueId and link index).");
  994. return NULL;
  995. }
  996. Py_INCREF(Py_None);
  997. return Py_None;
  998. }
  999. // internal function to set a float matrix[16]
  1000. // used to initialize camera position with
  1001. // a view and projection matrix in renderImage()
  1002. //
  1003. // // Args:
  1004. // matrix - float[16] which will be set by values from objMat
  1005. static int pybullet_internalSetMatrix(PyObject* objMat, float matrix[16]) {
  1006. int i, len;
  1007. PyObject* seq;
  1008. seq = PySequence_Fast(objMat, "expected a sequence");
  1009. len = PySequence_Size(objMat);
  1010. if (len == 16) {
  1011. for (i = 0; i < len; i++) {
  1012. matrix[i] = pybullet_internalGetFloatFromSequence(seq, i);
  1013. }
  1014. Py_DECREF(seq);
  1015. return 1;
  1016. }
  1017. Py_DECREF(seq);
  1018. return 0;
  1019. }
  1020. // internal function to set a float vector[3]
  1021. // used to initialize camera position with
  1022. // a view and projection matrix in renderImage()
  1023. //
  1024. // // Args:
  1025. // vector - float[3] which will be set by values from objMat
  1026. static int pybullet_internalSetVector(PyObject* objMat, float vector[3]) {
  1027. int i, len;
  1028. PyObject* seq;
  1029. seq = PySequence_Fast(objMat, "expected a sequence");
  1030. len = PySequence_Size(objMat);
  1031. if (len == 3) {
  1032. for (i = 0; i < len; i++) {
  1033. vector[i] = pybullet_internalGetFloatFromSequence(seq, i);
  1034. }
  1035. Py_DECREF(seq);
  1036. return 1;
  1037. }
  1038. Py_DECREF(seq);
  1039. return 0;
  1040. }
  1041. // vector - double[3] which will be set by values from obVec
  1042. static int pybullet_internalSetVectord(PyObject* obVec, double vector[3]) {
  1043. int i, len;
  1044. PyObject* seq;
  1045. seq = PySequence_Fast(obVec, "expected a sequence");
  1046. len = PySequence_Size(obVec);
  1047. if (len == 3) {
  1048. for (i = 0; i < len; i++) {
  1049. vector[i] = pybullet_internalGetFloatFromSequence(seq, i);
  1050. }
  1051. Py_DECREF(seq);
  1052. return 1;
  1053. }
  1054. Py_DECREF(seq);
  1055. return 0;
  1056. }
  1057. // vector - double[3] which will be set by values from obVec
  1058. static int pybullet_internalSetVector4(PyObject* obVec, double vector[4]) {
  1059. int i, len;
  1060. PyObject* seq;
  1061. seq = PySequence_Fast(obVec, "expected a sequence");
  1062. len = PySequence_Size(obVec);
  1063. if (len == 4) {
  1064. for (i = 0; i < len; i++) {
  1065. vector[i] = pybullet_internalGetFloatFromSequence(seq, i);
  1066. }
  1067. Py_DECREF(seq);
  1068. return 1;
  1069. }
  1070. Py_DECREF(seq);
  1071. return 0;
  1072. }
  1073. static PyObject* pybullet_getContactPointData(PyObject* self, PyObject* args) {
  1074. int size = PySequence_Size(args);
  1075. int objectUniqueIdA = -1;
  1076. int objectUniqueIdB = -1;
  1077. b3SharedMemoryCommandHandle commandHandle;
  1078. struct b3ContactInformation contactPointData;
  1079. b3SharedMemoryStatusHandle statusHandle;
  1080. int statusType;
  1081. int i;
  1082. PyObject* pyResultList = 0;
  1083. if (size == 1) {
  1084. if (!PyArg_ParseTuple(args, "i", &objectUniqueIdA)) {
  1085. PyErr_SetString(SpamError, "Error parsing object unique id");
  1086. return NULL;
  1087. }
  1088. }
  1089. if (size == 2) {
  1090. if (!PyArg_ParseTuple(args, "ii", &objectUniqueIdA, &objectUniqueIdB)) {
  1091. PyErr_SetString(SpamError, "Error parsing object unique id");
  1092. return NULL;
  1093. }
  1094. }
  1095. commandHandle = b3InitRequestContactPointInformation(sm);
  1096. b3SetContactFilterBodyA(commandHandle, objectUniqueIdA);
  1097. b3SetContactFilterBodyB(commandHandle, objectUniqueIdB);
  1098. b3SubmitClientCommand(sm, commandHandle);
  1099. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
  1100. statusType = b3GetStatusType(statusHandle);
  1101. if (statusType == CMD_CONTACT_POINT_INFORMATION_COMPLETED) {
  1102. /*
  1103. 0 int m_contactFlags;
  1104. 1 int m_bodyUniqueIdA;
  1105. 2 int m_bodyUniqueIdB;
  1106. 3 int m_linkIndexA;
  1107. 4 int m_linkIndexB;
  1108. 5-6-7 double m_positionOnAInWS[3];//contact point location on object A,
  1109. in world space coordinates
  1110. 8-9-10 double m_positionOnBInWS[3];//contact point location on object
  1111. A, in world space coordinates
  1112. 11-12-13 double m_contactNormalOnBInWS[3];//the separating contact
  1113. normal, pointing from object B towards object A
  1114. 14 double m_contactDistance;//negative number is penetration, positive
  1115. is distance.
  1116. 15 double m_normalForce;
  1117. */
  1118. b3GetContactPointInformation(sm, &contactPointData);
  1119. pyResultList = PyTuple_New(contactPointData.m_numContactPoints);
  1120. for (i = 0; i < contactPointData.m_numContactPoints; i++) {
  1121. PyObject* contactObList = PyTuple_New(16); // see above 16 fields
  1122. PyObject* item;
  1123. item =
  1124. PyInt_FromLong(contactPointData.m_contactPointData[i].m_contactFlags);
  1125. PyTuple_SetItem(contactObList, 0, item);
  1126. item = PyInt_FromLong(
  1127. contactPointData.m_contactPointData[i].m_bodyUniqueIdA);
  1128. PyTuple_SetItem(contactObList, 1, item);
  1129. item = PyInt_FromLong(
  1130. contactPointData.m_contactPointData[i].m_bodyUniqueIdB);
  1131. PyTuple_SetItem(contactObList, 2, item);
  1132. item =
  1133. PyInt_FromLong(contactPointData.m_contactPointData[i].m_linkIndexA);
  1134. PyTuple_SetItem(contactObList, 3, item);
  1135. item =
  1136. PyInt_FromLong(contactPointData.m_contactPointData[i].m_linkIndexB);
  1137. PyTuple_SetItem(contactObList, 4, item);
  1138. item = PyFloat_FromDouble(
  1139. contactPointData.m_contactPointData[i].m_positionOnAInWS[0]);
  1140. PyTuple_SetItem(contactObList, 5, item);
  1141. item = PyFloat_FromDouble(
  1142. contactPointData.m_contactPointData[i].m_positionOnAInWS[1]);
  1143. PyTuple_SetItem(contactObList, 6, item);
  1144. item = PyFloat_FromDouble(
  1145. contactPointData.m_contactPointData[i].m_positionOnAInWS[2]);
  1146. PyTuple_SetItem(contactObList, 7, item);
  1147. item = PyFloat_FromDouble(
  1148. contactPointData.m_contactPointData[i].m_positionOnBInWS[0]);
  1149. PyTuple_SetItem(contactObList, 8, item);
  1150. item = PyFloat_FromDouble(
  1151. contactPointData.m_contactPointData[i].m_positionOnBInWS[1]);
  1152. PyTuple_SetItem(contactObList, 9, item);
  1153. item = PyFloat_FromDouble(
  1154. contactPointData.m_contactPointData[i].m_positionOnBInWS[2]);
  1155. PyTuple_SetItem(contactObList, 10, item);
  1156. item = PyFloat_FromDouble(
  1157. contactPointData.m_contactPointData[i].m_contactNormalOnBInWS[0]);
  1158. PyTuple_SetItem(contactObList, 11, item);
  1159. item = PyFloat_FromDouble(
  1160. contactPointData.m_contactPointData[i].m_contactNormalOnBInWS[1]);
  1161. PyTuple_SetItem(contactObList, 12, item);
  1162. item = PyFloat_FromDouble(
  1163. contactPointData.m_contactPointData[i].m_contactNormalOnBInWS[2]);
  1164. PyTuple_SetItem(contactObList, 13, item);
  1165. item = PyFloat_FromDouble(
  1166. contactPointData.m_contactPointData[i].m_contactDistance);
  1167. PyTuple_SetItem(contactObList, 14, item);
  1168. item = PyFloat_FromDouble(
  1169. contactPointData.m_contactPointData[i].m_normalForce);
  1170. PyTuple_SetItem(contactObList, 15, item);
  1171. PyTuple_SetItem(pyResultList, i, contactObList);
  1172. }
  1173. return pyResultList;
  1174. }
  1175. Py_INCREF(Py_None);
  1176. return Py_None;
  1177. }
  1178. // Render an image from the current timestep of the simulation
  1179. //
  1180. // Examples:
  1181. // renderImage() - default image resolution and camera position
  1182. // renderImage(w, h) - image resolution of (w,h), default camera
  1183. // renderImage(w, h, view[16], projection[16]) - set both resolution
  1184. // and initialize camera to the view and projection values
  1185. // renderImage(w, h, cameraPos, targetPos, cameraUp, nearVal, farVal) - set
  1186. // resolution and initialize camera based on camera position, target
  1187. // position, camera up and fulstrum near/far values.
  1188. // renderImage(w, h, cameraPos, targetPos, cameraUp, nearVal, farVal, fov) -
  1189. // set resolution and initialize camera based on camera position, target
  1190. // position, camera up, fulstrum near/far values and camera field of view.
  1191. // renderImage(w, h, targetPos, distance, yaw, pitch, upAxisIndex, nearVal,
  1192. // farVal, fov)
  1193. //
  1194. // Note if the (w,h) is too small, the objects may not appear based on
  1195. // where the camera has been set
  1196. //
  1197. // TODO(hellojas): fix image is cut off at head
  1198. // TODO(hellojas): should we add check to give minimum image resolution
  1199. // to see object based on camera position?
  1200. static PyObject* pybullet_renderImage(PyObject* self, PyObject* args) {
  1201. /// request an image from a simulated camera, using a software renderer.
  1202. struct b3CameraImageData imageData;
  1203. PyObject* objViewMat, *objProjMat;
  1204. PyObject* objCameraPos, *objTargetPos, *objCameraUp;
  1205. int width, height;
  1206. int size = PySequence_Size(args);
  1207. float viewMatrix[16];
  1208. float projectionMatrix[16];
  1209. float cameraPos[3];
  1210. float targetPos[3];
  1211. float cameraUp[3];
  1212. float left, right, bottom, top, aspect;
  1213. float nearVal, farVal;
  1214. float fov;
  1215. // inialize cmd
  1216. b3SharedMemoryCommandHandle command;
  1217. if (0 == sm) {
  1218. PyErr_SetString(SpamError, "Not connected to physics server.");
  1219. return NULL;
  1220. }
  1221. command = b3InitRequestCameraImage(sm);
  1222. if (size == 2) // only set camera resolution
  1223. {
  1224. if (PyArg_ParseTuple(args, "ii", &width, &height)) {
  1225. b3RequestCameraImageSetPixelResolution(command, width, height);
  1226. }
  1227. } else if (size == 4) // set camera resolution and view and projection matrix
  1228. {
  1229. if (PyArg_ParseTuple(args, "iiOO", &width, &height, &objViewMat,
  1230. &objProjMat)) {
  1231. b3RequestCameraImageSetPixelResolution(command, width, height);
  1232. // set camera matrices only if set matrix function succeeds
  1233. if (pybullet_internalSetMatrix(objViewMat, viewMatrix) &&
  1234. (pybullet_internalSetMatrix(objProjMat, projectionMatrix))) {
  1235. b3RequestCameraImageSetCameraMatrices(command, viewMatrix,
  1236. projectionMatrix);
  1237. } else {
  1238. PyErr_SetString(SpamError, "Error parsing view or projection matrix.");
  1239. return NULL;
  1240. }
  1241. }
  1242. } else if (size == 7) // set camera resolution, camera positions and
  1243. // calculate projection using near/far values.
  1244. {
  1245. if (PyArg_ParseTuple(args, "iiOOOff", &width, &height, &objCameraPos,
  1246. &objTargetPos, &objCameraUp, &nearVal, &farVal)) {
  1247. b3RequestCameraImageSetPixelResolution(command, width, height);
  1248. if (pybullet_internalSetVector(objCameraPos, cameraPos) &&
  1249. pybullet_internalSetVector(objTargetPos, targetPos) &&
  1250. pybullet_internalSetVector(objCameraUp, cameraUp)) {
  1251. b3RequestCameraImageSetViewMatrix(command, cameraPos, targetPos,
  1252. cameraUp);
  1253. } else {
  1254. PyErr_SetString(SpamError,
  1255. "Error parsing camera position, target or up.");
  1256. return NULL;
  1257. }
  1258. aspect = width / height;
  1259. left = -aspect * nearVal;
  1260. right = aspect * nearVal;
  1261. bottom = -nearVal;
  1262. top = nearVal;
  1263. b3RequestCameraImageSetProjectionMatrix(command, left, right, bottom, top,
  1264. nearVal, farVal);
  1265. }
  1266. } else if (size == 8) // set camera resolution, camera positions and
  1267. // calculate projection using near/far values & field
  1268. // of view
  1269. {
  1270. if (PyArg_ParseTuple(args, "iiOOOfff", &width, &height, &objCameraPos,
  1271. &objTargetPos, &objCameraUp, &nearVal, &farVal,
  1272. &fov)) {
  1273. b3RequestCameraImageSetPixelResolution(command, width, height);
  1274. if (pybullet_internalSetVector(objCameraPos, cameraPos) &&
  1275. pybullet_internalSetVector(objTargetPos, targetPos) &&
  1276. pybullet_internalSetVector(objCameraUp, cameraUp)) {
  1277. b3RequestCameraImageSetViewMatrix(command, cameraPos, targetPos,
  1278. cameraUp);
  1279. } else {
  1280. PyErr_SetString(SpamError,
  1281. "Error parsing camera position, target or up.");
  1282. return NULL;
  1283. }
  1284. aspect = width / height;
  1285. b3RequestCameraImageSetFOVProjectionMatrix(command, fov, aspect, nearVal,
  1286. farVal);
  1287. }
  1288. } else if (size == 11) {
  1289. int upAxisIndex = 1;
  1290. float camDistance, yaw, pitch, roll;
  1291. // sometimes more arguments are better :-)
  1292. if (PyArg_ParseTuple(args, "iiOffffifff", &width, &height, &objTargetPos,
  1293. &camDistance, &yaw, &pitch, &roll, &upAxisIndex,
  1294. &nearVal, &farVal, &fov)) {
  1295. b3RequestCameraImageSetPixelResolution(command, width, height);
  1296. if (pybullet_internalSetVector(objTargetPos, targetPos)) {
  1297. // printf("width = %d, height = %d, targetPos = %f,%f,%f, distance = %f,
  1298. // yaw = %f, pitch = %f, upAxisIndex = %d, near=%f, far=%f,
  1299. // fov=%f\n",width,height,targetPos[0],targetPos[1],targetPos[2],camDistance,yaw,pitch,upAxisIndex,nearVal,farVal,fov);
  1300. b3RequestCameraImageSetViewMatrix2(command, targetPos, camDistance, yaw,
  1301. pitch, roll, upAxisIndex);
  1302. aspect = width / height;
  1303. b3RequestCameraImageSetFOVProjectionMatrix(command, fov, aspect,
  1304. nearVal, farVal);
  1305. } else {
  1306. PyErr_SetString(SpamError, "Error parsing camera target pos");
  1307. }
  1308. } else {
  1309. PyErr_SetString(SpamError, "Error parsing arguments");
  1310. }
  1311. } else {
  1312. PyErr_SetString(SpamError, "Invalid number of args passed to renderImage.");
  1313. return NULL;
  1314. }
  1315. if (b3CanSubmitCommand(sm)) {
  1316. b3SharedMemoryStatusHandle statusHandle;
  1317. int statusType;
  1318. // b3RequestCameraImageSelectRenderer(command,ER_BULLET_HARDWARE_OPENGL);
  1319. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
  1320. statusType = b3GetStatusType(statusHandle);
  1321. if (statusType == CMD_CAMERA_IMAGE_COMPLETED) {
  1322. PyObject* item2;
  1323. PyObject* pyResultList; // store 4 elements in this result: width,
  1324. // height, rgbData, depth
  1325. #ifdef PYBULLET_USE_NUMPY
  1326. PyObject* pyRGB;
  1327. PyObject* pyDep;
  1328. PyObject* pySeg;
  1329. int i, j, p;
  1330. b3GetCameraImageData(sm, &imageData);
  1331. // TODO(hellojas): error handling if image size is 0
  1332. pyResultList = PyTuple_New(5);
  1333. PyTuple_SetItem(pyResultList, 0, PyInt_FromLong(imageData.m_pixelWidth));
  1334. PyTuple_SetItem(pyResultList, 1, PyInt_FromLong(imageData.m_pixelHeight));
  1335. int bytesPerPixel = 4; // Red, Green, Blue, and Alpha each 8 bit values
  1336. npy_intp rgb_dims[3] = {imageData.m_pixelHeight, imageData.m_pixelWidth,
  1337. bytesPerPixel};
  1338. npy_intp dep_dims[2] = {imageData.m_pixelHeight, imageData.m_pixelWidth};
  1339. npy_intp seg_dims[2] = {imageData.m_pixelHeight, imageData.m_pixelWidth};
  1340. pyRGB = PyArray_SimpleNew(3, rgb_dims, NPY_UINT8);
  1341. pyDep = PyArray_SimpleNew(2, dep_dims, NPY_FLOAT32);
  1342. pySeg = PyArray_SimpleNew(2, seg_dims, NPY_INT32);
  1343. memcpy(PyArray_DATA(pyRGB), imageData.m_rgbColorData,
  1344. imageData.m_pixelHeight * imageData.m_pixelWidth * bytesPerPixel);
  1345. memcpy(PyArray_DATA(pyDep), imageData.m_depthValues,
  1346. imageData.m_pixelHeight * imageData.m_pixelWidth);
  1347. memcpy(PyArray_DATA(pySeg), imageData.m_segmentationMaskValues,
  1348. imageData.m_pixelHeight * imageData.m_pixelWidth);
  1349. PyTuple_SetItem(pyResultList, 2, pyRGB);
  1350. PyTuple_SetItem(pyResultList, 3, pyDep);
  1351. PyTuple_SetItem(pyResultList, 4, pySeg);
  1352. #else//PYBULLET_USE_NUMPY
  1353. PyObject* pylistRGB;
  1354. PyObject* pylistDep;
  1355. PyObject* pylistSeg;
  1356. int i, j, p;
  1357. b3GetCameraImageData(sm, &imageData);
  1358. // TODO(hellojas): error handling if image size is 0
  1359. pyResultList = PyTuple_New(5);
  1360. PyTuple_SetItem(pyResultList, 0, PyInt_FromLong(imageData.m_pixelWidth));
  1361. PyTuple_SetItem(pyResultList, 1, PyInt_FromLong(imageData.m_pixelHeight));
  1362. {
  1363. PyObject* item;
  1364. int bytesPerPixel = 4; // Red, Green, Blue, and Alpha each 8 bit values
  1365. int num =
  1366. bytesPerPixel * imageData.m_pixelWidth * imageData.m_pixelHeight;
  1367. pylistRGB = PyTuple_New(num);
  1368. pylistDep =
  1369. PyTuple_New(imageData.m_pixelWidth * imageData.m_pixelHeight);
  1370. pylistSeg =
  1371. PyTuple_New(imageData.m_pixelWidth * imageData.m_pixelHeight);
  1372. for (i = 0; i < imageData.m_pixelWidth; i++) {
  1373. for (j = 0; j < imageData.m_pixelHeight; j++) {
  1374. // TODO(hellojas): validate depth values make sense
  1375. int depIndex = i + j * imageData.m_pixelWidth;
  1376. {
  1377. item = PyFloat_FromDouble(imageData.m_depthValues[depIndex]);
  1378. PyTuple_SetItem(pylistDep, depIndex, item);
  1379. }
  1380. {
  1381. item2 =
  1382. PyLong_FromLong(imageData.m_segmentationMaskValues[depIndex]);
  1383. PyTuple_SetItem(pylistSeg, depIndex, item2);
  1384. }
  1385. for (p = 0; p < bytesPerPixel; p++) {
  1386. int pixelIndex =
  1387. bytesPerPixel * (i + j * imageData.m_pixelWidth) + p;
  1388. item = PyInt_FromLong(imageData.m_rgbColorData[pixelIndex]);
  1389. PyTuple_SetItem(pylistRGB, pixelIndex, item);
  1390. }
  1391. }
  1392. }
  1393. }
  1394. PyTuple_SetItem(pyResultList, 2, pylistRGB);
  1395. PyTuple_SetItem(pyResultList, 3, pylistDep);
  1396. PyTuple_SetItem(pyResultList, 4, pylistSeg);
  1397. return pyResultList;
  1398. #endif//PYBULLET_USE_NUMPY
  1399. return pyResultList;
  1400. }
  1401. }
  1402. Py_INCREF(Py_None);
  1403. return Py_None;
  1404. }
  1405. static PyObject* pybullet_applyExternalForce(PyObject* self, PyObject* args) {
  1406. if (0 == sm) {
  1407. PyErr_SetString(SpamError, "Not connected to physics server.");
  1408. return NULL;
  1409. }
  1410. {
  1411. int objectUniqueId, linkIndex, flags;
  1412. double force[3];
  1413. double position[3] = {0.0, 0.0, 0.0};
  1414. PyObject* forceObj, *posObj;
  1415. b3SharedMemoryCommandHandle command;
  1416. b3SharedMemoryStatusHandle statusHandle;
  1417. int size = PySequence_Size(args);
  1418. if (size == 5) {
  1419. if (!PyArg_ParseTuple(args, "iiOOi", &objectUniqueId, &linkIndex,
  1420. &forceObj, &posObj, &flags)) {
  1421. PyErr_SetString(SpamError, "applyBaseForce couldn't parse arguments");
  1422. return NULL;
  1423. }
  1424. } else {
  1425. PyErr_SetString(SpamError,
  1426. "applyBaseForce needs 5 arguments: objectUniqueId, "
  1427. "linkIndex (-1 for base/root link), force [x,y,z], "
  1428. "position [x,y,z], flags");
  1429. return NULL;
  1430. }
  1431. {
  1432. PyObject* seq;
  1433. int len, i;
  1434. seq = PySequence_Fast(forceObj, "expected a sequence");
  1435. len = PySequence_Size(forceObj);
  1436. if (len == 3) {
  1437. for (i = 0; i < 3; i++) {
  1438. force[i] = pybullet_internalGetFloatFromSequence(seq, i);
  1439. }
  1440. } else {
  1441. PyErr_SetString(SpamError, "force needs a 3 coordinates [x,y,z].");
  1442. Py_DECREF(seq);
  1443. return NULL;
  1444. }
  1445. Py_DECREF(seq);
  1446. }
  1447. {
  1448. PyObject* seq;
  1449. int len, i;
  1450. seq = PySequence_Fast(posObj, "expected a sequence");
  1451. len = PySequence_Size(posObj);
  1452. if (len == 3) {
  1453. for (i = 0; i < 3; i++) {
  1454. position[i] = pybullet_internalGetFloatFromSequence(seq, i);
  1455. }
  1456. } else {
  1457. PyErr_SetString(SpamError, "position needs a 3 coordinates [x,y,z].");
  1458. Py_DECREF(seq);
  1459. return NULL;
  1460. }
  1461. Py_DECREF(seq);
  1462. }
  1463. if ((flags != EF_WORLD_FRAME) && (flags != EF_LINK_FRAME)) {
  1464. PyErr_SetString(SpamError,
  1465. "flag has to be either WORLD_FRAME or LINK_FRAME");
  1466. return NULL;
  1467. }
  1468. command = b3ApplyExternalForceCommandInit(sm);
  1469. b3ApplyExternalForce(command, objectUniqueId, linkIndex, force, position,
  1470. flags);
  1471. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
  1472. }
  1473. Py_INCREF(Py_None);
  1474. return Py_None;
  1475. }
  1476. static PyObject* pybullet_applyExternalTorque(PyObject* self, PyObject* args) {
  1477. if (0 == sm) {
  1478. PyErr_SetString(SpamError, "Not connected to physics server.");
  1479. return NULL;
  1480. }
  1481. {
  1482. int objectUniqueId, linkIndex, flags;
  1483. double torque[3];
  1484. PyObject* torqueObj;
  1485. if (PyArg_ParseTuple(args, "iiOi", &objectUniqueId, &linkIndex, &torqueObj,
  1486. &flags)) {
  1487. PyObject* seq;
  1488. int len, i;
  1489. seq = PySequence_Fast(torqueObj, "expected a sequence");
  1490. len = PySequence_Size(torqueObj);
  1491. if (len == 3) {
  1492. for (i = 0; i < 3; i++) {
  1493. torque[i] = pybullet_internalGetFloatFromSequence(seq, i);
  1494. }
  1495. } else {
  1496. PyErr_SetString(SpamError, "torque needs a 3 coordinates [x,y,z].");
  1497. Py_DECREF(seq);
  1498. return NULL;
  1499. }
  1500. Py_DECREF(seq);
  1501. if (linkIndex < -1) {
  1502. PyErr_SetString(SpamError,
  1503. "Invalid link index, has to be -1 or larger");
  1504. return NULL;
  1505. }
  1506. if ((flags != EF_WORLD_FRAME) && (flags != EF_LINK_FRAME)) {
  1507. PyErr_SetString(SpamError,
  1508. "flag has to be either WORLD_FRAME or LINK_FRAME");
  1509. return NULL;
  1510. }
  1511. {
  1512. b3SharedMemoryStatusHandle statusHandle;
  1513. b3SharedMemoryCommandHandle command =
  1514. b3ApplyExternalForceCommandInit(sm);
  1515. b3ApplyExternalTorque(command, objectUniqueId, -1, torque, flags);
  1516. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
  1517. }
  1518. }
  1519. }
  1520. Py_INCREF(Py_None);
  1521. return Py_None;
  1522. }
  1523. static PyObject* pybullet_getQuaternionFromEuler(PyObject* self,
  1524. PyObject* args) {
  1525. double rpy[3];
  1526. PyObject* eulerObj;
  1527. if (PyArg_ParseTuple(args, "O", &eulerObj)) {
  1528. PyObject* seq;
  1529. int len, i;
  1530. seq = PySequence_Fast(eulerObj, "expected a sequence");
  1531. len = PySequence_Size(eulerObj);
  1532. if (len == 3) {
  1533. for (i = 0; i < 3; i++) {
  1534. rpy[i] = pybullet_internalGetFloatFromSequence(seq, i);
  1535. }
  1536. } else {
  1537. PyErr_SetString(SpamError,
  1538. "Euler angles need a 3 coordinates [roll, pitch, yaw].");
  1539. Py_DECREF(seq);
  1540. return NULL;
  1541. }
  1542. Py_DECREF(seq);
  1543. } else {
  1544. PyErr_SetString(SpamError,
  1545. "Euler angles need a 3 coordinates [roll, pitch, yaw].");
  1546. return NULL;
  1547. }
  1548. {
  1549. double phi, the, psi;
  1550. double roll = rpy[0];
  1551. double pitch = rpy[1];
  1552. double yaw = rpy[2];
  1553. phi = roll / 2.0;
  1554. the = pitch / 2.0;
  1555. psi = yaw / 2.0;
  1556. {
  1557. double quat[4] = {
  1558. sin(phi) * cos(the) * cos(psi) - cos(phi) * sin(the) * sin(psi),
  1559. cos(phi) * sin(the) * cos(psi) + sin(phi) * cos(the) * sin(psi),
  1560. cos(phi) * cos(the) * sin(psi) - sin(phi) * sin(the) * cos(psi),
  1561. cos(phi) * cos(the) * cos(psi) + sin(phi) * sin(the) * sin(psi)};
  1562. // normalize the quaternion
  1563. double len = sqrt(quat[0] * quat[0] + quat[1] * quat[1] +
  1564. quat[2] * quat[2] + quat[3] * quat[3]);
  1565. quat[0] /= len;
  1566. quat[1] /= len;
  1567. quat[2] /= len;
  1568. quat[3] /= len;
  1569. {
  1570. PyObject* pylist;
  1571. int i;
  1572. pylist = PyTuple_New(4);
  1573. for (i = 0; i < 4; i++)
  1574. PyTuple_SetItem(pylist, i, PyFloat_FromDouble(quat[i]));
  1575. return pylist;
  1576. }
  1577. }
  1578. }
  1579. Py_INCREF(Py_None);
  1580. return Py_None;
  1581. }
  1582. /// quaternion <-> euler yaw/pitch/roll convention from URDF/SDF, see Gazebo
  1583. /// https://github.com/arpg/Gazebo/blob/master/gazebo/math/Quaternion.cc
  1584. static PyObject* pybullet_getEulerFromQuaternion(PyObject* self,
  1585. PyObject* args) {
  1586. double squ;
  1587. double sqx;
  1588. double sqy;
  1589. double sqz;
  1590. double quat[4];
  1591. PyObject* quatObj;
  1592. if (PyArg_ParseTuple(args, "O", &quatObj)) {
  1593. PyObject* seq;
  1594. int len, i;
  1595. seq = PySequence_Fast(quatObj, "expected a sequence");
  1596. len = PySequence_Size(quatObj);
  1597. if (len == 4) {
  1598. for (i = 0; i < 4; i++) {
  1599. quat[i] = pybullet_internalGetFloatFromSequence(seq, i);
  1600. }
  1601. } else {
  1602. PyErr_SetString(SpamError, "Quaternion need a 4 components [x,y,z,w].");
  1603. Py_DECREF(seq);
  1604. return NULL;
  1605. }
  1606. Py_DECREF(seq);
  1607. } else {
  1608. PyErr_SetString(SpamError, "Quaternion need a 4 components [x,y,z,w].");
  1609. return NULL;
  1610. }
  1611. {
  1612. double rpy[3];
  1613. double sarg;
  1614. sqx = quat[0] * quat[0];
  1615. sqy = quat[1] * quat[1];
  1616. sqz = quat[2] * quat[2];
  1617. squ = quat[3] * quat[3];
  1618. rpy[0] = atan2(2 * (quat[1] * quat[2] + quat[3] * quat[0]),
  1619. squ - sqx - sqy + sqz);
  1620. sarg = -2 * (quat[0] * quat[2] - quat[3] * quat[1]);
  1621. rpy[1] = sarg <= -1.0 ? -0.5 * 3.141592538
  1622. : (sarg >= 1.0 ? 0.5 * 3.141592538 : asin(sarg));
  1623. rpy[2] = atan2(2 * (quat[0] * quat[1] + quat[3] * quat[2]),
  1624. squ + sqx - sqy - sqz);
  1625. {
  1626. PyObject* pylist;
  1627. int i;
  1628. pylist = PyTuple_New(3);
  1629. for (i = 0; i < 3; i++)
  1630. PyTuple_SetItem(pylist, i, PyFloat_FromDouble(rpy[i]));
  1631. return pylist;
  1632. }
  1633. }
  1634. Py_INCREF(Py_None);
  1635. return Py_None;
  1636. }
  1637. ///Experimental Inverse Kinematics binding ,7-dof KUKA IIWA only
  1638. static PyObject* pybullet_calculateInverseKinematicsKuka(PyObject* self,
  1639. PyObject* args) {
  1640. int size;
  1641. if (0 == sm) {
  1642. PyErr_SetString(SpamError, "Not connected to physics server.");
  1643. return NULL;
  1644. }
  1645. size = PySequence_Size(args);
  1646. if (size == 2)
  1647. {
  1648. int bodyIndex;
  1649. int endEffectorLinkIndex;
  1650. PyObject* targetPosObj;
  1651. PyObject* targetOrnObj;
  1652. if (PyArg_ParseTuple(args, "iiOO", &bodyIndex, &endEffectorLinkIndex, &targetPosObj,&targetOrnObj))
  1653. {
  1654. double pos[3];
  1655. double ori[4]={0,1.0,0,0};
  1656. if (pybullet_internalSetVectord(targetPosObj,pos) && pybullet_internalSetVector4(targetOrnObj,ori))
  1657. {
  1658. b3SharedMemoryStatusHandle statusHandle;
  1659. int numPos=0;
  1660. int resultBodyIndex;
  1661. int result;
  1662. b3SharedMemoryCommandHandle command = b3CalculateInverseKinematicsCommandInit(sm,bodyIndex);
  1663. b3CalculateInverseKinematicsAddTargetPositionWithOrientation(command,6,pos,ori);
  1664. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
  1665. result = b3GetStatusInverseKinematicsJointPositions(statusHandle,
  1666. &resultBodyIndex,
  1667. &numPos,
  1668. 0);
  1669. if (result && numPos)
  1670. {
  1671. int i;
  1672. PyObject* pylist;
  1673. double* ikOutPutJointPos = (double*)malloc(numPos*sizeof(double));
  1674. result = b3GetStatusInverseKinematicsJointPositions(statusHandle,
  1675. &resultBodyIndex,
  1676. &numPos,
  1677. ikOutPutJointPos);
  1678. pylist = PyTuple_New(numPos);
  1679. for (i = 0; i < numPos; i++)
  1680. {
  1681. PyTuple_SetItem(pylist, i,
  1682. PyFloat_FromDouble(ikOutPutJointPos[i]));
  1683. }
  1684. free(ikOutPutJointPos);
  1685. return pylist;
  1686. }
  1687. else
  1688. {
  1689. PyErr_SetString(SpamError,
  1690. "Error in calculateInverseKinematics");
  1691. return NULL;
  1692. }
  1693. } else
  1694. {
  1695. PyErr_SetString(SpamError,
  1696. "calculateInverseKinematics couldn't extract position vector3");
  1697. return NULL;
  1698. }
  1699. }
  1700. } else
  1701. {
  1702. PyErr_SetString(SpamError,
  1703. "calculateInverseKinematics expects 2 arguments, body index, "
  1704. "and target position for end effector");
  1705. return NULL;
  1706. }
  1707. Py_INCREF(Py_None);
  1708. return Py_None;
  1709. }
  1710. /// Given an object id, joint positions, joint velocities and joint
  1711. /// accelerations,
  1712. /// compute the joint forces using Inverse Dynamics
  1713. static PyObject* pybullet_calculateInverseDynamics(PyObject* self,
  1714. PyObject* args) {
  1715. int size;
  1716. if (0 == sm) {
  1717. PyErr_SetString(SpamError, "Not connected to physics server.");
  1718. return NULL;
  1719. }
  1720. size = PySequence_Size(args);
  1721. if (size == 4) {
  1722. int bodyIndex;
  1723. PyObject* objPositionsQ;
  1724. PyObject* objVelocitiesQdot;
  1725. PyObject* objAccelerations;
  1726. if (PyArg_ParseTuple(args, "iOOO", &bodyIndex, &objPositionsQ,
  1727. &objVelocitiesQdot, &objAccelerations)) {
  1728. int szObPos = PySequence_Size(objPositionsQ);
  1729. int szObVel = PySequence_Size(objVelocitiesQdot);
  1730. int szObAcc = PySequence_Size(objAccelerations);
  1731. int numJoints = b3GetNumJoints(sm, bodyIndex);
  1732. if (numJoints && (szObPos == numJoints) && (szObVel == numJoints) &&
  1733. (szObAcc == numJoints)) {
  1734. int szInBytes = sizeof(double) * numJoints;
  1735. int i;
  1736. PyObject* pylist = 0;
  1737. double* jointPositionsQ = (double*)malloc(szInBytes);
  1738. double* jointVelocitiesQdot = (double*)malloc(szInBytes);
  1739. double* jointAccelerations = (double*)malloc(szInBytes);
  1740. double* jointForcesOutput = (double*)malloc(szInBytes);
  1741. for (i = 0; i < numJoints; i++) {
  1742. jointPositionsQ[i] =
  1743. pybullet_internalGetFloatFromSequence(objPositionsQ, i);
  1744. jointVelocitiesQdot[i] =
  1745. pybullet_internalGetFloatFromSequence(objVelocitiesQdot, i);
  1746. jointAccelerations[i] =
  1747. pybullet_internalGetFloatFromSequence(objAccelerations, i);
  1748. }
  1749. {
  1750. b3SharedMemoryStatusHandle statusHandle;
  1751. int statusType;
  1752. b3SharedMemoryCommandHandle commandHandle =
  1753. b3CalculateInverseDynamicsCommandInit(
  1754. sm, bodyIndex, jointPositionsQ, jointVelocitiesQdot,
  1755. jointAccelerations);
  1756. statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
  1757. statusType = b3GetStatusType(statusHandle);
  1758. if (statusType == CMD_CALCULATED_INVERSE_DYNAMICS_COMPLETED) {
  1759. int bodyUniqueId;
  1760. int dofCount;
  1761. b3GetStatusInverseDynamicsJointForces(statusHandle, &bodyUniqueId,
  1762. &dofCount, 0);
  1763. if (dofCount) {
  1764. b3GetStatusInverseDynamicsJointForces(statusHandle, 0, 0,
  1765. jointForcesOutput);
  1766. {
  1767. {
  1768. int i;
  1769. pylist = PyTuple_New(dofCount);
  1770. for (i = 0; i < dofCount; i++)
  1771. PyTuple_SetItem(pylist, i,
  1772. PyFloat_FromDouble(jointForcesOutput[i]));
  1773. }
  1774. }
  1775. }
  1776. } else {
  1777. PyErr_SetString(SpamError,
  1778. "Internal error in calculateInverseDynamics");
  1779. }
  1780. }
  1781. free(jointPositionsQ);
  1782. free(jointVelocitiesQdot);
  1783. free(jointAccelerations);
  1784. free(jointForcesOutput);
  1785. if (pylist) return pylist;
  1786. } else {
  1787. PyErr_SetString(SpamError,
  1788. "calculateInverseDynamics numJoints needs to be "
  1789. "positive and [joint positions], [joint velocities], "
  1790. "[joint accelerations] need to match the number of "
  1791. "joints.");
  1792. return NULL;
  1793. }
  1794. } else {
  1795. PyErr_SetString(SpamError,
  1796. "calculateInverseDynamics expects 4 arguments, body "
  1797. "index, [joint positions], [joint velocities], [joint "
  1798. "accelerations].");
  1799. return NULL;
  1800. }
  1801. } else {
  1802. PyErr_SetString(SpamError,
  1803. "calculateInverseDynamics expects 4 arguments, body index, "
  1804. "[joint positions], [joint velocities], [joint "
  1805. "accelerations].");
  1806. return NULL;
  1807. }
  1808. Py_INCREF(Py_None);
  1809. return Py_None;
  1810. }
  1811. static PyMethodDef SpamMethods[] = {
  1812. {"connect", pybullet_connectPhysicsServer, METH_VARARGS,
  1813. "Connect to an existing physics server (using shared memory by default)."},
  1814. {"disconnect", pybullet_disconnectPhysicsServer, METH_VARARGS,
  1815. "Disconnect from the physics server."},
  1816. {"resetSimulation", pybullet_resetSimulation, METH_VARARGS,
  1817. "Reset the simulation: remove all objects and start from an empty world."},
  1818. {"stepSimulation", pybullet_stepSimulation, METH_VARARGS,
  1819. "Step the simulation using forward dynamics."},
  1820. {"setGravity", pybullet_setGravity, METH_VARARGS,
  1821. "Set the gravity acceleration (x,y,z)."},
  1822. {"setTimeStep", pybullet_setTimeStep, METH_VARARGS,
  1823. "Set the amount of time to proceed at each call to stepSimulation. (unit "
  1824. "is seconds, typically range is 0.01 or 0.001)"},
  1825. {"setTimeStep", pybullet_setTimeStep, METH_VARARGS,
  1826. "Set the amount of time to proceed at each call to stepSimulation."
  1827. " (unit is seconds, typically range is 0.01 or 0.001)"},
  1828. {"setDefaultContactERP", pybullet_setDefaultContactERP, METH_VARARGS,
  1829. "Set the amount of contact penetration Error Recovery Paramater "
  1830. "(ERP) in each time step. \
  1831. This is an tuning parameter to control resting contact stability. "
  1832. "This value depends on the time step."},
  1833. { "setRealTimeSimulation", pybullet_setRealTimeSimulation, METH_VARARGS,
  1834. "Enable or disable real time simulation (using the real time clock,"
  1835. " RTC) in the physics server. Expects one integer argument, 0 or 1" },
  1836. {"loadURDF", pybullet_loadURDF, METH_VARARGS,
  1837. "Create a multibody by loading a URDF file."},
  1838. {"loadSDF", pybullet_loadSDF, METH_VARARGS,
  1839. "Load multibodies from an SDF file."},
  1840. {"saveWorld", pybullet_saveWorld, METH_VARARGS,
  1841. "Save an approximate Python file to reproduce the current state of the world: saveWorld"
  1842. "(filename). (very preliminary and approximately)"},
  1843. {"getNumBodies", pybullet_getNumBodies, METH_VARARGS,
  1844. "Get the number of bodies in the simulation."},
  1845. {"getBodyUniqueId", pybullet_getBodyUniqueId, METH_VARARGS,
  1846. "Get the unique id of the body, given a integer serial index in range [0.. number of bodies)."},
  1847. {"getBodyInfo", pybullet_getBodyInfo, METH_VARARGS,
  1848. "Get the body info, given a body unique id."},
  1849. {"getBasePositionAndOrientation", pybullet_getBasePositionAndOrientation,
  1850. METH_VARARGS,
  1851. "Get the world position and orientation of the base of the object. "
  1852. "(x,y,z) position vector and (x,y,z,w) quaternion orientation."},
  1853. {"resetBasePositionAndOrientation",
  1854. pybullet_resetBasePositionAndOrientation, METH_VARARGS,
  1855. "Reset the world position and orientation of the base of the object "
  1856. "instantaneously, not through physics simulation. (x,y,z) position vector "
  1857. "and (x,y,z,w) quaternion orientation."},
  1858. {"getNumJoints", pybullet_getNumJoints, METH_VARARGS,
  1859. "Get the number of joints for an object."},
  1860. {"getJointInfo", pybullet_getJointInfo, METH_VARARGS,
  1861. "Get the name and type info for a joint on a body."},
  1862. {"getJointState", pybullet_getJointState, METH_VARARGS,
  1863. "Get the state (position, velocity etc) for a joint on a body."},
  1864. {"getLinkState", pybullet_getLinkState, METH_VARARGS,
  1865. "Provides extra information such as the Cartesian world coordinates"
  1866. " center of mass (COM) of the link, relative to the world reference"
  1867. " frame."},
  1868. {"resetJointState", pybullet_resetJointState, METH_VARARGS,
  1869. "Reset the state (position, velocity etc) for a joint on a body "
  1870. "instantaneously, not through physics simulation."},
  1871. {"setJointMotorControl", pybullet_setJointMotorControl, METH_VARARGS,
  1872. "Set a single joint motor control mode and desired target value. There is "
  1873. "no immediate state change, stepSimulation will process the motors."},
  1874. {"applyExternalForce", pybullet_applyExternalForce, METH_VARARGS,
  1875. "for objectUniqueId, linkIndex (-1 for base/root link), apply a force "
  1876. "[x,y,z] at the a position [x,y,z], flag to select FORCE_IN_LINK_FRAME or "
  1877. "FORCE_IN_WORLD_FRAME coordinates"},
  1878. {"applyExternalTorque", pybullet_applyExternalTorque, METH_VARARGS,
  1879. "for objectUniqueId, linkIndex (-1 for base/root link) apply a torque "
  1880. "[x,y,z] in Cartesian coordinates, flag to select TORQUE_IN_LINK_FRAME or "
  1881. "TORQUE_IN_WORLD_FRAME coordinates"},
  1882. {"renderImage", pybullet_renderImage, METH_VARARGS,
  1883. "Render an image (given the pixel resolution width, height, camera view "
  1884. "matrix, projection matrix, near, and far values), and return the "
  1885. "8-8-8bit RGB pixel data and floating point depth values"
  1886. #ifdef PYBULLET_USE_NUMPY
  1887. " as NumPy arrays"
  1888. #endif
  1889. },
  1890. {"getContactPointData", pybullet_getContactPointData, METH_VARARGS,
  1891. "Return the contact point information for all or some of pairwise "
  1892. "object-object collisions. Optional arguments one or two object unique "
  1893. "ids, that need to be involved in the contact."},
  1894. {"getQuaternionFromEuler", pybullet_getQuaternionFromEuler, METH_VARARGS,
  1895. "Convert Euler [roll, pitch, yaw] as in URDF/SDF convention, to "
  1896. "quaternion [x,y,z,w]"},
  1897. {"getEulerFromQuaternion", pybullet_getEulerFromQuaternion, METH_VARARGS,
  1898. "Convert quaternion [x,y,z,w] to Euler [roll, pitch, yaw] as in URDF/SDF "
  1899. "convention"},
  1900. {"calculateInverseDynamics", pybullet_calculateInverseDynamics,
  1901. METH_VARARGS,
  1902. "Given an object id, joint positions, joint velocities and joint "
  1903. "accelerations, compute the joint forces using Inverse Dynamics"},
  1904. {"calculateInverseKinematicsKuka", pybullet_calculateInverseKinematicsKuka,
  1905. METH_VARARGS,
  1906. "Experimental, KUKA IIWA only: Given an object id, "
  1907. "current joint positions and target position"
  1908. " for the end effector,"
  1909. "compute the inverse kinematics and return the new joint state"},
  1910. // todo(erwincoumans)
  1911. // saveSnapshot
  1912. // loadSnapshot
  1913. // raycast info
  1914. // object names
  1915. {NULL, NULL, 0, NULL} /* Sentinel */
  1916. };
  1917. #if PY_MAJOR_VERSION >= 3
  1918. static struct PyModuleDef moduledef = {
  1919. PyModuleDef_HEAD_INIT, "pybullet", /* m_name */
  1920. "Python bindings for Bullet Physics Robotics API (also known as Shared "
  1921. "Memory API)", /* m_doc */
  1922. -1, /* m_size */
  1923. SpamMethods, /* m_methods */
  1924. NULL, /* m_reload */
  1925. NULL, /* m_traverse */
  1926. NULL, /* m_clear */
  1927. NULL, /* m_free */
  1928. };
  1929. #endif
  1930. PyMODINIT_FUNC
  1931. #if PY_MAJOR_VERSION >= 3
  1932. PyInit_pybullet(void)
  1933. #else
  1934. initpybullet(void)
  1935. #endif
  1936. {
  1937. PyObject* m;
  1938. #if PY_MAJOR_VERSION >= 3
  1939. m = PyModule_Create(&moduledef);
  1940. #else
  1941. m = Py_InitModule3("pybullet", SpamMethods, "Python bindings for Bullet");
  1942. #endif
  1943. #if PY_MAJOR_VERSION >= 3
  1944. if (m == NULL) return m;
  1945. #else
  1946. if (m == NULL) return;
  1947. #endif
  1948. PyModule_AddIntConstant(m, "SHARED_MEMORY",
  1949. eCONNECT_SHARED_MEMORY); // user read
  1950. PyModule_AddIntConstant(m, "DIRECT", eCONNECT_DIRECT); // user read
  1951. PyModule_AddIntConstant(m, "GUI", eCONNECT_GUI); // user read
  1952. PyModule_AddIntConstant(m, "TORQUE_CONTROL", CONTROL_MODE_TORQUE);
  1953. PyModule_AddIntConstant(m, "VELOCITY_CONTROL",
  1954. CONTROL_MODE_VELOCITY); // user read
  1955. PyModule_AddIntConstant(m, "POSITION_CONTROL",
  1956. CONTROL_MODE_POSITION_VELOCITY_PD); // user read
  1957. PyModule_AddIntConstant(m, "LINK_FRAME", EF_LINK_FRAME);
  1958. PyModule_AddIntConstant(m, "WORLD_FRAME", EF_WORLD_FRAME);
  1959. SpamError = PyErr_NewException("pybullet.error", NULL, NULL);
  1960. Py_INCREF(SpamError);
  1961. PyModule_AddObject(m, "error", SpamError);
  1962. #ifdef PYBULLET_USE_NUMPY
  1963. // Initialize numpy array.
  1964. import_array();
  1965. #endif //PYBULLET_USE_NUMPY
  1966. #if PY_MAJOR_VERSION >= 3
  1967. return m;
  1968. #endif
  1969. }