add segmask_linkindex.py example using p.getCameraImage(320,200,flags=p.ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX)
to extract object unique id and link index from segmentation mask in getCameraImage
This commit is contained in:
@@ -9,21 +9,22 @@ for i in range (10):
|
||||
p.setGravity(0,0,-10)
|
||||
|
||||
|
||||
for i in range (500):
|
||||
p.stepSimulation()
|
||||
#for i in range (500):
|
||||
# p.stepSimulation()
|
||||
|
||||
|
||||
|
||||
saveState = 1
|
||||
|
||||
if saveState:
|
||||
for i in range (500):
|
||||
p.stepSimulation()
|
||||
p.saveBullet("state.bullet")
|
||||
else:
|
||||
p.restoreState(fileName="state.bullet")
|
||||
|
||||
for i in range (10):
|
||||
print("pos[",i,"]=",p.getBasePositionAndOrientation(i))
|
||||
|
||||
#saveState = 0
|
||||
|
||||
#if saveState:
|
||||
# for i in range (500):
|
||||
# p.stepSimulation()
|
||||
# p.saveBullet("state.bullet")
|
||||
#else:
|
||||
# p.restoreState(fileName="state.bullet")
|
||||
|
||||
|
||||
|
||||
while (p.getConnectionInfo()["isConnected"]):
|
||||
time.sleep(1)
|
||||
42
examples/pybullet/examples/segmask_linkindex.py
Normal file
42
examples/pybullet/examples/segmask_linkindex.py
Normal file
@@ -0,0 +1,42 @@
|
||||
import pybullet as p
|
||||
p.connect(p.GUI)
|
||||
r2d2 = p.loadURDF("r2d2.urdf",[0,0,1])
|
||||
for l in range (p.getNumJoints(r2d2)):
|
||||
print(p.getJointInfo(r2d2,l))
|
||||
|
||||
p.loadURDF("r2d2.urdf",[2,0,1])
|
||||
p.loadURDF("r2d2.urdf",[4,0,1])
|
||||
|
||||
p.getCameraImage(320,200,flags=p.ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX)
|
||||
segLinkIndex=1
|
||||
verbose = 0
|
||||
|
||||
while (1):
|
||||
keys = p.getKeyboardEvents()
|
||||
#for k in keys:
|
||||
# print("key=",k,"state=", keys[k])
|
||||
if ord('1') in keys:
|
||||
state = keys[ord('1')]
|
||||
if (state & p.KEY_WAS_RELEASED):
|
||||
verbose = 1-verbose
|
||||
if ord('s') in keys:
|
||||
state = keys[ord('s')]
|
||||
if (state & p.KEY_WAS_RELEASED):
|
||||
segLinkIndex = 1-segLinkIndex
|
||||
#print("segLinkIndex=",segLinkIndex)
|
||||
flags = 0
|
||||
if (segLinkIndex):
|
||||
flags=p.ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX
|
||||
|
||||
img = p.getCameraImage(320,200,flags=flags)
|
||||
#print(img[0],img[1])
|
||||
seg=img[4]
|
||||
if (verbose):
|
||||
for pixel in seg:
|
||||
if (pixel>=0):
|
||||
obUid = pixel & ((1<<24)-1)
|
||||
linkIndex = (pixel >> 24)-1
|
||||
print("obUid=",obUid,"linkIndex=",linkIndex)
|
||||
|
||||
|
||||
p.stepSimulation()
|
||||
@@ -6046,16 +6046,16 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
|
||||
float lightAmbientCoeff = -1;
|
||||
float lightDiffuseCoeff = -1;
|
||||
float lightSpecularCoeff = -1;
|
||||
|
||||
int flags = -1;
|
||||
int renderer = -1;
|
||||
// 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", "renderer", "physicsClientId", NULL};
|
||||
static char* kwlist[] = {"width", "height", "viewMatrix", "projectionMatrix", "lightDirection", "lightColor", "lightDistance", "shadow", "lightAmbientCoeff", "lightDiffuseCoeff", "lightSpecularCoeff", "renderer", "flags", "physicsClientId", NULL};
|
||||
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|OOOOfifffii", kwlist, &width, &height, &objViewMat, &objProjMat, &lightDirObj, &lightColorObj, &lightDist, &hasShadow, &lightAmbientCoeff, &lightDiffuseCoeff, &lightSpecularCoeff, &renderer, &physicsClientId))
|
||||
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|OOOOfifffiii", kwlist, &width, &height, &objViewMat, &objProjMat, &lightDirObj, &lightColorObj, &lightDist, &hasShadow, &lightAmbientCoeff, &lightDiffuseCoeff, &lightSpecularCoeff, &renderer, &flags, &physicsClientId))
|
||||
{
|
||||
return NULL;
|
||||
}
|
||||
@@ -6107,6 +6107,10 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
|
||||
b3RequestCameraImageSetLightSpecularCoeff(command, lightSpecularCoeff);
|
||||
}
|
||||
|
||||
if (flags >= 0)
|
||||
{
|
||||
b3RequestCameraImageSetFlags(command, flags);
|
||||
}
|
||||
if (renderer>=0)
|
||||
{
|
||||
b3RequestCameraImageSelectRenderer(command, renderer);//renderer could be ER_BULLET_HARDWARE_OPENGL
|
||||
@@ -8365,7 +8369,8 @@ initpybullet(void)
|
||||
|
||||
PyModule_AddIntConstant(m, "ER_TINY_RENDERER", ER_TINY_RENDERER);
|
||||
PyModule_AddIntConstant(m, "ER_BULLET_HARDWARE_OPENGL", ER_BULLET_HARDWARE_OPENGL);
|
||||
|
||||
PyModule_AddIntConstant(m, "ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX", ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX);
|
||||
|
||||
PyModule_AddIntConstant(m, "IK_DLS", IK_DLS);
|
||||
PyModule_AddIntConstant(m, "IK_SDLS", IK_SDLS);
|
||||
PyModule_AddIntConstant(m, "IK_HAS_TARGET_POSITION", IK_HAS_TARGET_POSITION);
|
||||
|
||||
Reference in New Issue
Block a user