Merge pull request #884 from YunfeiBai/master

Expose ambient, diffuse, and specular coefficients of the TinyRenderer light.
This commit is contained in:
erwincoumans
2016-12-09 08:56:26 -08:00
committed by GitHub
12 changed files with 163 additions and 30 deletions

View File

@@ -376,7 +376,9 @@ void TinyRendererSetup::stepSimulation(float deltaTime)
m_internalData->m_renderObjects[o]->m_lightColor = lightColor;
m_internalData->m_renderObjects[o]->m_lightDistance = 10.0;
m_internalData->m_renderObjects[o]->m_lightAmbientCoeff = 0.6;
m_internalData->m_renderObjects[o]->m_lightDiffuseCoeff = 0.35;
m_internalData->m_renderObjects[o]->m_lightSpecularCoeff = 0.05;
}
}
TinyRenderer::renderObjectDepth(*m_internalData->m_renderObjects[o]);
@@ -415,6 +417,9 @@ void TinyRendererSetup::stepSimulation(float deltaTime)
m_internalData->m_renderObjects[o]->m_lightColor = lightColor;
m_internalData->m_renderObjects[o]->m_lightDistance = 10.0;
m_internalData->m_renderObjects[o]->m_lightAmbientCoeff = 0.6;
m_internalData->m_renderObjects[o]->m_lightDiffuseCoeff = 0.35;
m_internalData->m_renderObjects[o]->m_lightSpecularCoeff = 0.05;
}
}

View File

@@ -1361,6 +1361,33 @@ void b3RequestCameraImageSetLightDistance(b3SharedMemoryCommandHandle commandHan
command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_LIGHT_DISTANCE;
}
void b3RequestCameraImageSetLightAmbientCoeff(b3SharedMemoryCommandHandle commandHandle, float lightAmbientCoeff)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA);
command->m_requestPixelDataArguments.m_lightAmbientCoeff = lightAmbientCoeff;
command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_AMBIENT_COEFF;
}
void b3RequestCameraImageSetLightDiffuseCoeff(b3SharedMemoryCommandHandle commandHandle, float lightDiffuseCoeff)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA);
command->m_requestPixelDataArguments.m_lightDiffuseCoeff = lightDiffuseCoeff;
command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_DIFFUSE_COEFF;
}
void b3RequestCameraImageSetLightSpecularCoeff(b3SharedMemoryCommandHandle commandHandle, float lightSpecularCoeff)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA);
command->m_requestPixelDataArguments.m_lightSpecularCoeff = lightSpecularCoeff;
command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_SPECULAR_COEFF;
}
void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, int hasShadow)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;

View File

@@ -105,6 +105,9 @@ void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle command,
void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHandle, const float lightDirection[3]);
void b3RequestCameraImageSetLightColor(b3SharedMemoryCommandHandle commandHandle, const float lightColor[3]);
void b3RequestCameraImageSetLightDistance(b3SharedMemoryCommandHandle commandHandle, float lightDistance);
void b3RequestCameraImageSetLightAmbientCoeff(b3SharedMemoryCommandHandle commandHandle, float lightAmbientCoeff);
void b3RequestCameraImageSetLightDiffuseCoeff(b3SharedMemoryCommandHandle commandHandle, float lightDiffuseCoeff);
void b3RequestCameraImageSetLightSpecularCoeff(b3SharedMemoryCommandHandle commandHandle, float lightSpecularCoeff);
void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, int hasShadow);
void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandle, int renderer);
void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData);

View File

@@ -1449,6 +1449,21 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
{
m_data->m_visualConverter.setShadow(clientCmd.m_requestPixelDataArguments.m_hasShadow);
}
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_AMBIENT_COEFF) != 0)
{
m_data->m_visualConverter.setLightAmbientCoeff(clientCmd.m_requestPixelDataArguments.m_lightAmbientCoeff);
}
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_DIFFUSE_COEFF) != 0)
{
m_data->m_visualConverter.setLightDiffuseCoeff(clientCmd.m_requestPixelDataArguments.m_lightDiffuseCoeff);
}
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_SPECULAR_COEFF) != 0)
{
m_data->m_visualConverter.setLightSpecularCoeff(clientCmd.m_requestPixelDataArguments.m_lightSpecularCoeff);
}
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES)!=0)
{

View File

@@ -145,6 +145,9 @@ struct RequestPixelDataArgs
float m_lightDirection[3];
float m_lightColor[3];
float m_lightDistance;
float m_lightAmbientCoeff;
float m_lightDiffuseCoeff;
float m_lightSpecularCoeff;
int m_hasShadow;
};
@@ -156,6 +159,9 @@ enum EnumRequestPixelDataUpdateFlags
REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR=8,
REQUEST_PIXEL_ARGS_SET_LIGHT_DISTANCE=16,
REQUEST_PIXEL_ARGS_SET_SHADOW=32,
REQUEST_PIXEL_ARGS_SET_AMBIENT_COEFF=64,
REQUEST_PIXEL_ARGS_SET_DIFFUSE_COEFF=128,
REQUEST_PIXEL_ARGS_SET_SPECULAR_COEFF=256,
//don't exceed (1<<15), because this enum is shared with EnumRenderer in SharedMemoryPublic.h
};

View File

@@ -79,6 +79,12 @@ struct TinyRendererVisualShapeConverterInternalData
bool m_hasLightColor;
float m_lightDistance;
bool m_hasLightDistance;
float m_lightAmbientCoeff;
bool m_hasLightAmbientCoeff;
float m_lightDiffuseCoeff;
bool m_hasLightDiffuseCoeff;
float m_lightSpecularCoeff;
bool m_hasLightSpecularCoeff;
bool m_hasShadow;
SimpleCamera m_camera;
@@ -142,6 +148,24 @@ void TinyRendererVisualShapeConverter::setShadow(bool hasShadow)
m_data->m_hasShadow = hasShadow;
}
void TinyRendererVisualShapeConverter::setLightAmbientCoeff(float ambientCoeff)
{
m_data->m_lightAmbientCoeff = ambientCoeff;
m_data->m_hasLightAmbientCoeff = true;
}
void TinyRendererVisualShapeConverter::setLightDiffuseCoeff(float diffuseCoeff)
{
m_data->m_lightDiffuseCoeff = diffuseCoeff;
m_data->m_hasLightDiffuseCoeff = true;
}
void TinyRendererVisualShapeConverter::setLightSpecularCoeff(float specularCoeff)
{
m_data->m_lightSpecularCoeff = specularCoeff;
m_data->m_hasLightSpecularCoeff = true;
}
void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray<GLInstanceVertex>& verticesOut, btAlignedObjectArray<int>& indicesOut, btAlignedObjectArray<MyTexture2>& texturesOut, b3VisualShapeData& visualShapeOut)
{
@@ -738,7 +762,25 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo
float lightDistance = 2.0;
if (m_data->m_hasLightDistance)
{
lightDistance = m_data->m_hasLightDistance;
lightDistance = m_data->m_lightDistance;
}
float lightAmbientCoeff = 0.6;
if (m_data->m_hasLightAmbientCoeff)
{
lightAmbientCoeff = m_data->m_lightAmbientCoeff;
}
float lightDiffuseCoeff = 0.35;
if (m_data->m_hasLightDiffuseCoeff)
{
lightDiffuseCoeff = m_data->m_lightDiffuseCoeff;
}
float lightSpecularCoeff = 0.05;
if (m_data->m_hasLightSpecularCoeff)
{
lightSpecularCoeff = m_data->m_lightSpecularCoeff;
}
if (m_data->m_hasShadow)
@@ -779,6 +821,9 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo
renderObj->m_lightDirWorld = lightDirWorld;
renderObj->m_lightColor = lightColor;
renderObj->m_lightDistance = lightDistance;
renderObj->m_lightAmbientCoeff = lightAmbientCoeff;
renderObj->m_lightDiffuseCoeff = lightDiffuseCoeff;
renderObj->m_lightSpecularCoeff = lightSpecularCoeff;
TinyRenderer::renderObjectDepth(*renderObj);
}
}
@@ -820,6 +865,9 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo
renderObj->m_lightDirWorld = lightDirWorld;
renderObj->m_lightColor = lightColor;
renderObj->m_lightDistance = lightDistance;
renderObj->m_lightAmbientCoeff = lightAmbientCoeff;
renderObj->m_lightDiffuseCoeff = lightDiffuseCoeff;
renderObj->m_lightSpecularCoeff = lightSpecularCoeff;
TinyRenderer::renderObject(*renderObj);
}
}

View File

@@ -35,6 +35,9 @@ struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter
void setLightDirection(float x, float y, float z);
void setLightColor(float x, float y, float z);
void setLightDistance(float dist);
void setLightAmbientCoeff(float ambientCoeff);
void setLightDiffuseCoeff(float diffuseCoeff);
void setLightSpecularCoeff(float specularCoeff);
void setShadow(bool hasShadow);
void copyCameraImageData(unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels, float* depthBuffer, int depthBufferSizeInPixels,int* segmentationMaskBuffer, int segmentationMaskSizeInPixels, int startPixelIndex, int* widthPtr, int* heightPtr, int* numPixelsCopied);

View File

@@ -209,10 +209,13 @@ public:
renderObj->m_projectionMatrix[i][j] = projMat[i+4*j];
renderObj->m_modelMatrix[i][j] = modelMat[i+4*j];
renderObj->m_viewMatrix[i][j] = viewMat[i+4*j];
renderObj->m_localScaling = colObj->getCollisionShape()->getLocalScaling();
renderObj->m_lightDirWorld = lightDirWorld;
}
}
renderObj->m_localScaling = colObj->getCollisionShape()->getLocalScaling();
renderObj->m_lightDirWorld = lightDirWorld;
renderObj->m_lightAmbientCoeff = 0.6;
renderObj->m_lightDiffuseCoeff = 0.35;
renderObj->m_lightSpecularCoeff = 0.05;
TinyRenderer::renderObject(*renderObj);
}
}

View File

@@ -230,10 +230,13 @@ struct TinyRendererGUIHelper : public GUIHelperInterface
renderObj->m_projectionMatrix[i][j] = projMat[i+4*j];
renderObj->m_modelMatrix[i][j] = modelMat[i+4*j];
renderObj->m_viewMatrix[i][j] = viewMat[i+4*j];
renderObj->m_localScaling = colObj->getCollisionShape()->getLocalScaling();
renderObj->m_lightDirWorld = lightDirWorld;
}
}
renderObj->m_localScaling = colObj->getCollisionShape()->getLocalScaling();
renderObj->m_lightDirWorld = lightDirWorld;
renderObj->m_lightAmbientCoeff = 0.6;
renderObj->m_lightDiffuseCoeff = 0.35;
renderObj->m_lightSpecularCoeff = 0.05;
TinyRenderer::renderObject(*renderObj);
}
}

View File

@@ -66,13 +66,15 @@ struct Shader : public IShader {
Vec3f m_light_color;
Matrix& m_modelMat;
Matrix m_invModelMat;
Matrix& m_modelView1;
Matrix& m_projectionMat;
Vec3f m_localScaling;
Matrix& m_lightModelView;
Vec4f m_colorRGBA;
Matrix& m_viewportMat;
float m_ambient_coefficient;
float m_diffuse_coefficient;
float m_specular_coefficient;
b3AlignedObjectArray<float>* m_shadowBuffer;
@@ -86,10 +88,13 @@ struct Shader : public IShader {
mat<4,3,float> varying_tri_light_view;
mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS
Shader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& lightModelView, Matrix& projectionMat, Matrix& modelMat, Matrix& viewportMat, Vec3f localScaling, const Vec4f& colorRGBA, int width, int height, b3AlignedObjectArray<float>* shadowBuffer)
Shader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& lightModelView, Matrix& projectionMat, Matrix& modelMat, Matrix& viewportMat, Vec3f localScaling, const Vec4f& colorRGBA, int width, int height, b3AlignedObjectArray<float>* shadowBuffer, float ambient_coefficient=0.6, float diffuse_coefficient=0.35, float specular_coefficient=0.05)
:m_model(model),
m_light_dir_local(light_dir_local),
m_light_color(light_color),
m_ambient_coefficient(ambient_coefficient),
m_diffuse_coefficient(diffuse_coefficient),
m_specular_coefficient(specular_coefficient),
m_modelView1(modelView),
m_lightModelView(lightModelView),
m_projectionMat(projectionMat),
@@ -126,7 +131,7 @@ struct Shader : public IShader {
int index_x = b3Max(0, b3Min(m_width-1, int(p[0])));
int index_y = b3Max(0, b3Min(m_height-1, int(p[1])));
int idx = index_x + index_y*m_width; // index in the shadowbuffer array
float shadow = 0.8+0.2*(m_shadowBuffer->at(idx)<-depth+0.2); // magic coeff to avoid z-fighting
float shadow = 0.8+0.2*(m_shadowBuffer->at(idx)<-depth+0.05); // magic coeff to avoid z-fighting
Vec3f bn = (varying_nrm*bar).normalize();
Vec2f uv = varying_uv*bar;
@@ -135,23 +140,16 @@ struct Shader : public IShader {
float specular = pow(b3Max(reflection_direction.z, 0.f), m_model->specular(uv));
float diffuse = b3Max(0.f, bn * m_light_dir_local);
float ambient_coefficient = 0.6;
float diffuse_coefficient = 0.35;
float specular_coefficient = 0.05;
color = TGAColor(255,255,255,255);
color[0] *= m_colorRGBA[0];
color[1] *= m_colorRGBA[1];
color[2] *= m_colorRGBA[2];
color[3] *= m_colorRGBA[3];
float intensity = ambient_coefficient + b3Min(diffuse * diffuse_coefficient + specular * specular_coefficient, 1.0f - ambient_coefficient);
color = m_model->diffuse(uv) * intensity * shadow;
//warning: bgra color is swapped to rgba to upload texture
color.bgra[0] *= m_colorRGBA[0];
color.bgra[1] *= m_colorRGBA[1];
color.bgra[2] *= m_colorRGBA[2];
color.bgra[3] *= m_colorRGBA[3];
color.bgra[0] *= m_light_color[0];
color.bgra[1] *= m_light_color[1];
color.bgra[2] *= m_light_color[2];
for (int i = 0; i < 3; ++i)
{
color[i] = b3Min(int(m_ambient_coefficient*color[i] + shadow*(m_diffuse_coefficient*diffuse+m_specular_coefficient*specular)*color[i]*m_light_color[i]), 255);
}
return false;
@@ -175,6 +173,9 @@ m_objectIndex(-1)
m_lightColor.setValue(1, 1, 1);
m_localScaling.setValue(1,1,1);
m_modelMatrix = Matrix::identity();
m_lightAmbientCoeff = 0.6;
m_lightDiffuseCoeff = 0.35;
m_lightSpecularCoeff = 0.05;
}
@@ -195,6 +196,9 @@ m_objectIndex(objectIndex)
m_lightColor.setValue(1, 1, 1);
m_localScaling.setValue(1,1,1);
m_modelMatrix = Matrix::identity();
m_lightAmbientCoeff = 0.6;
m_lightDiffuseCoeff = 0.35;
m_lightSpecularCoeff = 0.05;
}
@@ -214,6 +218,9 @@ m_objectIndex(-1)
m_lightColor.setValue(1, 1, 1);
m_localScaling.setValue(1,1,1);
m_modelMatrix = Matrix::identity();
m_lightAmbientCoeff = 0.6;
m_lightDiffuseCoeff = 0.35;
m_lightSpecularCoeff = 0.05;
}
@@ -233,6 +240,9 @@ m_objectIndex(objectIndex)
m_lightColor.setValue(1, 1, 1);
m_localScaling.setValue(1,1,1);
m_modelMatrix = Matrix::identity();
m_lightAmbientCoeff = 0.6;
m_lightDiffuseCoeff = 0.35;
m_lightSpecularCoeff = 0.05;
}
@@ -429,7 +439,7 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData)
Matrix modelViewMatrix = renderData.m_viewMatrix*renderData.m_modelMatrix;
Vec3f localScaling(renderData.m_localScaling[0],renderData.m_localScaling[1],renderData.m_localScaling[2]);
Shader shader(model, light_dir_local, light_color, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, renderData.m_viewportMatrix, localScaling, model->getColorRGBA(), width, height, shadowBufferPtr);
Shader shader(model, light_dir_local, light_color, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, renderData.m_viewportMatrix, localScaling, model->getColorRGBA(), width, height, shadowBufferPtr, renderData.m_lightAmbientCoeff, renderData.m_lightDiffuseCoeff, renderData.m_lightSpecularCoeff);
for (int i=0; i<model->nfaces(); i++)
{

View File

@@ -20,6 +20,9 @@ struct TinyRenderObjectData
btVector3 m_lightDirWorld;
btVector3 m_lightColor;
float m_lightDistance;
float m_lightAmbientCoeff;
float m_lightDiffuseCoeff;
float m_lightSpecularCoeff;
//Model (vertices, indices, textures, shader)
Matrix m_modelMatrix;

View File

@@ -2582,7 +2582,7 @@ static PyObject* pybullet_getContactPointData(PyObject* self, PyObject* args, Py
/// Render an image from the current timestep of the simulation, width, height are required, other args are optional
// getCameraImage(w, h, view[16], projection[16], lightDir[3], lightColor[3], lightDist, hasShadow)
// getCameraImage(w, h, view[16], projection[16], lightDir[3], lightColor[3], lightDist, hasShadow, lightAmbientCoeff, lightDiffuseCoeff, lightSpecularCoeff)
static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObject *keywds)
{
/// request an image from a simulated camera, using a software renderer.
@@ -2596,6 +2596,9 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
float lightColor[3];
float lightDist = 10.0;
int hasShadow = 0;
float lightAmbientCoeff = 0.6;
float lightDiffuseCoeff = 0.35;
float lightSpecularCoeff = 0.05;
// inialize cmd
b3SharedMemoryCommandHandle command;
@@ -2608,9 +2611,9 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
command = b3InitRequestCameraImage(sm);
// 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", NULL };
static char *kwlist[] = { "width", "height", "viewMatrix", "projectionMatrix", "lightDirection", "lightColor", "lightDistance", "shadow", "lightAmbientCoeff", "lightDiffuseCoeff", "lightSpecularCoeff", NULL };
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|OOOOfi", kwlist, &width, &height, &objViewMat, &objProjMat, &lightDirObj, &lightColorObj, &lightDist, &hasShadow))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|OOOOfifff", kwlist, &width, &height, &objViewMat, &objProjMat, &lightDirObj, &lightColorObj, &lightDist, &hasShadow, &lightAmbientCoeff, &lightDiffuseCoeff, &lightSpecularCoeff))
{
return NULL;
}
@@ -2635,6 +2638,10 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
b3RequestCameraImageSetLightDistance(command, lightDist);
b3RequestCameraImageSetShadow(command, hasShadow);
b3RequestCameraImageSetLightAmbientCoeff(command, lightAmbientCoeff);
b3RequestCameraImageSetLightDiffuseCoeff(command, lightDiffuseCoeff);
b3RequestCameraImageSetLightSpecularCoeff(command, lightSpecularCoeff);
if (b3CanSubmitCommand(sm))
{
@@ -3730,7 +3737,7 @@ static PyMethodDef SpamMethods[] = {
{ "getCameraImage",(PyCFunction)pybullet_getCameraImage, METH_VARARGS| METH_KEYWORDS,
"Render an image (given the pixel resolution width, height, camera viewMatrix "
", projectionMatrix, lightDirection, lightColor, lightDistance, and shadow), and return the "
", projectionMatrix, lightDirection, lightColor, lightDistance, shadow, lightAmbientCoeff, lightDiffuseCoeff, and lightSpecularCoeff), and return the "
"8-8-8bit RGB pixel data and floating point depth values"
#ifdef PYBULLET_USE_NUMPY
" as NumPy arrays"