Merge pull request #736 from erwincoumans/master

revert accidently renaming of m_depthvalues4
This commit is contained in:
erwincoumans
2016-08-12 14:43:21 -07:00
committed by GitHub
12 changed files with 60 additions and 20 deletions

View File

@@ -47,6 +47,18 @@ struct GUIHelperInterface
virtual void resetCamera(float camDist, float pitch, float yaw, float camPosX,float camPosY, float camPosZ)=0;
virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16],
unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels,
float* depthBuffer, int depthBufferSizeInPixels,
int startPixelIndex, int destinationWidth, int destinationHeight, int* numPixelsCopied)
{
copyCameraImageData(viewMatrix,projectionMatrix,pixelsRGBA,rgbaBufferSizeInPixels,
depthBuffer,depthBufferSizeInPixels,
0,0,
startPixelIndex,destinationWidth,
destinationHeight,numPixelsCopied);
}
virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16],
unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels,
float* depthBuffer, int depthBufferSizeInPixels,
int* segmentationMaskBuffer, int segmentationMaskBufferSizeInPixels,

View File

@@ -187,9 +187,9 @@ TinyRendererSetup::TinyRendererSetup(struct GUIHelperInterface* gui)
TinyRenderObjectData* ob = new TinyRenderObjectData(
m_internalData->m_rgbColorBuffer,
m_internalData->m_depthBuffer,
m_internalData->m_segmentationMaskBuffer,
m_internalData->m_renderObjects.size(),0);
//ob->loadModel("cube.obj");
&m_internalData->m_segmentationMaskBuffer,
m_internalData->m_renderObjects.size());
const int* indices = &meshData.m_gfxShape->m_indices->at(0);
ob->registerMeshShape(&meshData.m_gfxShape->m_vertices->at(0).xyzw[0],
meshData.m_gfxShape->m_numvertices,

View File

@@ -736,7 +736,7 @@ void PhysicsClientExample::stepSimulation(float deltaTime)
if (m_canvasDepthIndex >=0)
{
int depthPixelIndex = (xIndex+yIndex*imageData.m_pixelWidth);
float depthValue = imageData.m_depthValues4[depthPixelIndex];
float depthValue = imageData.m_depthValues[depthPixelIndex];
//todo: rescale the depthValue to [0..255]
if (depthValue>-1e20)
{
@@ -770,7 +770,7 @@ void PhysicsClientExample::stepSimulation(float deltaTime)
if (m_canvasDepthIndex >=0)
{
int depthPixelIndex = (xIndex+yIndex*imageData.m_pixelWidth);
float depthValue = imageData.m_depthValues4[depthPixelIndex];
float depthValue = imageData.m_depthValues[depthPixelIndex];
//todo: rescale the depthValue to [0..255]
if (depthValue>-1e20)
{

View File

@@ -712,7 +712,7 @@ void PhysicsClientSharedMemory::getCachedCameraImage(struct b3CameraImageData* c
{
cameraData->m_pixelWidth = m_data->m_cachedCameraPixelsWidth;
cameraData->m_pixelHeight = m_data->m_cachedCameraPixelsHeight;
cameraData->m_depthValues4 = m_data->m_cachedCameraDepthBuffer.size() ? &m_data->m_cachedCameraDepthBuffer[0] : 0;
cameraData->m_depthValues = m_data->m_cachedCameraDepthBuffer.size() ? &m_data->m_cachedCameraDepthBuffer[0] : 0;
cameraData->m_rgbColorData = m_data->m_cachedCameraPixelsRGBA.size() ? &m_data->m_cachedCameraPixelsRGBA[0] : 0;
cameraData->m_segmentationMaskValues = m_data->m_cachedSegmentationMaskBuffer.size()?&m_data->m_cachedSegmentationMaskBuffer[0] : 0;
}

View File

@@ -464,7 +464,7 @@ void PhysicsDirect::getCachedCameraImage(b3CameraImageData* cameraData)
{
cameraData->m_pixelWidth = m_data->m_cachedCameraPixelsWidth;
cameraData->m_pixelHeight = m_data->m_cachedCameraPixelsHeight;
cameraData->m_depthValues4 = m_data->m_cachedCameraDepthBuffer.size() ? &m_data->m_cachedCameraDepthBuffer[0] : 0;
cameraData->m_depthValues = m_data->m_cachedCameraDepthBuffer.size() ? &m_data->m_cachedCameraDepthBuffer[0] : 0;
cameraData->m_rgbColorData = m_data->m_cachedCameraPixelsRGBA.size() ? &m_data->m_cachedCameraPixelsRGBA[0] : 0;
cameraData->m_segmentationMaskValues = m_data->m_cachedSegmentationMask.size()? &m_data->m_cachedSegmentationMask[0] : 0;
}

View File

@@ -122,7 +122,7 @@ struct b3CameraImageData
int m_pixelWidth;
int m_pixelHeight;
const unsigned char* m_rgbColorData;//3*m_pixelWidth*m_pixelHeight bytes
const float* m_depthValues4;//m_pixelWidth*m_pixelHeight floats
const float* m_depthValues;//m_pixelWidth*m_pixelHeight floats
const int* m_segmentationMaskValues;//m_pixelWidth*m_pixelHeight ints
};

View File

@@ -490,7 +490,7 @@ void TinyRendererVisualShapeConverter::convertVisualShapes(int linkIndex, const
if (vertices.size() && indices.size())
{
TinyRenderObjectData* tinyObj = new TinyRenderObjectData(m_data->m_rgbColorBuffer,m_data->m_depthBuffer, m_data->m_segmentationMaskBuffer, objectIndex,0);
TinyRenderObjectData* tinyObj = new TinyRenderObjectData(m_data->m_rgbColorBuffer,m_data->m_depthBuffer, &m_data->m_segmentationMaskBuffer, objectIndex);
unsigned char* textureImage=0;
int textureWidth=0;
int textureHeight=0;

View File

@@ -87,11 +87,30 @@ struct Shader : public IShader {
}
};
TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray<float>&depthBuffer, b3AlignedObjectArray<int>& segmentationMaskBuffer, int objectIndex,int objectIndex2)
TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray<float>&depthBuffer)
:m_rgbColorBuffer(rgbColorBuffer),
m_depthBuffer(depthBuffer),
m_segmentationMaskBuffer(segmentationMaskBuffer),
m_segmentationMaskBufferPtr(0),
m_model(0),
m_userData(0),
m_userIndex(-1),
m_objectIndex(-1)
{
Vec3f eye(1,1,3);
Vec3f center(0,0,0);
Vec3f up(0,0,1);
m_lightDirWorld.setValue(0,0,0);
m_localScaling.setValue(1,1,1);
m_modelMatrix = Matrix::identity();
}
TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray<float>&depthBuffer, b3AlignedObjectArray<int>* segmentationMaskBuffer, int objectIndex)
:m_rgbColorBuffer(rgbColorBuffer),
m_depthBuffer(depthBuffer),
m_segmentationMaskBufferPtr(segmentationMaskBuffer),
m_model(0),
m_userData(0),
m_userIndex(-1),
@@ -249,7 +268,7 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData)
renderData.m_viewportMatrix = viewport(0,0,width, height);
b3AlignedObjectArray<float>& zbuffer = renderData.m_depthBuffer;
b3AlignedObjectArray<int>& segmentationMaskBuffer = renderData.m_segmentationMaskBuffer;
int* segmentationMaskBufferPtr = &renderData.m_segmentationMaskBufferPtr->at(0);
TGAImage& frame = renderData.m_rgbColorBuffer;
@@ -267,7 +286,7 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData)
for (int j=0; j<3; j++) {
shader.vertex(i, j);
}
triangle(shader.varying_tri, shader, frame, &zbuffer[0], &segmentationMaskBuffer[0], renderData.m_viewportMatrix, renderData.m_objectIndex);
triangle(shader.varying_tri, shader, frame, &zbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex);
}
}

View File

@@ -27,10 +27,11 @@ struct TinyRenderObjectData
//Output
TGAImage& m_rgbColorBuffer;
b3AlignedObjectArray<float>& m_depthBuffer;
b3AlignedObjectArray<int>& m_segmentationMaskBuffer;
b3AlignedObjectArray<float>& m_depthBuffer;//required, hence a reference
b3AlignedObjectArray<int>* m_segmentationMaskBufferPtr;//optional, hence a pointer
TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray<float>&depthBuffer, b3AlignedObjectArray<int>& segmentationMaskBuffer,int objectIndex,int objectIndex2);
TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray<float>&depthBuffer);
TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray<float>&depthBuffer, b3AlignedObjectArray<int>* segmentationMaskBuffer,int objectIndex);
virtual ~TinyRenderObjectData();
void loadModel(const char* fileName);

View File

@@ -59,6 +59,11 @@ Vec3f barycentric(Vec2f A, Vec2f B, Vec2f C, Vec2f P) {
return Vec3f(-1,1,1); // in this case generate negative coordinates, it will be thrown away by the rasterizator
}
void triangle(mat<4,3,float> &clipc, IShader &shader, TGAImage &image, float *zbuffer, const Matrix& viewPortMatrix, int objectIndex)
{
triangle(clipc,shader,image,zbuffer,0,viewPortMatrix,0);
}
void triangle(mat<4,3,float> &clipc, IShader &shader, TGAImage &image, float *zbuffer, int* segmentationMaskBuffer, const Matrix& viewPortMatrix, int objectIndex) {
mat<3,4,float> pts = (viewPortMatrix*clipc).transpose(); // transposed to ease access to each of the points
@@ -100,7 +105,10 @@ void triangle(mat<4,3,float> &clipc, IShader &shader, TGAImage &image, float *zb
bool discard = shader.fragment(bc_clip, color);
if (!discard) {
zbuffer[P.x+P.y*image.get_width()] = frag_depth;
segmentationMaskBuffer[P.x+P.y*image.get_width()] = objectIndex;
if (segmentationMaskBuffer)
{
segmentationMaskBuffer[P.x+P.y*image.get_width()] = objectIndex;
}
image.set(P.x, P.y, color);
}
}

View File

@@ -16,7 +16,7 @@ struct IShader {
virtual bool fragment(Vec3f bar, TGAColor &color) = 0;
};
//void triangle(Vec4f *pts, IShader &shader, TGAImage &image, float *zbuffer);
void triangle(mat<4,3,float> &pts, IShader &shader, TGAImage &image, float *zbuffer, const Matrix& viewPortMatrix);
void triangle(mat<4,3,float> &pts, IShader &shader, TGAImage &image, float *zbuffer, int* segmentationMaskBuffer, const Matrix& viewPortMatrix, int objectIndex);
#endif //__OUR_GL_H__

View File

@@ -1231,7 +1231,7 @@ static PyObject* pybullet_renderImage(PyObject* self, PyObject* args)
// TODO(hellojas): validate depth values make sense
int depIndex = i+j*imageData.m_pixelWidth;
{
item = PyFloat_FromDouble(imageData.m_depthValues4[depIndex]);
item = PyFloat_FromDouble(imageData.m_depthValues[depIndex]);
PyTuple_SetItem(pylistDep, depIndex, item);
}
{