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])
|
||||
{
|
||||
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 b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, int hasShadow);
|
||||
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);
|
||||
|
||||
///compute a view matrix, helper function for b3RequestCameraImageSetCameraMatrices
|
||||
|
||||
@@ -940,7 +940,7 @@ void PhysicsClientExample::stepSimulation(float deltaTime)
|
||||
btVector4(32,255,255,255)};
|
||||
if (segmentationMask>=0)
|
||||
{
|
||||
int obIndex = segmentationMask&(0x1e24-1);
|
||||
int obIndex = segmentationMask&((1<<24)-1);
|
||||
int linkIndex = (segmentationMask>>24)-1;
|
||||
|
||||
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,
|
||||
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 numRemainingPixels = numTotalPixels - startPixelIndex;
|
||||
|
||||
@@ -2169,7 +2169,7 @@ void PhysicsServerExample::updateGraphics()
|
||||
btVector4(32,255,255,255)};
|
||||
if (segmentationMask>=0)
|
||||
{
|
||||
int obIndex = segmentationMask&(0x1e24-1);
|
||||
int obIndex = segmentationMask&((1<<24)-1);
|
||||
int linkIndex = (segmentationMask>>24)-1;
|
||||
|
||||
btVector4 rgb = palette[(obIndex+linkIndex)&3];
|
||||
|
||||
@@ -238,6 +238,7 @@ struct RequestPixelDataArgs
|
||||
float m_lightDiffuseCoeff;
|
||||
float m_lightSpecularCoeff;
|
||||
int m_hasShadow;
|
||||
int m_flags;
|
||||
};
|
||||
|
||||
enum EnumRequestPixelDataUpdateFlags
|
||||
@@ -251,6 +252,8 @@ enum EnumRequestPixelDataUpdateFlags
|
||||
REQUEST_PIXEL_ARGS_SET_AMBIENT_COEFF=64,
|
||||
REQUEST_PIXEL_ARGS_SET_DIFFUSE_COEFF=128,
|
||||
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
|
||||
|
||||
};
|
||||
|
||||
@@ -584,6 +584,10 @@ enum EnumRenderer
|
||||
//ER_FIRE_RAYS=(1<<18),
|
||||
};
|
||||
|
||||
enum EnumRendererAuxFlags
|
||||
{
|
||||
ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX=1,
|
||||
};
|
||||
///flags to pick the IK solver and other options
|
||||
enum EnumCalculateInverseKinematicsFlags
|
||||
{
|
||||
|
||||
@@ -82,6 +82,7 @@ struct TinyRendererVisualShapeConverterInternalData
|
||||
float m_lightSpecularCoeff;
|
||||
bool m_hasLightSpecularCoeff;
|
||||
bool m_hasShadow;
|
||||
int m_flags;
|
||||
SimpleCamera m_camera;
|
||||
|
||||
|
||||
@@ -102,7 +103,8 @@ struct TinyRendererVisualShapeConverterInternalData
|
||||
m_hasLightDiffuseCoeff(false),
|
||||
m_lightSpecularCoeff(0.05),
|
||||
m_hasLightSpecularCoeff(false),
|
||||
m_hasShadow(false)
|
||||
m_hasShadow(false),
|
||||
m_flags(0)
|
||||
{
|
||||
m_depthBuffer.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;
|
||||
}
|
||||
void TinyRendererVisualShapeConverter::setFlags(int flags)
|
||||
{
|
||||
m_data->m_flags = flags;
|
||||
}
|
||||
|
||||
|
||||
void TinyRendererVisualShapeConverter::setLightAmbientCoeff(float ambientCoeff)
|
||||
{
|
||||
@@ -1043,7 +1050,17 @@ void TinyRendererVisualShapeConverter::copyCameraImageData(unsigned char* pixels
|
||||
}
|
||||
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)
|
||||
|
||||
@@ -43,6 +43,7 @@ struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter
|
||||
void setLightDiffuseCoeff(float diffuseCoeff);
|
||||
void setLightSpecularCoeff(float specularCoeff);
|
||||
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);
|
||||
|
||||
|
||||
Reference in New Issue
Block a user