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:
@@ -2940,6 +2940,20 @@ B3_SHARED_API void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandl
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
B3_SHARED_API void b3RequestCameraImageSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags)
|
||||||
|
{
|
||||||
|
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||||
|
b3Assert(command);
|
||||||
|
b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA);
|
||||||
|
if(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA)
|
||||||
|
{
|
||||||
|
command->m_requestPixelDataArguments.m_flags = flags;
|
||||||
|
command->m_updateFlags |= REQUEST_PIXEL_ARGS_HAS_FLAGS;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
B3_SHARED_API void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle commandHandle, float viewMatrix[16], float projectionMatrix[16])
|
B3_SHARED_API void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle commandHandle, float viewMatrix[16], float projectionMatrix[16])
|
||||||
{
|
{
|
||||||
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
|
||||||
|
|||||||
@@ -209,6 +209,9 @@ B3_SHARED_API void b3RequestCameraImageSetLightDiffuseCoeff(b3SharedMemoryComman
|
|||||||
B3_SHARED_API void b3RequestCameraImageSetLightSpecularCoeff(b3SharedMemoryCommandHandle commandHandle, float lightSpecularCoeff);
|
B3_SHARED_API void b3RequestCameraImageSetLightSpecularCoeff(b3SharedMemoryCommandHandle commandHandle, float lightSpecularCoeff);
|
||||||
B3_SHARED_API void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, int hasShadow);
|
B3_SHARED_API void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, int hasShadow);
|
||||||
B3_SHARED_API void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandle, int renderer);
|
B3_SHARED_API void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandle, int renderer);
|
||||||
|
B3_SHARED_API void b3RequestCameraImageSetFlags(b3SharedMemoryCommandHandle commandHandle, int flags);
|
||||||
|
|
||||||
|
|
||||||
B3_SHARED_API void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData);
|
B3_SHARED_API void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData);
|
||||||
|
|
||||||
///compute a view matrix, helper function for b3RequestCameraImageSetCameraMatrices
|
///compute a view matrix, helper function for b3RequestCameraImageSetCameraMatrices
|
||||||
|
|||||||
@@ -940,7 +940,7 @@ void PhysicsClientExample::stepSimulation(float deltaTime)
|
|||||||
btVector4(32,255,255,255)};
|
btVector4(32,255,255,255)};
|
||||||
if (segmentationMask>=0)
|
if (segmentationMask>=0)
|
||||||
{
|
{
|
||||||
int obIndex = segmentationMask&(0x1e24-1);
|
int obIndex = segmentationMask&((1<<24)-1);
|
||||||
int linkIndex = (segmentationMask>>24)-1;
|
int linkIndex = (segmentationMask>>24)-1;
|
||||||
|
|
||||||
btVector4 rgb = palette[(obIndex+linkIndex)&3];
|
btVector4 rgb = palette[(obIndex+linkIndex)&3];
|
||||||
|
|||||||
@@ -3017,7 +3017,12 @@ bool PhysicsServerCommandProcessor::processRequestCameraImageCommand(const struc
|
|||||||
m_data->m_visualConverter.setWidthAndHeight(clientCmd.m_requestPixelDataArguments.m_pixelWidth,
|
m_data->m_visualConverter.setWidthAndHeight(clientCmd.m_requestPixelDataArguments.m_pixelWidth,
|
||||||
clientCmd.m_requestPixelDataArguments.m_pixelHeight);
|
clientCmd.m_requestPixelDataArguments.m_pixelHeight);
|
||||||
}
|
}
|
||||||
|
int flags = 0;
|
||||||
|
if (clientCmd.m_updateFlags&REQUEST_PIXEL_ARGS_HAS_FLAGS)
|
||||||
|
{
|
||||||
|
flags = clientCmd.m_requestPixelDataArguments.m_flags;
|
||||||
|
}
|
||||||
|
m_data->m_visualConverter.setFlags(flags);
|
||||||
|
|
||||||
int numTotalPixels = width*height;
|
int numTotalPixels = width*height;
|
||||||
int numRemainingPixels = numTotalPixels - startPixelIndex;
|
int numRemainingPixels = numTotalPixels - startPixelIndex;
|
||||||
|
|||||||
@@ -2169,7 +2169,7 @@ void PhysicsServerExample::updateGraphics()
|
|||||||
btVector4(32,255,255,255)};
|
btVector4(32,255,255,255)};
|
||||||
if (segmentationMask>=0)
|
if (segmentationMask>=0)
|
||||||
{
|
{
|
||||||
int obIndex = segmentationMask&(0x1e24-1);
|
int obIndex = segmentationMask&((1<<24)-1);
|
||||||
int linkIndex = (segmentationMask>>24)-1;
|
int linkIndex = (segmentationMask>>24)-1;
|
||||||
|
|
||||||
btVector4 rgb = palette[(obIndex+linkIndex)&3];
|
btVector4 rgb = palette[(obIndex+linkIndex)&3];
|
||||||
|
|||||||
@@ -238,6 +238,7 @@ struct RequestPixelDataArgs
|
|||||||
float m_lightDiffuseCoeff;
|
float m_lightDiffuseCoeff;
|
||||||
float m_lightSpecularCoeff;
|
float m_lightSpecularCoeff;
|
||||||
int m_hasShadow;
|
int m_hasShadow;
|
||||||
|
int m_flags;
|
||||||
};
|
};
|
||||||
|
|
||||||
enum EnumRequestPixelDataUpdateFlags
|
enum EnumRequestPixelDataUpdateFlags
|
||||||
@@ -251,6 +252,8 @@ enum EnumRequestPixelDataUpdateFlags
|
|||||||
REQUEST_PIXEL_ARGS_SET_AMBIENT_COEFF=64,
|
REQUEST_PIXEL_ARGS_SET_AMBIENT_COEFF=64,
|
||||||
REQUEST_PIXEL_ARGS_SET_DIFFUSE_COEFF=128,
|
REQUEST_PIXEL_ARGS_SET_DIFFUSE_COEFF=128,
|
||||||
REQUEST_PIXEL_ARGS_SET_SPECULAR_COEFF=256,
|
REQUEST_PIXEL_ARGS_SET_SPECULAR_COEFF=256,
|
||||||
|
REQUEST_PIXEL_ARGS_HAS_FLAGS = 512,
|
||||||
|
|
||||||
//don't exceed (1<<15), because this enum is shared with EnumRenderer in SharedMemoryPublic.h
|
//don't exceed (1<<15), because this enum is shared with EnumRenderer in SharedMemoryPublic.h
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -584,6 +584,10 @@ enum EnumRenderer
|
|||||||
//ER_FIRE_RAYS=(1<<18),
|
//ER_FIRE_RAYS=(1<<18),
|
||||||
};
|
};
|
||||||
|
|
||||||
|
enum EnumRendererAuxFlags
|
||||||
|
{
|
||||||
|
ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX=1,
|
||||||
|
};
|
||||||
///flags to pick the IK solver and other options
|
///flags to pick the IK solver and other options
|
||||||
enum EnumCalculateInverseKinematicsFlags
|
enum EnumCalculateInverseKinematicsFlags
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -82,6 +82,7 @@ struct TinyRendererVisualShapeConverterInternalData
|
|||||||
float m_lightSpecularCoeff;
|
float m_lightSpecularCoeff;
|
||||||
bool m_hasLightSpecularCoeff;
|
bool m_hasLightSpecularCoeff;
|
||||||
bool m_hasShadow;
|
bool m_hasShadow;
|
||||||
|
int m_flags;
|
||||||
SimpleCamera m_camera;
|
SimpleCamera m_camera;
|
||||||
|
|
||||||
|
|
||||||
@@ -102,7 +103,8 @@ struct TinyRendererVisualShapeConverterInternalData
|
|||||||
m_hasLightDiffuseCoeff(false),
|
m_hasLightDiffuseCoeff(false),
|
||||||
m_lightSpecularCoeff(0.05),
|
m_lightSpecularCoeff(0.05),
|
||||||
m_hasLightSpecularCoeff(false),
|
m_hasLightSpecularCoeff(false),
|
||||||
m_hasShadow(false)
|
m_hasShadow(false),
|
||||||
|
m_flags(0)
|
||||||
{
|
{
|
||||||
m_depthBuffer.resize(m_swWidth*m_swHeight);
|
m_depthBuffer.resize(m_swWidth*m_swHeight);
|
||||||
m_shadowBuffer.resize(m_swWidth*m_swHeight);
|
m_shadowBuffer.resize(m_swWidth*m_swHeight);
|
||||||
@@ -154,6 +156,11 @@ void TinyRendererVisualShapeConverter::setShadow(bool hasShadow)
|
|||||||
{
|
{
|
||||||
m_data->m_hasShadow = hasShadow;
|
m_data->m_hasShadow = hasShadow;
|
||||||
}
|
}
|
||||||
|
void TinyRendererVisualShapeConverter::setFlags(int flags)
|
||||||
|
{
|
||||||
|
m_data->m_flags = flags;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
void TinyRendererVisualShapeConverter::setLightAmbientCoeff(float ambientCoeff)
|
void TinyRendererVisualShapeConverter::setLightAmbientCoeff(float ambientCoeff)
|
||||||
{
|
{
|
||||||
@@ -1043,7 +1050,17 @@ void TinyRendererVisualShapeConverter::copyCameraImageData(unsigned char* pixels
|
|||||||
}
|
}
|
||||||
if (segmentationMaskBuffer)
|
if (segmentationMaskBuffer)
|
||||||
{
|
{
|
||||||
segmentationMaskBuffer[i] = m_data->m_segmentationMaskBuffer[i+startPixelIndex];
|
int segMask = m_data->m_segmentationMaskBuffer[i + startPixelIndex];
|
||||||
|
if ((m_data->m_flags & ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX)==0)
|
||||||
|
{
|
||||||
|
//if we don't explicitly request link index, clear it out
|
||||||
|
//object index are the lower 24bits
|
||||||
|
if (segMask >= 0)
|
||||||
|
{
|
||||||
|
segMask &= ((1 << 24) - 1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
segmentationMaskBuffer[i] = segMask;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (pixelsRGBA)
|
if (pixelsRGBA)
|
||||||
|
|||||||
@@ -43,6 +43,7 @@ struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter
|
|||||||
void setLightDiffuseCoeff(float diffuseCoeff);
|
void setLightDiffuseCoeff(float diffuseCoeff);
|
||||||
void setLightSpecularCoeff(float specularCoeff);
|
void setLightSpecularCoeff(float specularCoeff);
|
||||||
void setShadow(bool hasShadow);
|
void setShadow(bool hasShadow);
|
||||||
|
void setFlags(int flags);
|
||||||
|
|
||||||
void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels,int* segmentationMaskBuffer, int segmentationMaskSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied);
|
void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels,int* segmentationMaskBuffer, int segmentationMaskSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied);
|
||||||
|
|
||||||
|
|||||||
@@ -562,12 +562,12 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData)
|
|||||||
{
|
{
|
||||||
for (int t=0;t<clippedTriangles.size();t++)
|
for (int t=0;t<clippedTriangles.size();t++)
|
||||||
{
|
{
|
||||||
triangleClipped(clippedTriangles[t], shader.varying_tri, shader, frame, &zbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex+((renderData.m_linkIndex+1)<<24));
|
triangleClipped(clippedTriangles[t], shader.varying_tri, shader, frame, &zbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex+((renderData.m_linkIndex + 1) << 24));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
triangle(shader.varying_tri, shader, frame, &zbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex+((renderData.m_linkIndex+1)<<24));
|
triangle(shader.varying_tri, shader, frame, &zbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex+((renderData.m_linkIndex + 1) << 24));
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -188,15 +188,8 @@ void triangle(mat<4,3,float> &clipc, IShader &shader, TGAImage &image, float *zb
|
|||||||
if (!discard) {
|
if (!discard) {
|
||||||
zbuffer[P.x+P.y*image.get_width()] = frag_depth;
|
zbuffer[P.x+P.y*image.get_width()] = frag_depth;
|
||||||
if (segmentationMaskBuffer)
|
if (segmentationMaskBuffer)
|
||||||
{
|
|
||||||
if (objectAndLinkIndex)
|
|
||||||
{
|
{
|
||||||
segmentationMaskBuffer[P.x+P.y*image.get_width()] = objectAndLinkIndex;
|
segmentationMaskBuffer[P.x+P.y*image.get_width()] = objectAndLinkIndex;
|
||||||
} else
|
|
||||||
{
|
|
||||||
segmentationMaskBuffer[P.x+P.y*image.get_width()] = 0;
|
|
||||||
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
image.set(P.x, P.y, color);
|
image.set(P.x, P.y, color);
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -9,21 +9,22 @@ for i in range (10):
|
|||||||
p.setGravity(0,0,-10)
|
p.setGravity(0,0,-10)
|
||||||
|
|
||||||
|
|
||||||
for i in range (500):
|
#for i in range (500):
|
||||||
|
# p.stepSimulation()
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
saveState = 1
|
||||||
|
|
||||||
|
if saveState:
|
||||||
|
for i in range (500):
|
||||||
p.stepSimulation()
|
p.stepSimulation()
|
||||||
|
p.saveBullet("state.bullet")
|
||||||
|
else:
|
||||||
|
p.restoreState(fileName="state.bullet")
|
||||||
|
|
||||||
for i in range (10):
|
for i in range (10):
|
||||||
print("pos[",i,"]=",p.getBasePositionAndOrientation(i))
|
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"]):
|
while (p.getConnectionInfo()["isConnected"]):
|
||||||
time.sleep(1)
|
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 lightAmbientCoeff = -1;
|
||||||
float lightDiffuseCoeff = -1;
|
float lightDiffuseCoeff = -1;
|
||||||
float lightSpecularCoeff = -1;
|
float lightSpecularCoeff = -1;
|
||||||
|
int flags = -1;
|
||||||
int renderer = -1;
|
int renderer = -1;
|
||||||
// inialize cmd
|
// inialize cmd
|
||||||
b3SharedMemoryCommandHandle command;
|
b3SharedMemoryCommandHandle command;
|
||||||
int physicsClientId = 0;
|
int physicsClientId = 0;
|
||||||
b3PhysicsClientHandle sm = 0;
|
b3PhysicsClientHandle sm = 0;
|
||||||
// set camera resolution, optionally view, projection matrix, light direction, light color, light distance, shadow
|
// 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;
|
return NULL;
|
||||||
}
|
}
|
||||||
@@ -6107,6 +6107,10 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
|
|||||||
b3RequestCameraImageSetLightSpecularCoeff(command, lightSpecularCoeff);
|
b3RequestCameraImageSetLightSpecularCoeff(command, lightSpecularCoeff);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (flags >= 0)
|
||||||
|
{
|
||||||
|
b3RequestCameraImageSetFlags(command, flags);
|
||||||
|
}
|
||||||
if (renderer>=0)
|
if (renderer>=0)
|
||||||
{
|
{
|
||||||
b3RequestCameraImageSelectRenderer(command, renderer);//renderer could be ER_BULLET_HARDWARE_OPENGL
|
b3RequestCameraImageSelectRenderer(command, renderer);//renderer could be ER_BULLET_HARDWARE_OPENGL
|
||||||
@@ -8365,6 +8369,7 @@ initpybullet(void)
|
|||||||
|
|
||||||
PyModule_AddIntConstant(m, "ER_TINY_RENDERER", ER_TINY_RENDERER);
|
PyModule_AddIntConstant(m, "ER_TINY_RENDERER", ER_TINY_RENDERER);
|
||||||
PyModule_AddIntConstant(m, "ER_BULLET_HARDWARE_OPENGL", ER_BULLET_HARDWARE_OPENGL);
|
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_DLS", IK_DLS);
|
||||||
PyModule_AddIntConstant(m, "IK_SDLS", IK_SDLS);
|
PyModule_AddIntConstant(m, "IK_SDLS", IK_SDLS);
|
||||||
|
|||||||
Reference in New Issue
Block a user