Merge pull request #1560 from YunfeiBai/master
Add shader and example for projective texture.
This commit is contained in:
@@ -56,7 +56,8 @@ premake4 --file=stringifyKernel.lua --kernelfile="../btgui/OpenGLWindow/Shaders/
|
|||||||
premake4 --file=stringifyKernel.lua --kernelfile="../btgui/OpenGLWindow/Shaders/useShadowMapInstancingPS.glsl" --headerfile="../btgui/OpenGLWindow/Shaders/useShadowMapInstancingPS.h" --stringname="useShadowMapInstancingFragmentShader" stringify
|
premake4 --file=stringifyKernel.lua --kernelfile="../btgui/OpenGLWindow/Shaders/useShadowMapInstancingPS.glsl" --headerfile="../btgui/OpenGLWindow/Shaders/useShadowMapInstancingPS.h" --stringname="useShadowMapInstancingFragmentShader" stringify
|
||||||
premake4 --file=stringifyKernel.lua --kernelfile="../btgui/OpenGLWindow/Shaders/useShadowMapInstancingVS.glsl" --headerfile="../btgui/OpenGLWindow/Shaders/useShadowMapInstancingVS.h" --stringname="useShadowMapInstancingVertexShader" stringify
|
premake4 --file=stringifyKernel.lua --kernelfile="../btgui/OpenGLWindow/Shaders/useShadowMapInstancingVS.glsl" --headerfile="../btgui/OpenGLWindow/Shaders/useShadowMapInstancingVS.h" --stringname="useShadowMapInstancingVertexShader" stringify
|
||||||
|
|
||||||
|
premake4 --file=stringifyKernel.lua --kernelfile="../btgui/OpenGLWindow/Shaders/projectiveTextureInstancingPS.glsl" --headerfile="../btgui/OpenGLWindow/Shaders/projectiveTextureInstancingPS.h" --stringname="projectiveTextureInstancingFragmentShader" stringify
|
||||||
|
premake4 --file=stringifyKernel.lua --kernelfile="../btgui/OpenGLWindow/Shaders/projectiveTextureInstancingVS.glsl" --headerfile="../btgui/OpenGLWindow/Shaders/projectiveTextureInstancingVS.h" --stringname="projectiveTextureInstancingVertexShader" stringify
|
||||||
|
|
||||||
|
|
||||||
premake4 --file=stringifyKernel.lua --kernelfile="../Demos3/GpuDemos/broadphase/pairsKernel.cl" --headerfile="../Demos3/GpuDemos/broadphase/pairsKernel.h" --stringname="pairsKernelsCL" stringify
|
premake4 --file=stringifyKernel.lua --kernelfile="../Demos3/GpuDemos/broadphase/pairsKernel.cl" --headerfile="../Demos3/GpuDemos/broadphase/pairsKernel.h" --stringname="pairsKernelsCL" stringify
|
||||||
|
|||||||
@@ -62,6 +62,8 @@ eval '$mypremake --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWin
|
|||||||
|
|
||||||
eval '$mypremake --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.h" --stringname="useShadowMapInstancingFragmentShader" stringify'
|
eval '$mypremake --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.h" --stringname="useShadowMapInstancingFragmentShader" stringify'
|
||||||
eval '$mypremake --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.h" --stringname="useShadowMapInstancingVertexShader" stringify'
|
eval '$mypremake --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.h" --stringname="useShadowMapInstancingVertexShader" stringify'
|
||||||
|
eval '$mypremake --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/projectiveTextureInstancingPS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/projectiveTextureInstancingPS.h" --stringname="projectiveTextureInstancingFragmentShader" stringify'
|
||||||
|
eval '$mypremake --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/projectiveTextureInstancingVS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/projectiveTextureInstancingVS.h" --stringname="projectiveTextureInstancingVertexShader" stringify'
|
||||||
eval '$mypremake --file=stringifyKernel.lua --kernelfile="../examples/OpenCL/broadphase/pairsKernel.cl" --headerfile="../examples/OpenCL/broadphase/pairsKernel.h" --stringname="pairsKernelsCL" stringify'
|
eval '$mypremake --file=stringifyKernel.lua --kernelfile="../examples/OpenCL/broadphase/pairsKernel.cl" --headerfile="../examples/OpenCL/broadphase/pairsKernel.h" --stringname="pairsKernelsCL" stringify'
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -10,6 +10,8 @@ premake4 --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shade
|
|||||||
premake4 --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/createShadowMapInstancingVS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/createShadowMapInstancingVS.h" --stringname="createShadowMapInstancingVertexShader" stringify
|
premake4 --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/createShadowMapInstancingVS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/createShadowMapInstancingVS.h" --stringname="createShadowMapInstancingVertexShader" stringify
|
||||||
premake4 --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.h" --stringname="useShadowMapInstancingFragmentShader" stringify
|
premake4 --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.h" --stringname="useShadowMapInstancingFragmentShader" stringify
|
||||||
premake4 --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.h" --stringname="useShadowMapInstancingVertexShader" stringify
|
premake4 --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.h" --stringname="useShadowMapInstancingVertexShader" stringify
|
||||||
|
premake4 --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/projectiveTextureInstancingPS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/projectiveTextureInstancingPS.h" --stringname="projectiveTextureInstancingFragmentShader" stringify
|
||||||
|
premake4 --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/projectiveTextureInstancingVS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/projectiveTextureInstancingVS.h" --stringname="projectiveTextureInstancingVertexShader" stringify
|
||||||
premake4 --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/linesVS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/linesVS.h" --stringname="linesVertexShader" stringify
|
premake4 --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/linesVS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/linesVS.h" --stringname="linesVertexShader" stringify
|
||||||
premake4 --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/linesPS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/linesPS.h" --stringname="linesFragmentShader" stringify
|
premake4 --file=stringifyKernel.lua --kernelfile="../examples/OpenGLWindow/Shaders/linesPS.glsl" --headerfile="../examples/OpenGLWindow/Shaders/linesPS.h" --stringname="linesFragmentShader" stringify
|
||||||
|
|
||||||
|
|||||||
32
data/teddy_large.urdf
Normal file
32
data/teddy_large.urdf
Normal file
@@ -0,0 +1,32 @@
|
|||||||
|
<?xml version="0.0" ?>
|
||||||
|
<robot name="cube.urdf">
|
||||||
|
<link name="baseLink">
|
||||||
|
<contact>
|
||||||
|
<lateral_friction value="0.5"/>
|
||||||
|
<rolling_friction value="0.0"/>
|
||||||
|
<contact_cfm value="0.0"/>
|
||||||
|
<contact_erp value="1.0"/>
|
||||||
|
</contact>
|
||||||
|
<inertial>
|
||||||
|
<origin rpy="0 0 0" xyz="0.07 0.05 0.03"/>
|
||||||
|
<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="teddy2_VHACD_CHs.obj" scale="3 3 3"/>
|
||||||
|
</geometry>
|
||||||
|
<material name="red">
|
||||||
|
<color rgba="1 1 1 1"/>
|
||||||
|
</material>
|
||||||
|
</visual>
|
||||||
|
<collision>
|
||||||
|
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||||
|
<geometry>
|
||||||
|
<mesh filename="teddy2_VHACD_CHs.obj" scale="3 3 3"/>
|
||||||
|
</geometry>
|
||||||
|
</collision>
|
||||||
|
</link>
|
||||||
|
</robot>
|
||||||
|
|
||||||
@@ -29,4 +29,3 @@
|
|||||||
</collision>
|
</collision>
|
||||||
</link>
|
</link>
|
||||||
</robot>
|
</robot>
|
||||||
|
|
||||||
|
|||||||
@@ -16,6 +16,7 @@ enum
|
|||||||
B3_CREATE_SHADOWMAP_RENDERMODE,
|
B3_CREATE_SHADOWMAP_RENDERMODE,
|
||||||
B3_USE_SHADOWMAP_RENDERMODE,
|
B3_USE_SHADOWMAP_RENDERMODE,
|
||||||
B3_USE_SHADOWMAP_RENDERMODE_REFLECTION,
|
B3_USE_SHADOWMAP_RENDERMODE_REFLECTION,
|
||||||
|
B3_USE_PROJECTIVE_TEXTURE_RENDERMODE,
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -17,6 +17,7 @@ subject to the following restrictions:
|
|||||||
|
|
||||||
///todo: make this configurable in the gui
|
///todo: make this configurable in the gui
|
||||||
bool useShadowMap = true;// true;//false;//true;
|
bool useShadowMap = true;// true;//false;//true;
|
||||||
|
bool useProjectiveTexture = false;
|
||||||
int shadowMapWidth= 4096;
|
int shadowMapWidth= 4096;
|
||||||
int shadowMapHeight= 4096;
|
int shadowMapHeight= 4096;
|
||||||
float shadowMapWorldSize=10;
|
float shadowMapWorldSize=10;
|
||||||
@@ -74,6 +75,8 @@ float shadowMapWorldSize=10;
|
|||||||
#include "Shaders/createShadowMapInstancingPS.h"
|
#include "Shaders/createShadowMapInstancingPS.h"
|
||||||
#include "Shaders/useShadowMapInstancingVS.h"
|
#include "Shaders/useShadowMapInstancingVS.h"
|
||||||
#include "Shaders/useShadowMapInstancingPS.h"
|
#include "Shaders/useShadowMapInstancingPS.h"
|
||||||
|
#include "Shaders/projectiveTextureInstancingVS.h"
|
||||||
|
#include "Shaders/projectiveTextureInstancingPS.h"
|
||||||
#include "Shaders/linesPS.h"
|
#include "Shaders/linesPS.h"
|
||||||
#include "Shaders/linesVS.h"
|
#include "Shaders/linesVS.h"
|
||||||
|
|
||||||
@@ -281,6 +284,7 @@ static GLuint triangleIndexVbo=0;
|
|||||||
static GLuint linesShader; // The line renderer
|
static GLuint linesShader; // The line renderer
|
||||||
static GLuint useShadowMapInstancingShader; // The shadow instancing renderer
|
static GLuint useShadowMapInstancingShader; // The shadow instancing renderer
|
||||||
static GLuint createShadowMapInstancingShader; // The shadow instancing renderer
|
static GLuint createShadowMapInstancingShader; // The shadow instancing renderer
|
||||||
|
static GLuint projectiveTextureInstancingShader; // The projective texture instancing renderer
|
||||||
static GLuint instancingShader; // The instancing renderer
|
static GLuint instancingShader; // The instancing renderer
|
||||||
static GLuint instancingShaderPointSprite; // The point sprite instancing renderer
|
static GLuint instancingShaderPointSprite; // The point sprite instancing renderer
|
||||||
|
|
||||||
@@ -318,6 +322,20 @@ static GLint useShadow_shadowMap = 0;
|
|||||||
|
|
||||||
static GLint createShadow_depthMVP=0;
|
static GLint createShadow_depthMVP=0;
|
||||||
|
|
||||||
|
static GLint projectiveTexture_ViewMatrixInverse=0;
|
||||||
|
static GLint projectiveTexture_ModelViewMatrix=0;
|
||||||
|
static GLint projectiveTexture_lightSpecularIntensity = 0;
|
||||||
|
static GLint projectiveTexture_materialSpecularColor = 0;
|
||||||
|
static GLint projectiveTexture_MVP=0;
|
||||||
|
static GLint projectiveTexture_lightPosIn=0;
|
||||||
|
static GLint projectiveTexture_cameraPositionIn = 0;
|
||||||
|
static GLint projectiveTexture_materialShininessIn = 0;
|
||||||
|
|
||||||
|
static GLint projectiveTexture_ProjectionMatrix=0;
|
||||||
|
static GLint projectiveTexture_TextureMVP=0;
|
||||||
|
static GLint projectiveTexture_uniform_texture_diffuse = 0;
|
||||||
|
static GLint projectiveTexture_shadowMap = 0;
|
||||||
|
|
||||||
static GLint ModelViewMatrix=0;
|
static GLint ModelViewMatrix=0;
|
||||||
static GLint ProjectionMatrix=0;
|
static GLint ProjectionMatrix=0;
|
||||||
static GLint regularLightDirIn=0;
|
static GLint regularLightDirIn=0;
|
||||||
@@ -1215,7 +1233,24 @@ void GLInstancingRenderer::InitShaders()
|
|||||||
glGetIntegerv(GL_SMOOTH_LINE_WIDTH_RANGE, lineWidthRange);
|
glGetIntegerv(GL_SMOOTH_LINE_WIDTH_RANGE, lineWidthRange);
|
||||||
|
|
||||||
|
|
||||||
|
projectiveTextureInstancingShader = gltLoadShaderPair(projectiveTextureInstancingVertexShader,projectiveTextureInstancingFragmentShader);
|
||||||
|
|
||||||
|
glLinkProgram(projectiveTextureInstancingShader);
|
||||||
|
glUseProgram(projectiveTextureInstancingShader);
|
||||||
|
projectiveTexture_ViewMatrixInverse = glGetUniformLocation(projectiveTextureInstancingShader, "ViewMatrixInverse");
|
||||||
|
projectiveTexture_ModelViewMatrix = glGetUniformLocation(projectiveTextureInstancingShader, "ModelViewMatrix");
|
||||||
|
projectiveTexture_lightSpecularIntensity = glGetUniformLocation(projectiveTextureInstancingShader, "lightSpecularIntensityIn");
|
||||||
|
projectiveTexture_materialSpecularColor = glGetUniformLocation(projectiveTextureInstancingShader, "materialSpecularColorIn");
|
||||||
|
projectiveTexture_MVP = glGetUniformLocation(projectiveTextureInstancingShader, "MVP");
|
||||||
|
projectiveTexture_ProjectionMatrix = glGetUniformLocation(projectiveTextureInstancingShader, "ProjectionMatrix");
|
||||||
|
projectiveTexture_TextureMVP = glGetUniformLocation(projectiveTextureInstancingShader, "TextureMVP");
|
||||||
|
projectiveTexture_uniform_texture_diffuse = glGetUniformLocation(projectiveTextureInstancingShader, "Diffuse");
|
||||||
|
projectiveTexture_shadowMap = glGetUniformLocation(projectiveTextureInstancingShader,"shadowMap");
|
||||||
|
projectiveTexture_lightPosIn = glGetUniformLocation(projectiveTextureInstancingShader,"lightPosIn");
|
||||||
|
projectiveTexture_cameraPositionIn = glGetUniformLocation(projectiveTextureInstancingShader,"cameraPositionIn");
|
||||||
|
projectiveTexture_materialShininessIn = glGetUniformLocation(projectiveTextureInstancingShader,"materialShininessIn");
|
||||||
|
|
||||||
|
glUseProgram(0);
|
||||||
|
|
||||||
useShadowMapInstancingShader = gltLoadShaderPair(useShadowMapInstancingVertexShader,useShadowMapInstancingFragmentShader);
|
useShadowMapInstancingShader = gltLoadShaderPair(useShadowMapInstancingVertexShader,useShadowMapInstancingFragmentShader);
|
||||||
|
|
||||||
@@ -1538,7 +1573,13 @@ void GLInstancingRenderer::renderScene()
|
|||||||
//renderSceneInternal(B3_USE_SHADOWMAP_RENDERMODE_REFLECTION);
|
//renderSceneInternal(B3_USE_SHADOWMAP_RENDERMODE_REFLECTION);
|
||||||
renderSceneInternal(B3_USE_SHADOWMAP_RENDERMODE);
|
renderSceneInternal(B3_USE_SHADOWMAP_RENDERMODE);
|
||||||
|
|
||||||
} else
|
}
|
||||||
|
else if (useProjectiveTexture)
|
||||||
|
{
|
||||||
|
//renderSceneInternal(B3_CREATE_SHADOWMAP_RENDERMODE);
|
||||||
|
renderSceneInternal(B3_USE_PROJECTIVE_TEXTURE_RENDERMODE);
|
||||||
|
}
|
||||||
|
else
|
||||||
{
|
{
|
||||||
renderSceneInternal();
|
renderSceneInternal();
|
||||||
}
|
}
|
||||||
@@ -1977,11 +2018,16 @@ void GLInstancingRenderer::renderSceneInternal(int orgRenderMode)
|
|||||||
reflectionPass = true;
|
reflectionPass = true;
|
||||||
renderMode = B3_USE_SHADOWMAP_RENDERMODE;
|
renderMode = B3_USE_SHADOWMAP_RENDERMODE;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!useShadowMap)
|
if (!useShadowMap)
|
||||||
{
|
{
|
||||||
renderMode = B3_DEFAULT_RENDERMODE;
|
renderMode = B3_DEFAULT_RENDERMODE;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if (orgRenderMode==B3_USE_PROJECTIVE_TEXTURE_RENDERMODE)
|
||||||
|
{
|
||||||
|
renderMode = B3_USE_PROJECTIVE_TEXTURE_RENDERMODE;
|
||||||
|
}
|
||||||
|
|
||||||
// glEnable(GL_DEPTH_TEST);
|
// glEnable(GL_DEPTH_TEST);
|
||||||
|
|
||||||
@@ -2010,6 +2056,10 @@ void GLInstancingRenderer::renderSceneInternal(int orgRenderMode)
|
|||||||
float depthProjectionMatrix[4][4];
|
float depthProjectionMatrix[4][4];
|
||||||
GLfloat depthModelViewMatrix[4][4];
|
GLfloat depthModelViewMatrix[4][4];
|
||||||
//GLfloat depthModelViewMatrix2[4][4];
|
//GLfloat depthModelViewMatrix2[4][4];
|
||||||
|
|
||||||
|
// For projective texture mapping
|
||||||
|
float textureProjectionMatrix[4][4];
|
||||||
|
GLfloat textureModelViewMatrix[4][4];
|
||||||
|
|
||||||
// Compute the MVP matrix from the light's point of view
|
// Compute the MVP matrix from the light's point of view
|
||||||
if (renderMode==B3_CREATE_SHADOWMAP_RENDERMODE)
|
if (renderMode==B3_CREATE_SHADOWMAP_RENDERMODE)
|
||||||
@@ -2120,6 +2170,9 @@ void GLInstancingRenderer::renderSceneInternal(int orgRenderMode)
|
|||||||
GLfloat depthBiasMVP[4][4];
|
GLfloat depthBiasMVP[4][4];
|
||||||
b3Matrix4x4Mul(biasMatrix,depthMVP,depthBiasMVP);
|
b3Matrix4x4Mul(biasMatrix,depthMVP,depthBiasMVP);
|
||||||
|
|
||||||
|
// TODO: Expose the projective texture matrix setup. Temporarily set it to be the same as camera view projection matrix.
|
||||||
|
GLfloat textureMVP[16];
|
||||||
|
b3Matrix4x4Mul16(m_data->m_projectionMatrix,m_data->m_viewMatrix,textureMVP);
|
||||||
|
|
||||||
//float m_frustumZNear=0.1;
|
//float m_frustumZNear=0.1;
|
||||||
//float m_frustumZFar=100.f;
|
//float m_frustumZFar=100.f;
|
||||||
@@ -2475,6 +2528,70 @@ b3Assert(glGetError() ==GL_NO_ERROR);
|
|||||||
glActiveTexture(GL_TEXTURE1);
|
glActiveTexture(GL_TEXTURE1);
|
||||||
glBindTexture(GL_TEXTURE_2D,0);
|
glBindTexture(GL_TEXTURE_2D,0);
|
||||||
|
|
||||||
|
glActiveTexture(GL_TEXTURE0);
|
||||||
|
glBindTexture(GL_TEXTURE_2D,0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case B3_USE_PROJECTIVE_TEXTURE_RENDERMODE:
|
||||||
|
{
|
||||||
|
if ( gfxObj->m_flags&eGfxTransparency)
|
||||||
|
{
|
||||||
|
glDepthMask(false);
|
||||||
|
glEnable (GL_BLEND);
|
||||||
|
glBlendFunc (GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
|
||||||
|
}
|
||||||
|
|
||||||
|
glUseProgram(projectiveTextureInstancingShader);
|
||||||
|
glUniformMatrix4fv(projectiveTexture_ProjectionMatrix, 1, false, &m_data->m_projectionMatrix[0]);
|
||||||
|
glUniform3f(projectiveTexture_lightSpecularIntensity, m_data->m_lightSpecularIntensity[0],m_data->m_lightSpecularIntensity[1],m_data->m_lightSpecularIntensity[2]);
|
||||||
|
glUniform3f(projectiveTexture_materialSpecularColor, gfxObj->m_materialSpecularColor[0],gfxObj->m_materialSpecularColor[1],gfxObj->m_materialSpecularColor[2]);
|
||||||
|
|
||||||
|
float MVP[16];
|
||||||
|
if (reflectionPass)
|
||||||
|
{
|
||||||
|
float tmp[16];
|
||||||
|
float reflectionMatrix[16] = {1,0,0,0,
|
||||||
|
0,1,0,0,
|
||||||
|
0,0,-1,0,
|
||||||
|
0,0,0,1};
|
||||||
|
glCullFace(GL_FRONT);
|
||||||
|
b3Matrix4x4Mul16(m_data->m_viewMatrix,reflectionMatrix,tmp);
|
||||||
|
b3Matrix4x4Mul16(m_data->m_projectionMatrix,tmp,MVP);
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
b3Matrix4x4Mul16(m_data->m_projectionMatrix,m_data->m_viewMatrix,MVP);
|
||||||
|
glCullFace(GL_BACK);
|
||||||
|
}
|
||||||
|
|
||||||
|
glUniformMatrix4fv(projectiveTexture_MVP, 1, false, &MVP[0]);
|
||||||
|
glUniform3f(projectiveTexture_lightPosIn,m_data->m_lightPos[0],m_data->m_lightPos[1],m_data->m_lightPos[2]);
|
||||||
|
float camPos[3];
|
||||||
|
m_data->m_activeCamera->getCameraPosition(camPos);
|
||||||
|
glUniform3f(projectiveTexture_cameraPositionIn,camPos[0],camPos[1],camPos[2]);
|
||||||
|
glUniform1f(projectiveTexture_materialShininessIn,gfxObj->m_materialShinyNess);
|
||||||
|
|
||||||
|
glUniformMatrix4fv(projectiveTexture_TextureMVP, 1, false, &textureMVP[0]);
|
||||||
|
|
||||||
|
//sort transparent objects
|
||||||
|
if ( gfxObj->m_flags&eGfxTransparency)
|
||||||
|
{
|
||||||
|
int instanceId = transparentInstances[i].m_instanceId;
|
||||||
|
glVertexAttribPointer(1, 4, GL_FLOAT, GL_FALSE, 0, (GLvoid *)((instanceId)*4*sizeof(float)+m_data->m_maxShapeCapacityInBytes));
|
||||||
|
glVertexAttribPointer(2, 4, GL_FLOAT, GL_FALSE, 0, (GLvoid *)((instanceId)*4*sizeof(float)+m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE));
|
||||||
|
glVertexAttribPointer(5, 4, GL_FLOAT, GL_FALSE, 0, (GLvoid *)((instanceId)*4*sizeof(float)+m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE+ORIENTATION_BUFFER_SIZE));
|
||||||
|
glVertexAttribPointer(6, 3, GL_FLOAT, GL_FALSE, 0, (GLvoid *)((instanceId)*3*sizeof(float)+m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE+ORIENTATION_BUFFER_SIZE+COLOR_BUFFER_SIZE));
|
||||||
|
glDrawElements(GL_TRIANGLES, indexCount, GL_UNSIGNED_INT, 0);
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
glDrawElementsInstanced(GL_TRIANGLES, indexCount, GL_UNSIGNED_INT, indexOffset, gfxObj->m_numGraphicsInstances);
|
||||||
|
}
|
||||||
|
|
||||||
|
if ( gfxObj->m_flags&eGfxTransparency)
|
||||||
|
{
|
||||||
|
glDisable (GL_BLEND);
|
||||||
|
glDepthMask(true);
|
||||||
|
}
|
||||||
|
|
||||||
glActiveTexture(GL_TEXTURE0);
|
glActiveTexture(GL_TEXTURE0);
|
||||||
glBindTexture(GL_TEXTURE_2D,0);
|
glBindTexture(GL_TEXTURE_2D,0);
|
||||||
break;
|
break;
|
||||||
|
|||||||
@@ -0,0 +1,72 @@
|
|||||||
|
#version 330 core
|
||||||
|
//precision highp float;
|
||||||
|
|
||||||
|
in Fragment
|
||||||
|
{
|
||||||
|
vec4 color;
|
||||||
|
} fragment;
|
||||||
|
|
||||||
|
in Vert
|
||||||
|
{
|
||||||
|
vec2 texcoord;
|
||||||
|
} vert;
|
||||||
|
|
||||||
|
uniform sampler2D Diffuse;
|
||||||
|
uniform mat4 ViewMatrixInverse;
|
||||||
|
|
||||||
|
in vec3 lightPos,cameraPosition, normal,ambient;
|
||||||
|
in vec4 vertexPos;
|
||||||
|
in float materialShininess;
|
||||||
|
in vec3 lightSpecularIntensity;
|
||||||
|
in vec3 materialSpecularColor;
|
||||||
|
|
||||||
|
out vec4 color;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
void main(void)
|
||||||
|
{
|
||||||
|
vec4 texel = fragment.color*texture(Diffuse,vert.texcoord.xy);
|
||||||
|
vec3 ct,cf;
|
||||||
|
float intensity,at,af;
|
||||||
|
if (fragment.color.w==0)
|
||||||
|
discard;
|
||||||
|
vec3 lightDir = normalize(lightPos);
|
||||||
|
|
||||||
|
vec3 normalDir = normalize(normal);
|
||||||
|
|
||||||
|
intensity = 0.5+0.5*clamp( dot( normalDir,lightDir ), -1,1 );
|
||||||
|
|
||||||
|
af = 1.0;
|
||||||
|
|
||||||
|
ct = texel.rgb;
|
||||||
|
at = texel.a;
|
||||||
|
|
||||||
|
//float bias = 0.005f;
|
||||||
|
|
||||||
|
vec3 specularReflection;
|
||||||
|
|
||||||
|
if (dot(normalDir, lightDir) < 0.0)
|
||||||
|
{
|
||||||
|
specularReflection = vec3(0.0, 0.0, 0.0);
|
||||||
|
}
|
||||||
|
else // light source on the right side
|
||||||
|
{
|
||||||
|
vec3 surfaceToLight = normalize(lightPos - vertexPos.xyz);
|
||||||
|
vec3 surfaceToCamera = normalize(cameraPosition - vertexPos.xyz);
|
||||||
|
|
||||||
|
|
||||||
|
float specularCoefficient = 0.0;
|
||||||
|
specularCoefficient = pow(max(0.0, dot(surfaceToCamera, reflect(-surfaceToLight, normalDir))), materialShininess);
|
||||||
|
specularReflection = specularCoefficient * materialSpecularColor * lightSpecularIntensity;
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
float visibility = 1.0;
|
||||||
|
|
||||||
|
intensity = 0.7*intensity + 0.3*intensity*visibility;
|
||||||
|
|
||||||
|
cf = intensity*(vec3(1.0,1.0,1.0)-ambient)+ambient+specularReflection*visibility;
|
||||||
|
color = vec4(ct * cf, fragment.color.w);
|
||||||
|
}
|
||||||
@@ -0,0 +1,65 @@
|
|||||||
|
//this file is autogenerated using stringify.bat (premake --stringify) in the build folder of this project
|
||||||
|
static const char* projectiveTextureInstancingFragmentShader= \
|
||||||
|
"#version 330 core\n"
|
||||||
|
"//precision highp float;\n"
|
||||||
|
"in Fragment\n"
|
||||||
|
"{\n"
|
||||||
|
" vec4 color;\n"
|
||||||
|
"} fragment;\n"
|
||||||
|
"in Vert\n"
|
||||||
|
"{\n"
|
||||||
|
" vec2 texcoord;\n"
|
||||||
|
"} vert;\n"
|
||||||
|
"uniform sampler2D Diffuse;\n"
|
||||||
|
"uniform mat4 ViewMatrixInverse;\n"
|
||||||
|
"in vec3 lightPos,cameraPosition, normal,ambient;\n"
|
||||||
|
"in vec4 vertexPos;\n"
|
||||||
|
"in float materialShininess;\n"
|
||||||
|
"in vec3 lightSpecularIntensity;\n"
|
||||||
|
"in vec3 materialSpecularColor;\n"
|
||||||
|
"out vec4 color;\n"
|
||||||
|
"void main(void)\n"
|
||||||
|
"{\n"
|
||||||
|
" vec4 texel = fragment.color*texture(Diffuse,vert.texcoord.xy);\n"
|
||||||
|
" vec3 ct,cf;\n"
|
||||||
|
" float intensity,at,af;\n"
|
||||||
|
" if (fragment.color.w==0)\n"
|
||||||
|
" discard;\n"
|
||||||
|
" vec3 lightDir = normalize(lightPos);\n"
|
||||||
|
" \n"
|
||||||
|
" vec3 normalDir = normalize(normal);\n"
|
||||||
|
" \n"
|
||||||
|
" intensity = 0.5+0.5*clamp( dot( normalDir,lightDir ), -1,1 );\n"
|
||||||
|
" \n"
|
||||||
|
" af = 1.0;\n"
|
||||||
|
" \n"
|
||||||
|
" ct = texel.rgb;\n"
|
||||||
|
" at = texel.a;\n"
|
||||||
|
" \n"
|
||||||
|
" //float bias = 0.005f;\n"
|
||||||
|
" \n"
|
||||||
|
" vec3 specularReflection;\n"
|
||||||
|
" \n"
|
||||||
|
" if (dot(normalDir, lightDir) < 0.0) \n"
|
||||||
|
" {\n"
|
||||||
|
" specularReflection = vec3(0.0, 0.0, 0.0);\n"
|
||||||
|
" }\n"
|
||||||
|
" else // light source on the right side\n"
|
||||||
|
" {\n"
|
||||||
|
" vec3 surfaceToLight = normalize(lightPos - vertexPos.xyz);\n"
|
||||||
|
" vec3 surfaceToCamera = normalize(cameraPosition - vertexPos.xyz);\n"
|
||||||
|
" \n"
|
||||||
|
" \n"
|
||||||
|
" float specularCoefficient = 0.0;\n"
|
||||||
|
" specularCoefficient = pow(max(0.0, dot(surfaceToCamera, reflect(-surfaceToLight, normalDir))), materialShininess);\n"
|
||||||
|
" specularReflection = specularCoefficient * materialSpecularColor * lightSpecularIntensity;\n"
|
||||||
|
" \n"
|
||||||
|
" }\n"
|
||||||
|
" \n"
|
||||||
|
" float visibility = 1.0;\n"
|
||||||
|
" intensity = 0.7*intensity + 0.3*intensity*visibility;\n"
|
||||||
|
" \n"
|
||||||
|
" cf = intensity*(vec3(1.0,1.0,1.0)-ambient)+ambient+specularReflection*visibility;\n"
|
||||||
|
" color = vec4(ct * cf, fragment.color.w);\n"
|
||||||
|
"}\n"
|
||||||
|
;
|
||||||
@@ -0,0 +1,99 @@
|
|||||||
|
#version 330
|
||||||
|
precision highp float;
|
||||||
|
|
||||||
|
|
||||||
|
layout (location = 0) in vec4 position;
|
||||||
|
layout (location = 1) in vec4 instance_position;
|
||||||
|
layout (location = 2) in vec4 instance_quaternion;
|
||||||
|
layout (location = 3) in vec2 uvcoords;
|
||||||
|
layout (location = 4) in vec3 vertexnormal;
|
||||||
|
layout (location = 5) in vec4 instance_color;
|
||||||
|
layout (location = 6) in vec3 instance_scale;
|
||||||
|
|
||||||
|
|
||||||
|
uniform mat4 TextureMVP;
|
||||||
|
uniform mat4 MVP;
|
||||||
|
uniform vec3 lightPosIn;
|
||||||
|
uniform vec3 cameraPositionIn;
|
||||||
|
uniform mat4 ViewMatrixInverse;
|
||||||
|
uniform float materialShininessIn;
|
||||||
|
uniform vec3 lightSpecularIntensityIn;
|
||||||
|
uniform vec3 materialSpecularColorIn;
|
||||||
|
|
||||||
|
out vec4 ShadowCoord;
|
||||||
|
|
||||||
|
out Fragment
|
||||||
|
{
|
||||||
|
vec4 color;
|
||||||
|
} fragment;
|
||||||
|
|
||||||
|
out Vert
|
||||||
|
{
|
||||||
|
vec2 texcoord;
|
||||||
|
} vert;
|
||||||
|
|
||||||
|
|
||||||
|
vec4 quatMul ( in vec4 q1, in vec4 q2 )
|
||||||
|
{
|
||||||
|
vec3 im = q1.w * q2.xyz + q1.xyz * q2.w + cross ( q1.xyz, q2.xyz );
|
||||||
|
vec4 dt = q1 * q2;
|
||||||
|
float re = dot ( dt, vec4 ( -1.0, -1.0, -1.0, 1.0 ) );
|
||||||
|
return vec4 ( im, re );
|
||||||
|
}
|
||||||
|
|
||||||
|
vec4 quatFromAxisAngle(vec4 axis, in float angle)
|
||||||
|
{
|
||||||
|
float cah = cos(angle*0.5);
|
||||||
|
float sah = sin(angle*0.5);
|
||||||
|
float d = inversesqrt(dot(axis,axis));
|
||||||
|
vec4 q = vec4(axis.x*sah*d,axis.y*sah*d,axis.z*sah*d,cah);
|
||||||
|
return q;
|
||||||
|
}
|
||||||
|
//
|
||||||
|
// vector rotation via quaternion
|
||||||
|
//
|
||||||
|
vec4 quatRotate3 ( in vec3 p, in vec4 q )
|
||||||
|
{
|
||||||
|
vec4 temp = quatMul ( q, vec4 ( p, 0.0 ) );
|
||||||
|
return quatMul ( temp, vec4 ( -q.x, -q.y, -q.z, q.w ) );
|
||||||
|
}
|
||||||
|
vec4 quatRotate ( in vec4 p, in vec4 q )
|
||||||
|
{
|
||||||
|
vec4 temp = quatMul ( q, p );
|
||||||
|
return quatMul ( temp, vec4 ( -q.x, -q.y, -q.z, q.w ) );
|
||||||
|
}
|
||||||
|
|
||||||
|
out vec3 lightPos,normal,ambient;
|
||||||
|
out vec4 vertexPos;
|
||||||
|
out vec3 cameraPosition;
|
||||||
|
out float materialShininess;
|
||||||
|
out vec3 lightSpecularIntensity;
|
||||||
|
out vec3 materialSpecularColor;
|
||||||
|
|
||||||
|
|
||||||
|
void main(void)
|
||||||
|
{
|
||||||
|
vec4 q = instance_quaternion;
|
||||||
|
ambient = vec3(0.5,.5,0.5);
|
||||||
|
|
||||||
|
vec4 worldNormal = (quatRotate3( vertexnormal,q));
|
||||||
|
|
||||||
|
normal = worldNormal.xyz;
|
||||||
|
|
||||||
|
lightPos = lightPosIn;
|
||||||
|
cameraPosition = cameraPositionIn;
|
||||||
|
materialShininess = materialShininessIn;
|
||||||
|
lightSpecularIntensity = lightSpecularIntensityIn;
|
||||||
|
materialSpecularColor = materialSpecularColorIn;
|
||||||
|
|
||||||
|
vec4 localcoord = quatRotate3( position.xyz*instance_scale,q);
|
||||||
|
vertexPos = vec4((instance_position+localcoord).xyz,1);
|
||||||
|
|
||||||
|
vec4 vertexLoc = MVP* vec4((instance_position+localcoord).xyz,1);
|
||||||
|
gl_Position = vertexLoc;
|
||||||
|
|
||||||
|
fragment.color = instance_color;
|
||||||
|
vec4 projcoords = TextureMVP * vec4((instance_position+localcoord).xyz,1);
|
||||||
|
vert.texcoord = projcoords.xy/projcoords.z;
|
||||||
|
}
|
||||||
|
|
||||||
@@ -0,0 +1,86 @@
|
|||||||
|
//this file is autogenerated using stringify.bat (premake --stringify) in the build folder of this project
|
||||||
|
static const char* projectiveTextureInstancingVertexShader= \
|
||||||
|
"#version 330 \n"
|
||||||
|
"precision highp float;\n"
|
||||||
|
"layout (location = 0) in vec4 position;\n"
|
||||||
|
"layout (location = 1) in vec4 instance_position;\n"
|
||||||
|
"layout (location = 2) in vec4 instance_quaternion;\n"
|
||||||
|
"layout (location = 3) in vec2 uvcoords;\n"
|
||||||
|
"layout (location = 4) in vec3 vertexnormal;\n"
|
||||||
|
"layout (location = 5) in vec4 instance_color;\n"
|
||||||
|
"layout (location = 6) in vec3 instance_scale;\n"
|
||||||
|
"uniform mat4 TextureMVP;\n"
|
||||||
|
"uniform mat4 MVP;\n"
|
||||||
|
"uniform vec3 lightPosIn;\n"
|
||||||
|
"uniform vec3 cameraPositionIn;\n"
|
||||||
|
"uniform mat4 ViewMatrixInverse;\n"
|
||||||
|
"uniform float materialShininessIn;\n"
|
||||||
|
"uniform vec3 lightSpecularIntensityIn;\n"
|
||||||
|
"uniform vec3 materialSpecularColorIn;\n"
|
||||||
|
"out vec4 ShadowCoord;\n"
|
||||||
|
"out Fragment\n"
|
||||||
|
"{\n"
|
||||||
|
" vec4 color;\n"
|
||||||
|
"} fragment;\n"
|
||||||
|
"out Vert\n"
|
||||||
|
"{\n"
|
||||||
|
" vec2 texcoord;\n"
|
||||||
|
"} vert;\n"
|
||||||
|
"vec4 quatMul ( in vec4 q1, in vec4 q2 )\n"
|
||||||
|
"{\n"
|
||||||
|
" vec3 im = q1.w * q2.xyz + q1.xyz * q2.w + cross ( q1.xyz, q2.xyz );\n"
|
||||||
|
" vec4 dt = q1 * q2;\n"
|
||||||
|
" float re = dot ( dt, vec4 ( -1.0, -1.0, -1.0, 1.0 ) );\n"
|
||||||
|
" return vec4 ( im, re );\n"
|
||||||
|
"}\n"
|
||||||
|
"vec4 quatFromAxisAngle(vec4 axis, in float angle)\n"
|
||||||
|
"{\n"
|
||||||
|
" float cah = cos(angle*0.5);\n"
|
||||||
|
" float sah = sin(angle*0.5);\n"
|
||||||
|
" float d = inversesqrt(dot(axis,axis));\n"
|
||||||
|
" vec4 q = vec4(axis.x*sah*d,axis.y*sah*d,axis.z*sah*d,cah);\n"
|
||||||
|
" return q;\n"
|
||||||
|
"}\n"
|
||||||
|
"//\n"
|
||||||
|
"// vector rotation via quaternion\n"
|
||||||
|
"//\n"
|
||||||
|
"vec4 quatRotate3 ( in vec3 p, in vec4 q )\n"
|
||||||
|
"{\n"
|
||||||
|
" vec4 temp = quatMul ( q, vec4 ( p, 0.0 ) );\n"
|
||||||
|
" return quatMul ( temp, vec4 ( -q.x, -q.y, -q.z, q.w ) );\n"
|
||||||
|
"}\n"
|
||||||
|
"vec4 quatRotate ( in vec4 p, in vec4 q )\n"
|
||||||
|
"{\n"
|
||||||
|
" vec4 temp = quatMul ( q, p );\n"
|
||||||
|
" return quatMul ( temp, vec4 ( -q.x, -q.y, -q.z, q.w ) );\n"
|
||||||
|
"}\n"
|
||||||
|
"out vec3 lightPos,normal,ambient;\n"
|
||||||
|
"out vec4 vertexPos;\n"
|
||||||
|
"out vec3 cameraPosition;\n"
|
||||||
|
"out float materialShininess;\n"
|
||||||
|
"out vec3 lightSpecularIntensity;\n"
|
||||||
|
"out vec3 materialSpecularColor;\n"
|
||||||
|
"void main(void)\n"
|
||||||
|
"{\n"
|
||||||
|
" vec4 q = instance_quaternion;\n"
|
||||||
|
" ambient = vec3(0.5,.5,0.5);\n"
|
||||||
|
" \n"
|
||||||
|
" vec4 worldNormal = (quatRotate3( vertexnormal,q));\n"
|
||||||
|
" \n"
|
||||||
|
" normal = worldNormal.xyz;\n"
|
||||||
|
" lightPos = lightPosIn;\n"
|
||||||
|
" cameraPosition = cameraPositionIn;\n"
|
||||||
|
" materialShininess = materialShininessIn;\n"
|
||||||
|
" lightSpecularIntensity = lightSpecularIntensityIn;\n"
|
||||||
|
" materialSpecularColor = materialSpecularColorIn;\n"
|
||||||
|
" \n"
|
||||||
|
" vec4 localcoord = quatRotate3( position.xyz*instance_scale,q);\n"
|
||||||
|
" vertexPos = vec4((instance_position+localcoord).xyz,1);\n"
|
||||||
|
" \n"
|
||||||
|
" vec4 vertexLoc = MVP* vec4((instance_position+localcoord).xyz,1);\n"
|
||||||
|
" gl_Position = vertexLoc;\n"
|
||||||
|
" fragment.color = instance_color;\n"
|
||||||
|
" vec4 projcoords = TextureMVP * vec4((instance_position+localcoord).xyz,1);\n"
|
||||||
|
" vert.texcoord = projcoords.xy/projcoords.z;\n"
|
||||||
|
"}\n"
|
||||||
|
;
|
||||||
0
examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.glsl
Normal file → Executable file
0
examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.glsl
Normal file → Executable file
0
examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.h
Normal file → Executable file
0
examples/OpenGLWindow/Shaders/useShadowMapInstancingPS.h
Normal file → Executable file
2
examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.glsl
Normal file → Executable file
2
examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.glsl
Normal file → Executable file
@@ -11,6 +11,8 @@ layout (location = 5) in vec4 instance_color;
|
|||||||
layout (location = 6) in vec3 instance_scale;
|
layout (location = 6) in vec3 instance_scale;
|
||||||
|
|
||||||
|
|
||||||
|
uniform mat4 ModelViewMatrix;
|
||||||
|
uniform mat4 ProjectionMatrix;
|
||||||
uniform mat4 DepthBiasModelViewProjectionMatrix;
|
uniform mat4 DepthBiasModelViewProjectionMatrix;
|
||||||
uniform mat4 MVP;
|
uniform mat4 MVP;
|
||||||
uniform vec3 lightPosIn;
|
uniform vec3 lightPosIn;
|
||||||
|
|||||||
2
examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.h
Normal file → Executable file
2
examples/OpenGLWindow/Shaders/useShadowMapInstancingVS.h
Normal file → Executable file
@@ -9,6 +9,8 @@ static const char* useShadowMapInstancingVertexShader= \
|
|||||||
"layout (location = 4) in vec3 vertexnormal;\n"
|
"layout (location = 4) in vec3 vertexnormal;\n"
|
||||||
"layout (location = 5) in vec4 instance_color;\n"
|
"layout (location = 5) in vec4 instance_color;\n"
|
||||||
"layout (location = 6) in vec3 instance_scale;\n"
|
"layout (location = 6) in vec3 instance_scale;\n"
|
||||||
|
"uniform mat4 ModelViewMatrix;\n"
|
||||||
|
"uniform mat4 ProjectionMatrix;\n"
|
||||||
"uniform mat4 DepthBiasModelViewProjectionMatrix;\n"
|
"uniform mat4 DepthBiasModelViewProjectionMatrix;\n"
|
||||||
"uniform mat4 MVP;\n"
|
"uniform mat4 MVP;\n"
|
||||||
"uniform vec3 lightPosIn;\n"
|
"uniform vec3 lightPosIn;\n"
|
||||||
|
|||||||
31
examples/pybullet/examples/projective_texture.py
Normal file
31
examples/pybullet/examples/projective_texture.py
Normal file
@@ -0,0 +1,31 @@
|
|||||||
|
import pybullet as p
|
||||||
|
from time import sleep
|
||||||
|
from PIL import Image
|
||||||
|
import matplotlib.pyplot as plt
|
||||||
|
import numpy as np
|
||||||
|
|
||||||
|
physicsClient = p.connect(p.GUI)
|
||||||
|
|
||||||
|
p.setGravity(0,0,0)
|
||||||
|
bearStartPos1 = [-3.3,0,0]
|
||||||
|
bearStartOrientation1 = p.getQuaternionFromEuler([0,0,0])
|
||||||
|
bearId1 = p.loadURDF("teddy_large.urdf", bearStartPos1, bearStartOrientation1)
|
||||||
|
bearStartPos2 = [0,0,0]
|
||||||
|
bearStartOrientation2 = p.getQuaternionFromEuler([0,0,0])
|
||||||
|
bearId2 = p.loadURDF("teddy_large.urdf",bearStartPos2, bearStartOrientation2)
|
||||||
|
textureId = p.loadTexture("checker_grid.jpg")
|
||||||
|
p.changeVisualShape(objectUniqueId=0, linkIndex=-1, textureUniqueId=textureId)
|
||||||
|
p.changeVisualShape(objectUniqueId=1, linkIndex=-1, textureUniqueId=textureId)
|
||||||
|
|
||||||
|
|
||||||
|
useRealTimeSimulation = 1
|
||||||
|
|
||||||
|
if (useRealTimeSimulation):
|
||||||
|
p.setRealTimeSimulation(1)
|
||||||
|
|
||||||
|
while 1:
|
||||||
|
if (useRealTimeSimulation):
|
||||||
|
p.setGravity(0,0,0)
|
||||||
|
sleep(0.01) # Time in seconds.
|
||||||
|
else:
|
||||||
|
p.stepSimulation()
|
||||||
Reference in New Issue
Block a user