mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-12 21:00:11 +00:00
Add pybullet transparent.py example, transparency with global per-object sort in GLInstancingRenderer
This commit is contained in:
parent
a651cb9ab4
commit
d5fe67cf57
32
data/sphere_transparent.urdf
Normal file
32
data/sphere_transparent.urdf
Normal file
@ -0,0 +1,32 @@
|
||||
<?xml version="0.0" ?>
|
||||
<robot name="urdf_robot">
|
||||
<link name="baseLink">
|
||||
<contact>
|
||||
<rolling_friction value="0.03"/>
|
||||
<spinning_friction value="0.03"/>
|
||||
</contact>
|
||||
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<mass value="10.0"/>
|
||||
<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="textured_sphere_smooth.obj" scale="0.5 0.5 0.5"/>
|
||||
</geometry>
|
||||
<material name="red_transparent">
|
||||
<color rgba="1 0 0 0.5"/>
|
||||
<specular rgb="11 1 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<sphere radius="0.5"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
</robot>
|
||||
|
@ -79,7 +79,6 @@ public:
|
||||
|
||||
gTotalPoints = 0;
|
||||
m_app->setUpAxis(1);
|
||||
m_app->m_renderer->enableBlend(true);
|
||||
|
||||
switch (m_tutorialIndex)
|
||||
{
|
||||
@ -250,7 +249,6 @@ public:
|
||||
|
||||
m_timeSeriesCanvas0 = 0;
|
||||
|
||||
m_app->m_renderer->enableBlend(false);
|
||||
}
|
||||
|
||||
|
||||
|
@ -2046,9 +2046,9 @@ void GLInstancingRenderer::renderSceneInternal(int renderMode)
|
||||
b3Vector3 center = b3MakeVector3(0,0,0);
|
||||
//float upf[3];
|
||||
//m_data->m_activeCamera->getCameraUpVector(upf);
|
||||
b3Vector3 up, fwd;
|
||||
b3Vector3 up, lightFwd;
|
||||
b3Vector3 lightDir = m_data->m_lightPos.normalized();
|
||||
b3PlaneSpace1(lightDir,up,fwd);
|
||||
b3PlaneSpace1(lightDir,up,lightFwd);
|
||||
// b3Vector3 up = b3MakeVector3(upf[0],upf[1],upf[2]);
|
||||
b3CreateLookAt(m_data->m_lightPos,center,up,&depthViewMatrix[0][0]);
|
||||
//b3CreateLookAt(lightPos,m_data->m_cameraTargetPosition,b3Vector3(0,1,0),(float*)depthModelViewMatrix2);
|
||||
@ -2109,15 +2109,75 @@ b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
totalNumInstances+=m_graphicsInstances[i]->m_numGraphicsInstances;
|
||||
}
|
||||
|
||||
b3AlignedObjectArray<SortableTransparentInstance> transparentInstances;
|
||||
|
||||
{
|
||||
int curOffset = 0;
|
||||
//GLuint lastBindTexture = 0;
|
||||
|
||||
transparentInstances.reserve(totalNumInstances);
|
||||
|
||||
for (int i=0;i<m_graphicsInstances.size();i++)
|
||||
for (int obj=0;obj<m_graphicsInstances.size();obj++)
|
||||
{
|
||||
b3GraphicsInstance* gfxObj = m_graphicsInstances[obj];
|
||||
if (gfxObj->m_numGraphicsInstances)
|
||||
{
|
||||
SortableTransparentInstance inst;
|
||||
|
||||
inst.m_shapeIndex = obj;
|
||||
|
||||
|
||||
if ((gfxObj->m_flags&eGfxTransparency)==0)
|
||||
{
|
||||
inst.m_instanceId = curOffset;
|
||||
inst.m_centerPosition.setValue(m_data->m_instance_positions_ptr[inst.m_instanceId*4+0],
|
||||
m_data->m_instance_positions_ptr[inst.m_instanceId*4+1],
|
||||
m_data->m_instance_positions_ptr[inst.m_instanceId*4+2]);
|
||||
inst.m_centerPosition *= -1;//reverse sort opaque instances
|
||||
transparentInstances.push_back(inst);
|
||||
} else
|
||||
{
|
||||
for (int i=0;i<gfxObj->m_numGraphicsInstances;i++)
|
||||
{
|
||||
inst.m_instanceId = curOffset+i;
|
||||
inst.m_centerPosition.setValue(m_data->m_instance_positions_ptr[inst.m_instanceId*4+0],
|
||||
m_data->m_instance_positions_ptr[inst.m_instanceId*4+1],
|
||||
m_data->m_instance_positions_ptr[inst.m_instanceId*4+2]);
|
||||
transparentInstances.push_back(inst);
|
||||
}
|
||||
}
|
||||
curOffset+=gfxObj->m_numGraphicsInstances;
|
||||
}
|
||||
}
|
||||
TransparentDistanceSortPredicate sorter;
|
||||
float fwd[3];
|
||||
m_data->m_activeCamera->getCameraForwardVector(fwd);
|
||||
sorter.m_camForwardVec.setValue(fwd[0],fwd[1],fwd[2]);
|
||||
transparentInstances.quickSort(sorter);
|
||||
}
|
||||
|
||||
|
||||
//two passes: first for opaque instances, second for transparent ones.
|
||||
for (int pass = 0; pass<2;pass++)
|
||||
{
|
||||
for (int i=0;i<transparentInstances.size();i++)
|
||||
{
|
||||
|
||||
b3GraphicsInstance* gfxObj = m_graphicsInstances[i];
|
||||
if (gfxObj->m_numGraphicsInstances)
|
||||
int shapeIndex = transparentInstances[i].m_shapeIndex;
|
||||
|
||||
b3GraphicsInstance* gfxObj = m_graphicsInstances[shapeIndex];
|
||||
|
||||
//only draw stuff (opaque/transparent) if it is the right pass
|
||||
int drawThisPass = (pass==0) == ((gfxObj->m_flags&eGfxTransparency)==0);
|
||||
|
||||
//transparent objects don't cast shadows (to simplify things)
|
||||
if (gfxObj->m_flags&eGfxTransparency)
|
||||
{
|
||||
if (renderMode==B3_CREATE_SHADOWMAP_RENDERMODE)
|
||||
drawThisPass = 0;
|
||||
}
|
||||
|
||||
if (drawThisPass && gfxObj->m_numGraphicsInstances)
|
||||
{
|
||||
glActiveTexture(GL_TEXTURE0);
|
||||
GLuint curBindTexture = 0;
|
||||
@ -2150,8 +2210,8 @@ b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
|
||||
|
||||
glVertexAttribPointer(0, 4, GL_FLOAT, GL_FALSE, 9*sizeof(float), vertex.m_pointer);
|
||||
glVertexAttribPointer(1, 4, GL_FLOAT, GL_FALSE, 0, (GLvoid *)(curOffset*4*sizeof(float)+m_data->m_maxShapeCapacityInBytes));
|
||||
glVertexAttribPointer(2, 4, GL_FLOAT, GL_FALSE, 0, (GLvoid *)(curOffset*4*sizeof(float)+m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE));
|
||||
glVertexAttribPointer(1, 4, GL_FLOAT, GL_FALSE, 0, (GLvoid *)(transparentInstances[i].m_instanceId*4*sizeof(float)+m_data->m_maxShapeCapacityInBytes));
|
||||
glVertexAttribPointer(2, 4, GL_FLOAT, GL_FALSE, 0, (GLvoid *)(transparentInstances[i].m_instanceId*4*sizeof(float)+m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE));
|
||||
|
||||
PointerCaster uv;
|
||||
uv.m_baseIndex = 7*sizeof(float)+vertex.m_baseIndex;
|
||||
@ -2161,8 +2221,8 @@ b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
|
||||
glVertexAttribPointer(3, 2, GL_FLOAT, GL_FALSE, 9*sizeof(float), uv.m_pointer);
|
||||
glVertexAttribPointer(4, 3, GL_FLOAT, GL_FALSE, 9*sizeof(float), normal.m_pointer);
|
||||
glVertexAttribPointer(5, 4, GL_FLOAT, GL_FALSE, 0, (GLvoid *)(curOffset*4*sizeof(float)+m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE+ORIENTATION_BUFFER_SIZE));
|
||||
glVertexAttribPointer(6, 3, GL_FLOAT, GL_FALSE, 0, (GLvoid *)(curOffset*3*sizeof(float)+m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE+ORIENTATION_BUFFER_SIZE+COLOR_BUFFER_SIZE));
|
||||
glVertexAttribPointer(5, 4, GL_FLOAT, GL_FALSE, 0, (GLvoid *)(transparentInstances[i].m_instanceId*4*sizeof(float)+m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE+ORIENTATION_BUFFER_SIZE));
|
||||
glVertexAttribPointer(6, 3, GL_FLOAT, GL_FALSE, 0, (GLvoid *)(transparentInstances[i].m_instanceId*3*sizeof(float)+m_data->m_maxShapeCapacityInBytes+POSITION_BUFFER_SIZE+ORIENTATION_BUFFER_SIZE+COLOR_BUFFER_SIZE));
|
||||
|
||||
glEnableVertexAttribArray(0);
|
||||
glEnableVertexAttribArray(1);
|
||||
@ -2216,6 +2276,13 @@ b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
|
||||
case B3_DEFAULT_RENDERMODE:
|
||||
{
|
||||
if ( gfxObj->m_flags&eGfxTransparency)
|
||||
{
|
||||
glDepthMask(false);
|
||||
glEnable (GL_BLEND);
|
||||
glBlendFunc (GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
|
||||
}
|
||||
|
||||
glUseProgram(instancingShader);
|
||||
glUniformMatrix4fv(ProjectionMatrix, 1, false, &m_data->m_projectionMatrix[0]);
|
||||
glUniformMatrix4fv(ModelViewMatrix, 1, false, &m_data->m_viewMatrix[0]);
|
||||
@ -2225,18 +2292,33 @@ b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
glUniform3f(regularLightDirIn,gLightDir[0],gLightDir[1],gLightDir[2]);
|
||||
|
||||
glUniform1i(uniform_texture_diffuse, 0);
|
||||
|
||||
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);
|
||||
}
|
||||
|
||||
break;
|
||||
}
|
||||
case B3_CREATE_SHADOWMAP_RENDERMODE:
|
||||
{
|
||||
/*printf("createShadowMapInstancingShader=%d\n",createShadowMapInstancingShader);
|
||||
printf("createShadow_depthMVP=%d\n",createShadow_depthMVP);
|
||||
printf("indexOffset=%d\n",indexOffset);
|
||||
printf("gfxObj->m_numGraphicsInstances=%d\n",gfxObj->m_numGraphicsInstances);
|
||||
printf("indexCount=%d\n",indexCount);
|
||||
*/
|
||||
|
||||
glUseProgram(createShadowMapInstancingShader);
|
||||
glUniformMatrix4fv(createShadow_depthMVP, 1, false, &depthMVP[0][0]);
|
||||
glDrawElementsInstanced(GL_TRIANGLES, indexCount, GL_UNSIGNED_INT, indexOffset, gfxObj->m_numGraphicsInstances);
|
||||
@ -2283,40 +2365,13 @@ b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
//gfxObj->m_instanceOffset
|
||||
|
||||
if ( gfxObj->m_flags&eGfxTransparency)
|
||||
{
|
||||
b3AlignedObjectArray<SortableTransparentInstance> transparentInstances;
|
||||
transparentInstances.reserve(gfxObj->m_numGraphicsInstances);
|
||||
|
||||
for (int i=0;i<gfxObj->m_numGraphicsInstances;i++)
|
||||
{
|
||||
SortableTransparentInstance inst;
|
||||
|
||||
inst.m_shapeIndex = -1;
|
||||
|
||||
inst.m_instanceId = curOffset+i;
|
||||
inst.m_centerPosition.setValue(m_data->m_instance_positions_ptr[inst.m_instanceId*4+0],
|
||||
m_data->m_instance_positions_ptr[inst.m_instanceId*4+1],
|
||||
m_data->m_instance_positions_ptr[inst.m_instanceId*4+2]);
|
||||
transparentInstances.push_back(inst);
|
||||
|
||||
}
|
||||
TransparentDistanceSortPredicate sorter;
|
||||
float fwd[3];
|
||||
m_data->m_activeCamera->getCameraForwardVector(fwd);
|
||||
sorter.m_camForwardVec.setValue(fwd[0],fwd[1],fwd[2]);
|
||||
transparentInstances.quickSort(sorter);
|
||||
|
||||
|
||||
for (int i=0;i<transparentInstances.size();i++)
|
||||
{
|
||||
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);
|
||||
@ -2345,7 +2400,7 @@ b3Assert(glGetError() ==GL_NO_ERROR);
|
||||
//glDrawElementsInstanced(GL_LINE_LOOP, indexCount, GL_UNSIGNED_INT, (void*)indexOffset, gfxObj->m_numGraphicsInstances);
|
||||
}
|
||||
}
|
||||
curOffset+= gfxObj->m_numGraphicsInstances;
|
||||
}
|
||||
}
|
||||
|
||||
{
|
||||
|
@ -425,21 +425,23 @@ public:
|
||||
}
|
||||
|
||||
// int boxId = m_app->registerCubeShape(1,1,1,textureIndex);
|
||||
int boxId = m_app->registerGraphicsUnitSphereShape(SPHERE_LOD_HIGH, textureIndex);
|
||||
|
||||
int sphereTransparent = m_app->registerGraphicsUnitSphereShape(SPHERE_LOD_HIGH, textureIndex);
|
||||
int sphereOpaque= m_app->registerGraphicsUnitSphereShape(SPHERE_LOD_HIGH, textureIndex);
|
||||
|
||||
b3Vector3 scaling = b3MakeVector3(SPHERE_RADIUS,SPHERE_RADIUS,SPHERE_RADIUS);
|
||||
for (int i=0;i<m_bodies.size();i++)
|
||||
{
|
||||
b3Vector4 color = b3MakeVector4(1,1,1,0.6);
|
||||
int gfxShape = sphereOpaque;
|
||||
b3Vector4 color = b3MakeVector4(.1,.1,1,1);
|
||||
if (i%2)
|
||||
{
|
||||
color.setValue(1,.1,.1,0.8);
|
||||
color.setValue(1,.1,.1,0.1);
|
||||
gfxShape = sphereTransparent;
|
||||
}
|
||||
m_bodies[i]->m_collisionShape.m_sphere.m_radius = SPHERE_RADIUS;
|
||||
m_bodies[i]->m_collisionShape.m_type = LW_SPHERE_TYPE;
|
||||
|
||||
m_bodies[i]->m_graphicsIndex = m_app->m_renderer->registerGraphicsInstance(boxId,m_bodies[i]->m_worldPose.m_position, m_bodies[i]->m_worldPose.m_orientation,color,scaling);
|
||||
m_bodies[i]->m_graphicsIndex = m_app->m_renderer->registerGraphicsInstance(gfxShape,m_bodies[i]->m_worldPose.m_position, m_bodies[i]->m_worldPose.m_orientation,color,scaling);
|
||||
m_app->m_renderer->writeSingleInstanceTransformToCPU(m_bodies[i]->m_worldPose.m_position, m_bodies[i]->m_worldPose.m_orientation, m_bodies[i]->m_graphicsIndex);
|
||||
}
|
||||
}
|
||||
|
18
examples/pybullet/examples/transparent.py
Normal file
18
examples/pybullet/examples/transparent.py
Normal file
@ -0,0 +1,18 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
p.connect(p.GUI)
|
||||
p.loadURDF("plane.urdf")
|
||||
sphereUid = p.loadURDF("sphere_transparent.urdf",[0,0,2])
|
||||
|
||||
redSlider = p.addUserDebugParameter("red",0,1,1)
|
||||
greenSlider = p.addUserDebugParameter("green",0,1,0)
|
||||
blueSlider = p.addUserDebugParameter("blue",0,1,0)
|
||||
alphaSlider = p.addUserDebugParameter("alpha",0,1,0.5)
|
||||
|
||||
while (1):
|
||||
red = p.readUserDebugParameter(redSlider)
|
||||
green = p.readUserDebugParameter(greenSlider)
|
||||
blue = p.readUserDebugParameter(blueSlider)
|
||||
alpha = p.readUserDebugParameter(alphaSlider)
|
||||
p.changeVisualShape(sphereUid,-1,rgbaColor=[red,green,blue,alpha])
|
||||
time.sleep(0.01)
|
Loading…
Reference in New Issue
Block a user