From e0c74a46ac95551247ff4acc0e9015a6ef7e4878 Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Sat, 4 Mar 2017 13:31:30 -0800 Subject: [PATCH] Set renderer in pybullet. --- examples/pybullet/pybullet.c | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 24234c53b..da71a68dc 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -3834,10 +3834,10 @@ static PyObject* pybullet_getContactPointData(PyObject* self, PyObject* args, Py /// Render an image from the current timestep of the simulation, width, height are required, other args are optional -// getCameraImage(w, h, view[16], projection[16], lightDir[3], lightColor[3], lightDist, hasShadow, lightAmbientCoeff, lightDiffuseCoeff, lightSpecularCoeff) +// getCameraImage(w, h, view[16], projection[16], lightDir[3], lightColor[3], lightDist, hasShadow, lightAmbientCoeff, lightDiffuseCoeff, lightSpecularCoeff, renderer) static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObject *keywds) { - /// request an image from a simulated camera, using a software renderer. + /// request an image from a simulated camera, using software or hardware renderer. struct b3CameraImageData imageData; PyObject* objViewMat = 0, *objProjMat = 0, *lightDirObj = 0, *lightColorObj = 0; int width, height; @@ -3850,14 +3850,15 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec float lightAmbientCoeff = 0.6; float lightDiffuseCoeff = 0.35; float lightSpecularCoeff = 0.05; + int renderer = 0; // inialize cmd b3SharedMemoryCommandHandle command; int physicsClientId = 0; b3PhysicsClientHandle sm = 0; // set camera resolution, optionally view, projection matrix, light direction, light color, light distance, shadow - static char *kwlist[] = { "width", "height", "viewMatrix", "projectionMatrix", "lightDirection", "lightColor", "lightDistance", "shadow", "lightAmbientCoeff", "lightDiffuseCoeff", "lightSpecularCoeff", "physicsClientId", NULL }; + static char *kwlist[] = { "width", "height", "viewMatrix", "projectionMatrix", "lightDirection", "lightColor", "lightDistance", "shadow", "lightAmbientCoeff", "lightDiffuseCoeff", "lightSpecularCoeff", "renderer", "physicsClientId", NULL }; - if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|OOOOfifffi", kwlist, &width, &height, &objViewMat, &objProjMat, &lightDirObj, &lightColorObj, &lightDist, &hasShadow, &lightAmbientCoeff, &lightDiffuseCoeff, &lightSpecularCoeff,&physicsClientId)) + if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|OOOOfifffii", kwlist, &width, &height, &objViewMat, &objProjMat, &lightDirObj, &lightColorObj, &lightDist, &hasShadow, &lightAmbientCoeff, &lightDiffuseCoeff, &lightSpecularCoeff, &renderer, &physicsClientId)) { return NULL; } @@ -3894,6 +3895,8 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec b3RequestCameraImageSetLightAmbientCoeff(command, lightAmbientCoeff); b3RequestCameraImageSetLightDiffuseCoeff(command, lightDiffuseCoeff); b3RequestCameraImageSetLightSpecularCoeff(command, lightSpecularCoeff); + + b3RequestCameraImageSelectRenderer(command, renderer); if (b3CanSubmitCommand(sm)) { @@ -5104,7 +5107,7 @@ static PyMethodDef SpamMethods[] = { { "getCameraImage",(PyCFunction)pybullet_getCameraImage, METH_VARARGS| METH_KEYWORDS, "Render an image (given the pixel resolution width, height, camera viewMatrix " - ", projectionMatrix, lightDirection, lightColor, lightDistance, shadow, lightAmbientCoeff, lightDiffuseCoeff, and lightSpecularCoeff), and return the " + ", projectionMatrix, lightDirection, lightColor, lightDistance, shadow, lightAmbientCoeff, lightDiffuseCoeff, lightSpecularCoeff, and renderer), and return the " "8-8-8bit RGB pixel data and floating point depth values" #ifdef PYBULLET_USE_NUMPY " as NumPy arrays"