Expose ambient, diffuse and specular coefficient of the light.

This commit is contained in:
yunfeibai
2016-12-06 15:21:35 -08:00
parent 08b449f149
commit c253c750b9
11 changed files with 145 additions and 13 deletions

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);