Fix a bug that createVisualShape(Array) does not have the correct color. Add urdfEditor.py to pybullet_utils. Remove all unnecessary changes of white spaces.

This commit is contained in:
jietan 2018-03-14 20:47:56 -07:00
parent d91a58e050
commit f4ca3f5963
2 changed files with 535 additions and 528 deletions

View File

@ -3953,7 +3953,6 @@ bool PhysicsServerCommandProcessor::processCreateVisualShapeCommand(const struct
btAlignedObjectArray<BulletURDFTexture> textures; btAlignedObjectArray<BulletURDFTexture> textures;
UrdfVisual visualShape; UrdfVisual visualShape;
for (int userShapeIndex = 0; userShapeIndex< clientCmd.m_createUserShapeArgs.m_numUserShapes; userShapeIndex++) for (int userShapeIndex = 0; userShapeIndex< clientCmd.m_createUserShapeArgs.m_numUserShapes; userShapeIndex++)
{ {
@ -4039,9 +4038,6 @@ bool PhysicsServerCommandProcessor::processCreateVisualShapeCommand(const struct
bool hasRGBA = (clientCmd.m_createUserShapeArgs.m_shapes[userShapeIndex].m_visualFlags&GEOM_VISUAL_HAS_RGBA_COLOR) != 0;; bool hasRGBA = (clientCmd.m_createUserShapeArgs.m_shapes[userShapeIndex].m_visualFlags&GEOM_VISUAL_HAS_RGBA_COLOR) != 0;;
bool hasSpecular = (clientCmd.m_createUserShapeArgs.m_shapes[userShapeIndex].m_visualFlags&GEOM_VISUAL_HAS_SPECULAR_COLOR) != 0;; bool hasSpecular = (clientCmd.m_createUserShapeArgs.m_shapes[userShapeIndex].m_visualFlags&GEOM_VISUAL_HAS_SPECULAR_COLOR) != 0;;
visualShape.m_geometry.m_hasLocalMaterial = hasRGBA | hasSpecular; visualShape.m_geometry.m_hasLocalMaterial = hasRGBA | hasSpecular;
@ -4086,7 +4082,9 @@ bool PhysicsServerCommandProcessor::processCreateVisualShapeCommand(const struct
u2b.convertURDFToVisualShapeInternal(&visualShape, pathPrefix, localInertiaFrame.inverse()*childTrans, vertices, indices, textures); u2b.convertURDFToVisualShapeInternal(&visualShape, pathPrefix, localInertiaFrame.inverse()*childTrans, vertices, indices, textures);
} }
if (vertices.size() && indices.size()) if (vertices.size() && indices.size())
{ {
if (1) if (1)

View File

@ -6094,29 +6094,31 @@ static PyObject* pybullet_createVisualShape(PyObject* self, PyObject* args, PyOb
if (shapeIndex>=0) if (shapeIndex>=0)
{ {
double rgbaColor[4] = {1,1,1,1}; double rgbaColor[4] = {1,1,1,1};
double specularColor[3] = {1,1,1}; double specularColor[3] = {1,1,1};
if (rgbaColorObj) if (rgbaColorObj)
{ {
pybullet_internalSetVector4d(rgbaColorObj,rgbaColor); pybullet_internalSetVector4d(rgbaColorObj,rgbaColor);
} }
b3CreateVisualShapeSetRGBAColor(commandHandle,shapeIndex, rgbaColor); b3CreateVisualShapeSetRGBAColor(commandHandle,shapeIndex, rgbaColor);
if (specularColorObj) if (specularColorObj)
{ {
pybullet_internalSetVectord(specularColorObj,specularColor); pybullet_internalSetVectord(specularColorObj,specularColor);
} }
b3CreateVisualShapeSetSpecularColor(commandHandle,shapeIndex,specularColor); b3CreateVisualShapeSetSpecularColor(commandHandle,shapeIndex,specularColor);
if (visualFramePositionObj) if (visualFramePositionObj)
{ {
pybullet_internalSetVectord(visualFramePositionObj,visualFramePosition); pybullet_internalSetVectord(visualFramePositionObj,visualFramePosition);
} }
if (visualFrameOrientationObj) if (visualFrameOrientationObj)
{ {
pybullet_internalSetVector4d(visualFrameOrientationObj,visualFrameOrientation); pybullet_internalSetVector4d(visualFrameOrientationObj,visualFrameOrientation);
} }
b3CreateVisualShapeSetChildTransform(commandHandle, shapeIndex, visualFramePosition,visualFrameOrientation); b3CreateVisualShapeSetChildTransform(commandHandle, shapeIndex, visualFramePosition,visualFrameOrientation);
} }
@ -6148,16 +6150,16 @@ static PyObject* pybullet_createVisualShapeArray(PyObject* self, PyObject* args,
PyObject* fileNameArray = 0; PyObject* fileNameArray = 0;
PyObject* meshScaleObjArray = 0; PyObject* meshScaleObjArray = 0;
PyObject* planeNormalObjArray = 0; PyObject* planeNormalObjArray = 0;
PyObject* rgbaColorArray = 0; PyObject* rgbaColorArray = 0;
PyObject* flagsArray = 0; PyObject* flagsArray = 0;
PyObject* visualFramePositionObjArray = 0; PyObject* visualFramePositionObjArray = 0;
PyObject* visualFrameOrientationObjArray = 0; PyObject* visualFrameOrientationObjArray = 0;
static char* kwlist[] = { "shapeTypes", "radii", "halfExtents", "lengths", "fileNames", "meshScales", "planeNormals", static char* kwlist[] = { "shapeTypes", "radii", "halfExtents", "lengths", "fileNames", "meshScales", "planeNormals",
"flags", "rgbaColors", "visualFramePositions", "visualFrameOrientations", "physicsClientId", NULL }; "flags", "rgbaColors", "visualFramePositions", "visualFrameOrientations", "physicsClientId", NULL };
if (!PyArg_ParseTupleAndKeywords(args, keywds, "O|OOOOOOOOOOi", kwlist, if (!PyArg_ParseTupleAndKeywords(args, keywds, "O|OOOOOOOOOOi", kwlist,
&shapeTypeArray, &radiusArray, &halfExtentsObjArray, &lengthArray, &fileNameArray, &meshScaleObjArray, &planeNormalObjArray, &flagsArray, &rgbaColorArray, &visualFramePositionObjArray, &visualFrameOrientationObjArray, &physicsClientId)) &shapeTypeArray, &radiusArray, &halfExtentsObjArray, &lengthArray, &fileNameArray, &meshScaleObjArray, &planeNormalObjArray, &flagsArray, &rgbaColorArray, &visualFramePositionObjArray, &visualFrameOrientationObjArray, &physicsClientId))
{ {
return NULL; return NULL;
} }
@ -6167,6 +6169,10 @@ static PyObject* pybullet_createVisualShapeArray(PyObject* self, PyObject* args,
PyErr_SetString(SpamError, "Not connected to physics server."); PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL; return NULL;
} }
{ {
b3SharedMemoryCommandHandle commandHandle = b3CreateVisualShapeCommandInit(sm); b3SharedMemoryCommandHandle commandHandle = b3CreateVisualShapeCommandInit(sm);
int numShapeTypes = 0; int numShapeTypes = 0;
@ -6176,7 +6182,7 @@ static PyObject* pybullet_createVisualShapeArray(PyObject* self, PyObject* args,
int numFileNames = 0; int numFileNames = 0;
int numMeshScales = 0; int numMeshScales = 0;
int numPlaneNormals = 0; int numPlaneNormals = 0;
int numRGBAColors = 0; int numRGBAColors = 0;
int numFlags = 0; int numFlags = 0;
int numPositions = 0; int numPositions = 0;
int numOrientations = 0; int numOrientations = 0;
@ -6189,7 +6195,7 @@ static PyObject* pybullet_createVisualShapeArray(PyObject* self, PyObject* args,
PyObject* fileNameArraySeq = fileNameArray ? PySequence_Fast(fileNameArray, "expected a sequence of filename") : 0; PyObject* fileNameArraySeq = fileNameArray ? PySequence_Fast(fileNameArray, "expected a sequence of filename") : 0;
PyObject* meshScaleArraySeq = meshScaleObjArray ? PySequence_Fast(meshScaleObjArray, "expected a sequence of mesh scale") : 0; PyObject* meshScaleArraySeq = meshScaleObjArray ? PySequence_Fast(meshScaleObjArray, "expected a sequence of mesh scale") : 0;
PyObject* planeNormalArraySeq = planeNormalObjArray ? PySequence_Fast(planeNormalObjArray, "expected a sequence of plane normal") : 0; PyObject* planeNormalArraySeq = planeNormalObjArray ? PySequence_Fast(planeNormalObjArray, "expected a sequence of plane normal") : 0;
PyObject* rgbaColorArraySeq = rgbaColorArray ? PySequence_Fast(rgbaColorArray, "expected a sequence of rgba color") : 0; PyObject* rgbaColorArraySeq = rgbaColorArray ? PySequence_Fast(rgbaColorArray, "expected a sequence of rgba color") : 0;
PyObject* flagsArraySeq = flagsArray ? PySequence_Fast(flagsArray, "expected a sequence of flags") : 0; PyObject* flagsArraySeq = flagsArray ? PySequence_Fast(flagsArray, "expected a sequence of flags") : 0;
PyObject* positionArraySeq = visualFramePositionObjArray ? PySequence_Fast(visualFramePositionObjArray, "expected a sequence of visual frame positions") : 0; PyObject* positionArraySeq = visualFramePositionObjArray ? PySequence_Fast(visualFramePositionObjArray, "expected a sequence of visual frame positions") : 0;
PyObject* orientationArraySeq = visualFrameOrientationObjArray ? PySequence_Fast(visualFrameOrientationObjArray, "expected a sequence of visual frame orientations") : 0; PyObject* orientationArraySeq = visualFrameOrientationObjArray ? PySequence_Fast(visualFrameOrientationObjArray, "expected a sequence of visual frame orientations") : 0;
@ -6207,7 +6213,7 @@ static PyObject* pybullet_createVisualShapeArray(PyObject* self, PyObject* args,
numFileNames = fileNameArraySeq ? PySequence_Size(fileNameArraySeq) : 0; numFileNames = fileNameArraySeq ? PySequence_Size(fileNameArraySeq) : 0;
numMeshScales = meshScaleArraySeq ? PySequence_Size(meshScaleArraySeq) : 0; numMeshScales = meshScaleArraySeq ? PySequence_Size(meshScaleArraySeq) : 0;
numPlaneNormals = planeNormalArraySeq ? PySequence_Size(planeNormalArraySeq) : 0; numPlaneNormals = planeNormalArraySeq ? PySequence_Size(planeNormalArraySeq) : 0;
numRGBAColors = rgbaColorArraySeq ? PySequence_Size(rgbaColorArraySeq) : 0; numRGBAColors = rgbaColorArraySeq ? PySequence_Size(rgbaColorArraySeq) : 0;
for (s = 0; s<numShapeTypes; s++) for (s = 0; s<numShapeTypes; s++)
{ {
@ -6302,16 +6308,16 @@ static PyObject* pybullet_createVisualShapeArray(PyObject* self, PyObject* args,
int flags = pybullet_internalGetIntFromSequence(flagsArraySeq, s); int flags = pybullet_internalGetIntFromSequence(flagsArraySeq, s);
b3CreateVisualSetFlag(commandHandle, shapeIndex, flags); b3CreateVisualSetFlag(commandHandle, shapeIndex, flags);
} }
if (rgbaColorArraySeq) if (rgbaColorArraySeq)
{ {
PyObject* rgbaColorObj = rgbaColorArraySeq ? PyList_GET_ITEM(rgbaColorArraySeq, s) : 0; PyObject* rgbaColorObj = rgbaColorArraySeq ? PyList_GET_ITEM(rgbaColorArraySeq, s) : 0;
double rgbaColor[4] = {1,1,1,1}; double rgbaColor[4] = {1,1,1,1};
if (rgbaColorObj) if (rgbaColorObj)
{ {
pybullet_internalSetVector4d(rgbaColorObj,rgbaColor); pybullet_internalSetVector4d(rgbaColorObj,rgbaColor);
} }
b3CreateVisualShapeSetRGBAColor(commandHandle,shapeIndex, rgbaColor); b3CreateVisualShapeSetRGBAColor(commandHandle,shapeIndex, rgbaColor);
} }
if (positionArraySeq || orientationArraySeq) if (positionArraySeq || orientationArraySeq)
{ {
PyObject* visualFramePositionObj = positionArraySeq ? PyList_GET_ITEM(positionArraySeq, s) : 0; PyObject* visualFramePositionObj = positionArraySeq ? PyList_GET_ITEM(positionArraySeq, s) : 0;
@ -6334,6 +6340,9 @@ static PyObject* pybullet_createVisualShapeArray(PyObject* self, PyObject* args,
} }
} }
} }
if (shapeTypeArraySeq) if (shapeTypeArraySeq)
@ -6350,10 +6359,10 @@ static PyObject* pybullet_createVisualShapeArray(PyObject* self, PyObject* args,
Py_DECREF(meshScaleArraySeq); Py_DECREF(meshScaleArraySeq);
if (planeNormalArraySeq) if (planeNormalArraySeq)
Py_DECREF(planeNormalArraySeq); Py_DECREF(planeNormalArraySeq);
if (rgbaColorArraySeq)
Py_DECREF(rgbaColorArraySeq);
if (flagsArraySeq) if (flagsArraySeq)
Py_DECREF(flagsArraySeq); Py_DECREF(flagsArraySeq);
if (rgbaColorArraySeq)
Py_DECREF(rgbaColorArraySeq);
if (positionArraySeq) if (positionArraySeq)
Py_DECREF(positionArraySeq); Py_DECREF(positionArraySeq);
if (orientationArraySeq) if (orientationArraySeq)