Merge remote-tracking branch 'bp/master'

This commit is contained in:
Erwin Coumans
2016-11-29 19:14:04 -08:00
25 changed files with 20758 additions and 100 deletions

10
data/torus/plane_only.mtl Normal file
View File

@@ -0,0 +1,10 @@
# Blender MTL File: 'None'
# Material Count: 1
newmtl None
Ns 0
Ka 0.000000 0.000000 0.000000
Kd 0.8 0.8 0.8
Ks 0.8 0.8 0.8
d 1
illum 2

7913
data/torus/plane_only.obj Normal file

File diff suppressed because it is too large Load Diff

10
data/torus/torus.mtl Normal file
View File

@@ -0,0 +1,10 @@
# Blender MTL File: 'None'
# Material Count: 1
newmtl None
Ns 0
Ka 0.000000 0.000000 0.000000
Kd 0.8 0.8 0.8
Ks 0.8 0.8 0.8
d 1
illum 2

1446
data/torus/torus.obj Normal file

File diff suppressed because it is too large Load Diff

33
data/torus/torus.urdf Normal file
View File

@@ -0,0 +1,33 @@
<?xml version="0.0" ?>
<robot name="cube.urdf">
<link name="baseLink">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="1.0"/>
<inertia_scaling value="3.0"/>
<contact_cfm value="0.0"/>
<contact_erp value="1.0"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value=".1"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="torus.obj" scale=".3 .3 .3"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="torus.obj" scale=".3 .3 .3"/>
</geometry>
</collision>
</link>
</robot>

12
data/torus/torus_only.mtl Normal file
View File

@@ -0,0 +1,12 @@
# Blender MTL File: 'None'
# Material Count: 1
newmtl None
Ns 0.000000
Ka 0.000000 0.000000 0.000000
Kd 0.800000 0.800000 0.800000
Ks 0.800000 0.800000 0.800000
Ke 0.000000 0.000000 0.000000
Ni 1.000000
d 1.000000
illum 2

1474
data/torus/torus_only.obj Normal file

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,10 @@
# Blender MTL File: 'None'
# Material Count: 1
newmtl None
Ns 0
Ka 0.000000 0.000000 0.000000
Kd 0.8 0.8 0.8
Ks 0.8 0.8 0.8
d 1
illum 2

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,33 @@
<?xml version="0.0" ?>
<robot name="cube.urdf">
<link name="baseLink">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="1.0"/>
<inertia_scaling value="3.0"/>
<contact_cfm value="0.0"/>
<contact_erp value="1.0"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value=".1"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="torus_with_plane.obj" scale=".3 .3 .3"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="torus_with_plane.obj" scale=".3 .3 .3"/>
</geometry>
</collision>
</link>
</robot>

View File

@@ -0,0 +1,48 @@
<?xml version="0.0" ?>
<robot name="cube.urdf">
<link name="baseLink">
<contact>
<lateral_friction value="1.0"/>
<rolling_friction value="1.0"/>
<inertia_scaling value="3.0"/>
<contact_cfm value="0.0"/>
<contact_erp value="1.0"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value=".1"/>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="torus_only.obj" scale=".3 .3 .3"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="plane_only.obj" scale=".3 .3 .3"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="torus_only.obj" scale=".3 .3 .3"/>
</geometry>
</collision>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="plane_only.obj" scale=".3 .3 .3"/>
</geometry>
</collision>
</link>
</robot>

View File

@@ -23,6 +23,7 @@ struct TinyRendererSetupInternalData
TGAImage m_rgbColorBuffer;
b3AlignedObjectArray<float> m_depthBuffer;
b3AlignedObjectArray<float> m_shadowBuffer;
b3AlignedObjectArray<int> m_segmentationMaskBuffer;
@@ -53,6 +54,7 @@ struct TinyRendererSetupInternalData
m_animateRenderer(0)
{
m_depthBuffer.resize(m_width*m_height);
m_shadowBuffer.resize(m_width*m_height);
// m_segmentationMaskBuffer.resize(m_width*m_height);
}
@@ -152,7 +154,7 @@ TinyRendererSetup::TinyRendererSetup(struct GUIHelperInterface* gui)
const char* fileName = "textured_sphere_smooth.obj";
fileName = "cube.obj";
fileName = "torus/torus_with_plane.obj";
{
@@ -188,6 +190,7 @@ TinyRendererSetup::TinyRendererSetup(struct GUIHelperInterface* gui)
TinyRenderObjectData* ob = new TinyRenderObjectData(
m_internalData->m_rgbColorBuffer,
m_internalData->m_depthBuffer,
m_internalData->m_shadowBuffer,
&m_internalData->m_segmentationMaskBuffer,
m_internalData->m_renderObjects.size());
@@ -328,6 +331,7 @@ void TinyRendererSetup::stepSimulation(float deltaTime)
{
m_internalData->m_rgbColorBuffer.set(x,y,clearColor);
m_internalData->m_depthBuffer[x+y*m_internalData->m_width] = -1e30f;
m_internalData->m_shadowBuffer[x+y*m_internalData->m_width] = -1e30f;
}
}
@@ -339,7 +343,44 @@ void TinyRendererSetup::stepSimulation(float deltaTime)
render->getActiveCamera()->getCameraViewMatrix(viewMat);
render->getActiveCamera()->getCameraProjectionMatrix(projMat);
for (int o=0;o<this->m_internalData->m_renderObjects.size();o++)
{
const btTransform& tr = m_internalData->m_transforms[o];
tr.getOpenGLMatrix(modelMat2);
for (int i=0;i<4;i++)
{
for (int j=0;j<4;j++)
{
m_internalData->m_renderObjects[o]->m_modelMatrix[i][j] = float(modelMat2[i+4*j]);
m_internalData->m_renderObjects[o]->m_viewMatrix[i][j] = viewMat[i+4*j];
m_internalData->m_renderObjects[o]->m_projectionMatrix[i][j] = projMat[i+4*j];
btVector3 lightDirWorld;
switch (m_app->getUpAxis())
{
case 1:
lightDirWorld = btVector3(-50.f,100,30);
break;
case 2:
lightDirWorld = btVector3(-50.f,30,100);
break;
default:{}
};
m_internalData->m_renderObjects[o]->m_lightDirWorld = lightDirWorld.normalized();
btVector3 lightColor(1.0,1.0,1.0);
m_internalData->m_renderObjects[o]->m_lightColor = lightColor;
m_internalData->m_renderObjects[o]->m_lightDistance = 10.0;
}
}
TinyRenderer::renderObjectDepth(*m_internalData->m_renderObjects[o]);
}
for (int o=0;o<this->m_internalData->m_renderObjects.size();o++)
{
@@ -370,6 +411,11 @@ void TinyRendererSetup::stepSimulation(float deltaTime)
m_internalData->m_renderObjects[o]->m_lightDirWorld = lightDirWorld.normalized();
btVector3 lightColor(1.0,1.0,1.0);
m_internalData->m_renderObjects[o]->m_lightColor = lightColor;
m_internalData->m_renderObjects[o]->m_lightDistance = 10.0;
}
}
TinyRenderer::renderObject(*m_internalData->m_renderObjects[o]);

View File

@@ -1332,6 +1332,24 @@ void b3RequestCameraImageSetLightColor(b3SharedMemoryCommandHandle commandHandle
command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR;
}
void b3RequestCameraImageSetLightDistance(b3SharedMemoryCommandHandle commandHandle, float lightDistance)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA);
command->m_requestPixelDataArguments.m_lightDistance = lightDistance;
command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_LIGHT_DISTANCE;
}
void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, int hasShadow)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_REQUEST_CAMERA_IMAGE_DATA);
command->m_requestPixelDataArguments.m_hasShadow = hasShadow;
command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_SHADOW;
}
void b3ComputeViewMatrixFromPositions(const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3], float viewMatrix[16])
{
b3Vector3 eye = b3MakeVector3(cameraPosition[0], cameraPosition[1], cameraPosition[2]);

View File

@@ -104,6 +104,8 @@ void b3RequestCameraImageSetCameraMatrices(b3SharedMemoryCommandHandle command,
void b3RequestCameraImageSetPixelResolution(b3SharedMemoryCommandHandle command, int width, int height );
void b3RequestCameraImageSetLightDirection(b3SharedMemoryCommandHandle commandHandle, const float lightDirection[3]);
void b3RequestCameraImageSetLightColor(b3SharedMemoryCommandHandle commandHandle, const float lightColor[3]);
void b3RequestCameraImageSetLightDistance(b3SharedMemoryCommandHandle commandHandle, float lightDistance);
void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, int hasShadow);
void b3RequestCameraImageSelectRenderer(b3SharedMemoryCommandHandle commandHandle, int renderer);
void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImageData* imageData);

View File

@@ -89,10 +89,10 @@ protected:
virtual void resetCamera()
{
float dist = 4;
float pitch = 193;
float yaw = 25;
float targetPos[3]={0,0,0.5};//-3,2.8,-2.5};
float dist = 4;
float pitch = 193;
float yaw = 25;
float targetPos[3]={0,0,0.5};//-3,2.8,-2.5};
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
}
@@ -481,6 +481,22 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
}
break;
}
case CMD_SET_SHADOW:
{
b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle);
float viewMatrix[16];
float projectionMatrix[16];
m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix);
m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix);
b3RequestCameraImageSetCameraMatrices(commandHandle, viewMatrix,projectionMatrix);
b3RequestCameraImageSetPixelResolution(commandHandle, camVisualizerWidth,camVisualizerHeight);
bool hasShadow = true;
b3RequestCameraImageSetShadow(commandHandle, hasShadow);
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
break;
}
default:
{
b3Error("Unknown buttonId");
@@ -556,6 +572,7 @@ void PhysicsClientExample::createButtons()
createButton("Load URDF",CMD_LOAD_URDF, isTrigger);
createButton("Load SDF",CMD_LOAD_SDF, isTrigger);
createButton("Save World",CMD_SAVE_WORLD, isTrigger);
createButton("Set Shadow",CMD_SET_SHADOW, isTrigger);
createButton("Get Camera Image",CMD_REQUEST_CAMERA_IMAGE_DATA,isTrigger);
createButton("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger);
createButton("Realtime Sim",CMD_CUSTOM_SET_REALTIME_SIMULATION, isTrigger);

View File

@@ -1426,6 +1426,16 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
m_data->m_visualConverter.setLightColor(clientCmd.m_requestPixelDataArguments.m_lightColor[0], clientCmd.m_requestPixelDataArguments.m_lightColor[1], clientCmd.m_requestPixelDataArguments.m_lightColor[2]);
}
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_LIGHT_DISTANCE) != 0)
{
m_data->m_visualConverter.setLightDistance(clientCmd.m_requestPixelDataArguments.m_lightDistance);
}
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_SET_SHADOW) != 0)
{
m_data->m_visualConverter.setShadow(clientCmd.m_requestPixelDataArguments.m_hasShadow);
}
if ((clientCmd.m_updateFlags & REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES)!=0)
{
m_data->m_visualConverter.render(

View File

@@ -144,6 +144,8 @@ struct RequestPixelDataArgs
int m_pixelHeight;
float m_lightDirection[3];
float m_lightColor[3];
float m_lightDistance;
int m_hasShadow;
};
enum EnumRequestPixelDataUpdateFlags
@@ -152,6 +154,8 @@ enum EnumRequestPixelDataUpdateFlags
REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT=2,
REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION=4,
REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR=8,
REQUEST_PIXEL_ARGS_SET_LIGHT_DISTANCE=16,
REQUEST_PIXEL_ARGS_SET_SHADOW=32,
//don't exceed (1<<15), because this enum is shared with EnumRenderer in SharedMemoryPublic.h
};

View File

@@ -40,6 +40,7 @@ enum EnumSharedMemoryClientCommand
CMD_REQUEST_VISUAL_SHAPE_INFO,
CMD_UPDATE_VISUAL_SHAPE,
CMD_LOAD_TEXTURE,
CMD_SET_SHADOW,
CMD_USER_DEBUG_DRAW,
//don't go beyond this command!

View File

@@ -36,7 +36,6 @@ subject to the following restrictions:
#include "../TinyRenderer/model.h"
#include "../ThirdPartyLibs/stb_image/stb_image.h"
enum MyFileType
{
MY_FILE_STL=1,
@@ -72,11 +71,15 @@ struct TinyRendererVisualShapeConverterInternalData
TGAImage m_rgbColorBuffer;
b3AlignedObjectArray<MyTexture2> m_textures;
b3AlignedObjectArray<float> m_depthBuffer;
b3AlignedObjectArray<float> m_shadowBuffer;
b3AlignedObjectArray<int> m_segmentationMaskBuffer;
btVector3 m_lightDirection;
bool m_hasLightDirection;
btVector3 m_lightColor;
bool m_hasLightColor;
float m_lightDistance;
bool m_hasLightDistance;
bool m_hasShadow;
SimpleCamera m_camera;
@@ -86,9 +89,11 @@ struct TinyRendererVisualShapeConverterInternalData
m_swHeight(START_HEIGHT),
m_rgbColorBuffer(START_WIDTH,START_HEIGHT,TGAImage::RGB),
m_hasLightDirection(false),
m_hasLightColor(false)
m_hasLightColor(false),
m_hasShadow(false)
{
m_depthBuffer.resize(m_swWidth*m_swHeight);
m_shadowBuffer.resize(m_swWidth*m_swHeight);
m_segmentationMaskBuffer.resize(m_swWidth*m_swHeight,-1);
}
@@ -126,6 +131,17 @@ void TinyRendererVisualShapeConverter::setLightColor(float x, float y, float z)
m_data->m_hasLightColor = true;
}
void TinyRendererVisualShapeConverter::setLightDistance(float dist)
{
m_data->m_lightDistance = dist;
m_data->m_hasLightDistance = true;
}
void TinyRendererVisualShapeConverter::setShadow(bool hasShadow)
{
m_data->m_hasShadow = hasShadow;
}
void convertURDFToVisualShape(const UrdfVisual* visual, const char* urdfPathPrefix, const btTransform& visualTransform, btAlignedObjectArray<GLInstanceVertex>& verticesOut, btAlignedObjectArray<int>& indicesOut, btAlignedObjectArray<MyTexture2>& texturesOut, b3VisualShapeData& visualShapeOut)
{
@@ -552,7 +568,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, bodyUniqueId);
TinyRenderObjectData* tinyObj = new TinyRenderObjectData(m_data->m_rgbColorBuffer,m_data->m_depthBuffer, m_data->m_shadowBuffer, &m_data->m_segmentationMaskBuffer, bodyUniqueId);
unsigned char* textureImage=0;
int textureWidth=0;
int textureHeight=0;
@@ -658,6 +674,7 @@ void TinyRendererVisualShapeConverter::clearBuffers(TGAColor& clearColor)
{
m_data->m_rgbColorBuffer.set(x,y,clearColor);
m_data->m_depthBuffer[x+y*m_data->m_swWidth] = -1e30f;
m_data->m_shadowBuffer[x+y*m_data->m_swWidth] = -1e30f;
m_data->m_segmentationMaskBuffer[x+y*m_data->m_swWidth] = -1;
}
}
@@ -718,15 +735,63 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo
lightColor = m_data->m_lightColor;
}
// printf("num m_swRenderInstances = %d\n", m_data->m_swRenderInstances.size());
for (int i=0;i<m_data->m_swRenderInstances.size();i++)
float lightDistance = 2.0;
if (m_data->m_hasLightDistance)
{
TinyRendererObjectArray** visualArrayPtr = m_data->m_swRenderInstances.getAtIndex(i);
lightDistance = m_data->m_hasLightDistance;
}
if (m_data->m_hasShadow)
{
for (int n=0;n<m_data->m_swRenderInstances.size();n++)
{
TinyRendererObjectArray** visualArrayPtr = m_data->m_swRenderInstances.getAtIndex(n);
if (0==visualArrayPtr)
continue;//can this ever happen?
TinyRendererObjectArray* visualArray = *visualArrayPtr;
btHashPtr colObjHash = m_data->m_swRenderInstances.getKeyAtIndex(n);
const btCollisionObject* colObj = (btCollisionObject*) colObjHash.getPointer();
for (int v=0;v<visualArray->m_renderObjects.size();v++)
{
TinyRenderObjectData* renderObj = visualArray->m_renderObjects[v];
//sync the object transform
const btTransform& tr = colObj->getWorldTransform();
tr.getOpenGLMatrix(modelMat);
for (int i=0;i<4;i++)
{
for (int j=0;j<4;j++)
{
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_lightColor = lightColor;
renderObj->m_lightDistance = lightDistance;
TinyRenderer::renderObjectDepth(*renderObj);
}
}
}
for (int n=0;n<m_data->m_swRenderInstances.size();n++)
{
TinyRendererObjectArray** visualArrayPtr = m_data->m_swRenderInstances.getAtIndex(n);
if (0==visualArrayPtr)
continue;//can this ever happen?
TinyRendererObjectArray* visualArray = *visualArrayPtr;
btHashPtr colObjHash = m_data->m_swRenderInstances.getKeyAtIndex(i);
btHashPtr colObjHash = m_data->m_swRenderInstances.getKeyAtIndex(n);
const btCollisionObject* colObj = (btCollisionObject*) colObjHash.getPointer();
@@ -749,11 +814,12 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo
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_lightColor = lightColor;
}
}
renderObj->m_localScaling = colObj->getCollisionShape()->getLocalScaling();
renderObj->m_lightDirWorld = lightDirWorld;
renderObj->m_lightColor = lightColor;
renderObj->m_lightDistance = lightDistance;
TinyRenderer::renderObject(*renderObj);
}
}
@@ -772,6 +838,7 @@ void TinyRendererVisualShapeConverter::render(const float viewMat[16], const flo
for (int i=0;i<m_data->m_swWidth;i++)
{
btSwap(m_data->m_depthBuffer[l1+i],m_data->m_depthBuffer[l2+i]);
btSwap(m_data->m_shadowBuffer[l1+i],m_data->m_shadowBuffer[l2+i]);
btSwap(m_data->m_segmentationMaskBuffer[l1+i],m_data->m_segmentationMaskBuffer[l2+i]);
}
}
@@ -791,6 +858,7 @@ void TinyRendererVisualShapeConverter::setWidthAndHeight(int width, int height)
m_data->m_swHeight = height;
m_data->m_depthBuffer.resize(m_data->m_swWidth*m_data->m_swHeight);
m_data->m_shadowBuffer.resize(m_data->m_swWidth*m_data->m_swHeight);
m_data->m_segmentationMaskBuffer.resize(m_data->m_swWidth*m_data->m_swHeight);
m_data->m_rgbColorBuffer = TGAImage(width, height, TGAImage::RGB);

View File

@@ -34,6 +34,8 @@ struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter
void setWidthAndHeight(int width, int height);
void setLightDirection(float x, float y, float z);
void setLightColor(float x, float y, float z);
void setLightDistance(float dist);
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

@@ -13,7 +13,51 @@
#include "LinearMath/btAlignedObjectArray.h"
#include "LinearMath/btVector3.h"
struct DepthShader : public IShader {
Model* m_model;
Matrix& m_modelMat;
Matrix m_invModelMat;
Matrix& m_projectionMat;
Vec3f m_localScaling;
Matrix& m_lightModelView;
float m_lightDistance;
mat<2,3,float> varying_uv; // triangle uv coordinates, written by the vertex shader, read by the fragment shader
mat<4,3,float> varying_tri; // triangle coordinates (clip coordinates), written by VS, read by FS
mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS
DepthShader(Model* model, Matrix& lightModelView, Matrix& projectionMat, Matrix& modelMat, Vec3f localScaling, float lightDistance)
:m_model(model),
m_lightModelView(lightModelView),
m_projectionMat(projectionMat),
m_modelMat(modelMat),
m_localScaling(localScaling),
m_lightDistance(lightDistance)
{
m_invModelMat = m_modelMat.invert_transpose();
}
virtual Vec4f vertex(int iface, int nthvert) {
Vec2f uv = m_model->uv(iface, nthvert);
varying_uv.set_col(nthvert, uv);
varying_nrm.set_col(nthvert, proj<3>(m_invModelMat*embed<4>(m_model->normal(iface, nthvert), 0.f)));
Vec3f unScaledVert = m_model->vert(iface, nthvert);
Vec3f scaledVert=Vec3f(unScaledVert[0]*m_localScaling[0],
unScaledVert[1]*m_localScaling[1],
unScaledVert[2]*m_localScaling[2]);
Vec4f gl_Vertex = m_projectionMat*m_lightModelView*embed<4>(scaledVert);
varying_tri.set_col(nthvert, gl_Vertex);
return gl_Vertex;
}
virtual bool fragment(Vec3f bar, TGAColor &color) {
Vec4f p = varying_tri*bar;
color = TGAColor(255, 255, 255)*(p[2]/m_lightDistance);
return false;
}
};
struct Shader : public IShader {
@@ -21,50 +65,69 @@ struct Shader : public IShader {
Vec3f m_light_dir_local;
Vec3f m_light_color;
Matrix& m_modelMat;
Matrix m_invModelMat;
Matrix m_invModelMat;
Matrix& m_modelView1;
Matrix& m_projectionMatrix;
Matrix& m_projectionMat;
Vec3f m_localScaling;
Matrix& m_lightModelView;
Vec4f m_colorRGBA;
Matrix& m_viewportMat;
b3AlignedObjectArray<float>& m_shadowBuffer;
int m_width;
int m_height;
int m_index;
mat<2,3,float> varying_uv; // triangle uv coordinates, written by the vertex shader, read by the fragment shader
mat<4,3,float> varying_tri; // triangle coordinates (clip coordinates), written by VS, read by FS
mat<4,3,float> varying_tri_light_view;
mat<3,3,float> varying_nrm; // normal per vertex to be interpolated by FS
//mat<3,3,float> ndc_tri; // triangle in normalized device coordinates
Shader(Model* model, Vec3f light_dir_local, Vec3f light_color, Matrix& modelView, Matrix& projectionMatrix, Matrix& modelMat, Vec3f localScaling, const Vec4f& colorRGBA)
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)
:m_model(model),
m_light_dir_local(light_dir_local),
m_light_color(light_color),
m_modelView1(modelView),
m_projectionMatrix(projectionMatrix),
m_lightModelView(lightModelView),
m_projectionMat(projectionMat),
m_modelMat(modelMat),
m_localScaling(localScaling),
m_colorRGBA(colorRGBA)
m_viewportMat(viewportMat),
m_localScaling(localScaling),
m_colorRGBA(colorRGBA),
m_width(width),
m_height(height),
m_shadowBuffer(shadowBuffer)
{
m_invModelMat = m_modelMat.invert_transpose();
}
virtual Vec4f vertex(int iface, int nthvert) {
Vec2f uv = m_model->uv(iface, nthvert);
varying_uv.set_col(nthvert, uv);
//varying_nrm.set_col(nthvert, proj<3>((m_projectionMatrix*m_modelView).invert_transpose()*embed<4>(m_model->normal(iface, nthvert), 0.f)));
varying_nrm.set_col(nthvert, proj<3>(m_invModelMat*embed<4>(m_model->normal(iface, nthvert), 0.f)));
//m_localNormal = m_model->normal(iface, nthvert);
//varying_nrm.set_col(nthvert, m_model->normal(iface, nthvert));
Vec3f unScaledVert = m_model->vert(iface, nthvert);
Vec3f scaledVert=Vec3f(unScaledVert[0]*m_localScaling[0],
unScaledVert[1]*m_localScaling[1],
unScaledVert[2]*m_localScaling[2]);
Vec4f gl_Vertex = m_projectionMatrix*m_modelView1*embed<4>(scaledVert);
Vec4f gl_Vertex = m_projectionMat*m_modelView1*embed<4>(scaledVert);
varying_tri.set_col(nthvert, gl_Vertex);
Vec4f gl_VertexLightView = m_projectionMat*m_lightModelView*embed<4>(scaledVert);
varying_tri_light_view.set_col(nthvert, gl_VertexLightView);
return gl_Vertex;
}
virtual bool fragment(Vec3f bar, TGAColor &color) {
Vec4f p = m_viewportMat*(varying_tri_light_view*bar);
float depth = p[2];
p = p/p[3];
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[idx]<-depth+0.2); // magic coeff to avoid z-fighting
Vec3f bn = (varying_nrm*bar).normalize();
Vec2f uv = varying_uv*bar;
@@ -72,13 +135,13 @@ 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 ambient_coefficient = 0.6;
float diffuse_coefficient = 0.35;
float specular_coefficient = 0.05;
float intensity = ambient_coefficient + b3Min(diffuse * diffuse_coefficient + specular * specular_coefficient, 1.0f - ambient_coefficient);
color = m_model->diffuse(uv) * intensity;
color = m_model->diffuse(uv) * intensity * shadow;
//warning: bgra color is swapped to rgba to upload texture
color.bgra[0] *= m_colorRGBA[0];
@@ -91,12 +154,14 @@ struct Shader : public IShader {
color.bgra[2] *= m_light_color[2];
return false;
}
};
TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray<float>&depthBuffer)
TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray<float>&depthBuffer,b3AlignedObjectArray<float>&shadowBuffer)
:m_rgbColorBuffer(rgbColorBuffer),
m_depthBuffer(depthBuffer),
m_shadowBuffer(shadowBuffer),
m_segmentationMaskBufferPtr(0),
m_model(0),
m_userData(0),
@@ -115,9 +180,10 @@ m_objectIndex(-1)
TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray<float>&depthBuffer, b3AlignedObjectArray<int>* segmentationMaskBuffer, int objectIndex)
TinyRenderObjectData::TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray<float>&depthBuffer, b3AlignedObjectArray<float>&shadowBuffer, b3AlignedObjectArray<int>* segmentationMaskBuffer, int objectIndex)
:m_rgbColorBuffer(rgbColorBuffer),
m_depthBuffer(depthBuffer),
m_shadowBuffer(shadowBuffer),
m_segmentationMaskBufferPtr(segmentationMaskBuffer),
m_model(0),
m_userData(0),
@@ -262,43 +328,80 @@ TinyRenderObjectData::~TinyRenderObjectData()
delete m_model;
}
void TinyRenderer::renderObject(TinyRenderObjectData& renderData)
void TinyRenderer::renderObjectDepth(TinyRenderObjectData& renderData)
{
int width = renderData.m_rgbColorBuffer.get_width();
int height = renderData.m_rgbColorBuffer.get_height();
int width = renderData.m_rgbColorBuffer.get_width();
int height = renderData.m_rgbColorBuffer.get_height();
Vec3f light_dir_local = Vec3f(renderData.m_lightDirWorld[0],renderData.m_lightDirWorld[1],renderData.m_lightDirWorld[2]);
Vec3f light_color = Vec3f(renderData.m_lightColor[0],renderData.m_lightColor[1],renderData.m_lightColor[2]);
Vec3f light_dir_local = Vec3f(renderData.m_lightDirWorld[0],renderData.m_lightDirWorld[1],renderData.m_lightDirWorld[2]);
float light_distance = renderData.m_lightDistance;
Model* model = renderData.m_model;
if (0==model)
return;
renderData.m_viewportMatrix = viewport(0,0,width, height);
b3AlignedObjectArray<float>& shadowbuffer = renderData.m_shadowBuffer;
int* segmentationMaskBufferPtr = 0;
renderData.m_viewportMatrix = viewport(0,0,width, height);
TGAImage depthFrame(width, height, TGAImage::RGB);
{
// light target is set to be the origin, and the up direction is set to be vertical up.
Matrix lightViewMatrix = lookat(light_dir_local*light_distance, Vec3f(0.0,0.0,0.0), Vec3f(0.0,0.0,1.0));
Matrix lightModelViewMatrix = lightViewMatrix*renderData.m_modelMatrix;
Matrix lightViewProjectionMatrix = renderData.m_projectionMatrix;
Vec3f localScaling(renderData.m_localScaling[0],renderData.m_localScaling[1],renderData.m_localScaling[2]);
DepthShader shader(model, lightModelViewMatrix, lightViewProjectionMatrix,renderData.m_modelMatrix, localScaling, light_distance);
for (int i=0; i<model->nfaces(); i++)
{
for (int j=0; j<3; j++) {
shader.vertex(i, j);
}
triangle(shader.varying_tri, shader, depthFrame, &shadowbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex);
}
}
}
void TinyRenderer::renderObject(TinyRenderObjectData& renderData)
{
int width = renderData.m_rgbColorBuffer.get_width();
int height = renderData.m_rgbColorBuffer.get_height();
Vec3f light_dir_local = Vec3f(renderData.m_lightDirWorld[0],renderData.m_lightDirWorld[1],renderData.m_lightDirWorld[2]);
Vec3f light_color = Vec3f(renderData.m_lightColor[0],renderData.m_lightColor[1],renderData.m_lightColor[2]);
float light_distance = renderData.m_lightDistance;
Model* model = renderData.m_model;
if (0==model)
return;
renderData.m_viewportMatrix = viewport(0,0,width, height);
b3AlignedObjectArray<float>& zbuffer = renderData.m_depthBuffer;
b3AlignedObjectArray<float>& shadowbuffer = renderData.m_shadowBuffer;
int* segmentationMaskBufferPtr = (renderData.m_segmentationMaskBufferPtr && renderData.m_segmentationMaskBufferPtr->size())?&renderData.m_segmentationMaskBufferPtr->at(0):0;
TGAImage& frame = renderData.m_rgbColorBuffer;
{
// light target is set to be the origin, and the up direction is set to be vertical up.
Matrix lightViewMatrix = lookat(light_dir_local*light_distance, Vec3f(0.0,0.0,0.0), Vec3f(0.0,0.0,1.0));
Matrix lightModelViewMatrix = lightViewMatrix*renderData.m_modelMatrix;
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, renderData.m_projectionMatrix,renderData.m_modelMatrix, localScaling, model->getColorRGBA());
//printf("Render %d triangles.\n",model->nfaces());
for (int i=0; i<model->nfaces(); i++)
{
Shader shader(model, light_dir_local, light_color, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, renderData.m_viewportMatrix, localScaling, model->getColorRGBA(), width, height, shadowbuffer);
for (int i=0; i<model->nfaces(); i++)
{
for (int j=0; j<3; j++) {
shader.vertex(i, j);
}
triangle(shader.varying_tri, shader, frame, &zbuffer[0], segmentationMaskBufferPtr, renderData.m_viewportMatrix, renderData.m_objectIndex);
}
}
}

View File

@@ -19,6 +19,7 @@ struct TinyRenderObjectData
btVector3 m_localScaling;
btVector3 m_lightDirWorld;
btVector3 m_lightColor;
float m_lightDistance;
//Model (vertices, indices, textures, shader)
Matrix m_modelMatrix;
@@ -29,10 +30,11 @@ struct TinyRenderObjectData
TGAImage& m_rgbColorBuffer;
b3AlignedObjectArray<float>& m_depthBuffer;//required, hence a reference
b3AlignedObjectArray<float>& m_shadowBuffer;
b3AlignedObjectArray<int>* m_segmentationMaskBufferPtr;//optional, hence a pointer
TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray<float>&depthBuffer);
TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray<float>&depthBuffer, b3AlignedObjectArray<int>* segmentationMaskBuffer,int objectIndex);
TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray<float>&depthBuffer,b3AlignedObjectArray<float>&shadowBuffer);
TinyRenderObjectData(TGAImage& rgbColorBuffer,b3AlignedObjectArray<float>&depthBuffer,b3AlignedObjectArray<float>&shadowBuffer, b3AlignedObjectArray<int>* segmentationMaskBuffer,int objectIndex);
virtual ~TinyRenderObjectData();
void loadModel(const char* fileName);
@@ -51,6 +53,7 @@ struct TinyRenderObjectData
class TinyRenderer
{
public:
static void renderObjectDepth(TinyRenderObjectData& renderData);
static void renderObject(TinyRenderObjectData& renderData);
};

View File

@@ -147,6 +147,7 @@ int main(int argc, char* argv[])
renderData.m_rgbColorBuffer.set(x,y,color);
renderData.m_depthBuffer[x+y*textureWidth] = -1e30f;
renderData.m_shadowBuffer[x+y*textureWidth] = -1e30f;
}
}

View File

@@ -4,9 +4,6 @@
#include "our_gl.h"
#include "Bullet3Common/b3MinMax.h"
IShader::~IShader() {}
Matrix viewport(int x, int y, int w, int h)
@@ -15,10 +12,10 @@ Matrix viewport(int x, int y, int w, int h)
Viewport = Matrix::identity();
Viewport[0][3] = x+w/2.f;
Viewport[1][3] = y+h/2.f;
Viewport[2][3] = 1.f;
Viewport[2][3] = .5f;
Viewport[0][0] = w/2.f;
Viewport[1][1] = h/2.f;
Viewport[2][2] = 0;
Viewport[2][2] = .5f;
return Viewport;
}
@@ -30,19 +27,33 @@ Matrix projection(float coeff) {
}
Matrix lookat(Vec3f eye, Vec3f center, Vec3f up) {
Vec3f z = (eye-center).normalize();
Vec3f x = cross(up,z).normalize();
Vec3f y = cross(z,x).normalize();
Matrix Minv = Matrix::identity();
Matrix Tr = Matrix::identity();
for (int i=0; i<3; i++) {
Minv[0][i] = x[i];
Minv[1][i] = y[i];
Minv[2][i] = z[i];
Tr[i][3] = -center[i];
}
Vec3f f = (center - eye).normalize();
Vec3f u = up.normalize();
Vec3f s = cross(f,u).normalize();
u = cross(s,f);
Matrix ModelView;
ModelView = Minv*Tr;
ModelView[0][0] = s.x;
ModelView[0][1] = s.y;
ModelView[0][2] = s.z;
ModelView[1][0] = u.x;
ModelView[1][1] = u.y;
ModelView[1][2] = u.z;
ModelView[2][0] =-f.x;
ModelView[2][1] =-f.y;
ModelView[2][2] =-f.z;
ModelView[3][0] = 0.f;
ModelView[3][1] = 0.f;
ModelView[3][2] = 0.f;
ModelView[0][3] = -(s[0]*eye[0]+s[1]*eye[1]+s[2]*eye[2]);
ModelView[1][3] = -(u[0]*eye[0]+u[1]*eye[1]+u[2]*eye[2]);
ModelView[2][3] = f[0]*eye[0]+f[1]*eye[1]+f[2]*eye[2];
ModelView[3][3] = 1.f;
return ModelView;
}
@@ -67,12 +78,10 @@ void triangle(mat<4,3,float> &clipc, IShader &shader, TGAImage &image, float *zb
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
//we don't clip triangles that cross the near plane, just discard them instead of showing artifacts
if (pts[0][3]<0 || pts[1][3] <0 || pts[2][3] <0)
return;
mat<3,2,float> pts2;
for (int i=0; i<3; i++) pts2[i] = proj<2>(pts[i]/pts[i][3]);
@@ -87,15 +96,11 @@ void triangle(mat<4,3,float> &clipc, IShader &shader, TGAImage &image, float *zb
}
}
Vec2i P;
TGAColor color;
for (P.x=bboxmin.x; P.x<=bboxmax.x; P.x++) {
for (P.y=bboxmin.y; P.y<=bboxmax.y; P.y++) {
Vec3f bc_screen = barycentric(pts2[0], pts2[1], pts2[2], P);
Vec3f bc_clip = Vec3f(bc_screen.x/pts[0][3], bc_screen.y/pts[1][3], bc_screen.z/pts[2][3]);
bc_clip = bc_clip/(bc_clip.x+bc_clip.y+bc_clip.z);
float frag_depth = -1*(clipc[2]*bc_clip);

View File

@@ -2451,7 +2451,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])
// getCameraImage(w, h, view[16], projection[16], lightDir[3], lightColor[3], lightDist, hasShadow)
static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObject *keywds)
{
/// request an image from a simulated camera, using a software renderer.
@@ -2463,6 +2463,8 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
float projectionMatrix[16];
float lightDir[3];
float lightColor[3];
float lightDist = 10.0;
int hasShadow = 0;
// inialize cmd
b3SharedMemoryCommandHandle command;
@@ -2474,10 +2476,10 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
command = b3InitRequestCameraImage(sm);
// set camera resolution, optionally view, projection matrix, light direction
static char *kwlist[] = { "width", "height", "viewMatrix", "projectionMatrix", "lightDirection", "lightColor", NULL };
// 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 };
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|OOOO", kwlist, &width, &height, &objViewMat, &objProjMat, &lightDirObj, &lightColorObj))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|OOOOfi", kwlist, &width, &height, &objViewMat, &objProjMat, &lightDirObj, &lightColorObj, &lightDist, &hasShadow))
{
return NULL;
}
@@ -2499,6 +2501,9 @@ static PyObject* pybullet_getCameraImage(PyObject* self, PyObject* args, PyObjec
b3RequestCameraImageSetLightColor(command, lightColor);
}
b3RequestCameraImageSetLightDistance(command, lightDist);
b3RequestCameraImageSetShadow(command, hasShadow);
if (b3CanSubmitCommand(sm))
{
@@ -3589,7 +3594,7 @@ static PyMethodDef SpamMethods[] = {
{ "getCameraImage",(PyCFunction)pybullet_getCameraImage, METH_VARARGS| METH_KEYWORDS,
"Render an image (given the pixel resolution width, height, camera viewMatrix "
", projectionMatrix and lightDirection), and return the "
", projectionMatrix, lightDirection, lightColor, lightDistance, and shadow), and return the "
"8-8-8bit RGB pixel data and floating point depth values"
#ifdef PYBULLET_USE_NUMPY
" as NumPy arrays"