expose texture unique id after loading URD file, so you can restore to the original texture after changing it to a custom texture. See also getTextureUid.py example.

This commit is contained in:
Erwin Coumans
2018-07-08 11:23:12 +02:00
parent bfc85ff1fd
commit 127b82ec1b
8 changed files with 227 additions and 26 deletions

View File

@@ -0,0 +1,19 @@
import pybullet as p
p.connect(p.GUI)
plane = p.loadURDF("plane.urdf")
visualData = p.getVisualShapeData(plane, p.VISUAL_SHAPE_DATA_TEXTURE_UNIQUE_IDS)
print(visualData)
curTexUid = visualData[0][8]
print(curTexUid)
texUid = p.loadTexture("tex256.png")
print("texUid=",texUid)
p.changeVisualShape(plane,-1,textureUniqueId=texUid)
for i in range (100):
p.getCameraImage(320,200)
p.changeVisualShape(plane,-1,textureUniqueId=curTexUid)
for i in range (100):
p.getCameraImage(320,200)

View File

@@ -13,8 +13,8 @@ bearStartPos2 = [0,0,0]
bearStartOrientation2 = p.getQuaternionFromEuler([0,0,0])
bearId2 = p.loadURDF("teddy_large.urdf",bearStartPos2, bearStartOrientation2)
textureId = p.loadTexture("checker_grid.jpg")
p.changeVisualShape(objectUniqueId=0, linkIndex=-1, textureUniqueId=textureId)
p.changeVisualShape(objectUniqueId=1, linkIndex=-1, textureUniqueId=textureId)
#p.changeVisualShape(objectUniqueId=0, linkIndex=-1, textureUniqueId=textureId)
#p.changeVisualShape(objectUniqueId=1, linkIndex=-1, textureUniqueId=textureId)
useRealTimeSimulation = 1

View File

@@ -5428,8 +5428,10 @@ static PyObject* pybullet_getVisualShapeData(PyObject* self, PyObject* args, PyO
PyObject* pyResultList = 0;
int physicsClientId = 0;
b3PhysicsClientHandle sm = 0;
static char* kwlist[] = {"objectUniqueId", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|i", kwlist, &objectUniqueId, &physicsClientId))
int flags=0;
static char* kwlist[] = {"objectUniqueId", "flags", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "i|ii", kwlist, &objectUniqueId, &flags, &physicsClientId))
{
return NULL;
}
@@ -5450,7 +5452,9 @@ static PyObject* pybullet_getVisualShapeData(PyObject* self, PyObject* args, PyO
pyResultList = PyTuple_New(visualShapeInfo.m_numVisualShapes);
for (i = 0; i < visualShapeInfo.m_numVisualShapes; i++)
{
PyObject* visualShapeObList = PyTuple_New(8);
int numFields = flags&eVISUAL_SHAPE_DATA_TEXTURE_UNIQUE_IDS ? 9 : 8;
PyObject* visualShapeObList = PyTuple_New(numFields);
PyObject* item;
item = PyInt_FromLong(visualShapeInfo.m_visualShapeData[i].m_objectUniqueId);
PyTuple_SetItem(visualShapeObList, 0, item);
@@ -5511,6 +5515,11 @@ static PyObject* pybullet_getVisualShapeData(PyObject* self, PyObject* args, PyO
PyTuple_SetItem(rgba, 3, item);
PyTuple_SetItem(visualShapeObList, 7, rgba);
}
if (flags&eVISUAL_SHAPE_DATA_TEXTURE_UNIQUE_IDS)
{
item = PyInt_FromLong(visualShapeInfo.m_visualShapeData[i].m_textureUniqueId);
PyTuple_SetItem(visualShapeObList, 8, item);
}
PyTuple_SetItem(pyResultList, i, visualShapeObList);
}
@@ -9656,6 +9665,8 @@ initpybullet(void)
PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION_EXCLUDE_PARENT", URDF_USE_SELF_COLLISION_EXCLUDE_PARENT);
PyModule_AddIntConstant(m, "URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS", URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS);
PyModule_AddIntConstant(m, "VISUAL_SHAPE_DATA_TEXTURE_UNIQUE_IDS", eVISUAL_SHAPE_DATA_TEXTURE_UNIQUE_IDS);
PyModule_AddIntConstant(m, "MAX_RAY_INTERSECTION_BATCH_SIZE", MAX_RAY_INTERSECTION_BATCH_SIZE_STREAMING);
PyModule_AddIntConstant(m, "B3G_F1", B3G_F1);