implement specular, URDF non-standard specular part (see sphere2.urdf) and SDF specular support.
pybullet.changeVisualShape(obUid,linkIndex,specularColor=[R,G,B]) and Bullet C-API b3UpdateVisualShapeSpecularColor Bug fixes in b3ResourcePath::findResourcePath resolution. add stadium.sdf and roboschool/models_outdoor/stadium assets https://github.com/openai/roboschool/tree/master/roboschool/models_outdoor/stadium minor fixes to obj2sdf
This commit is contained in:
@@ -492,6 +492,60 @@ void GLInstancingRenderer::writeSingleInstanceScaleToCPU(const float* scale, int
|
||||
m_data->m_instance_scale_ptr[srcIndex*3+2]=scale[2];
|
||||
}
|
||||
|
||||
void GLInstancingRenderer::writeSingleInstanceSpecularColorToCPU(const double* specular, int bodyUniqueId)
|
||||
{
|
||||
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
|
||||
b3Assert(pg);
|
||||
int srcIndex = pg->m_internalInstanceIndex;
|
||||
|
||||
int totalNumInstances = 0;
|
||||
|
||||
int gfxObjIndex = -1;
|
||||
|
||||
for (int i=0;i<m_graphicsInstances.size();i++)
|
||||
{
|
||||
totalNumInstances+=m_graphicsInstances[i]->m_numGraphicsInstances;
|
||||
if (srcIndex<totalNumInstances)
|
||||
{
|
||||
gfxObjIndex = i;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (gfxObjIndex>0)
|
||||
{
|
||||
m_graphicsInstances[gfxObjIndex]->m_materialSpecularColor[0] = specular[0];
|
||||
m_graphicsInstances[gfxObjIndex]->m_materialSpecularColor[1] = specular[1];
|
||||
m_graphicsInstances[gfxObjIndex]->m_materialSpecularColor[2] = specular[2];
|
||||
}
|
||||
}
|
||||
void GLInstancingRenderer::writeSingleInstanceSpecularColorToCPU(const float* specular, int bodyUniqueId)
|
||||
{
|
||||
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
|
||||
b3Assert(pg);
|
||||
int srcIndex = pg->m_internalInstanceIndex;
|
||||
|
||||
int totalNumInstances = 0;
|
||||
|
||||
int gfxObjIndex = -1;
|
||||
|
||||
for (int i=0;i<m_graphicsInstances.size();i++)
|
||||
{
|
||||
totalNumInstances+=m_graphicsInstances[i]->m_numGraphicsInstances;
|
||||
if (srcIndex<totalNumInstances)
|
||||
{
|
||||
gfxObjIndex = i;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (gfxObjIndex>0)
|
||||
{
|
||||
m_graphicsInstances[gfxObjIndex]->m_materialSpecularColor[0] = specular[0];
|
||||
m_graphicsInstances[gfxObjIndex]->m_materialSpecularColor[1] = specular[1];
|
||||
m_graphicsInstances[gfxObjIndex]->m_materialSpecularColor[2] = specular[2];
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
void GLInstancingRenderer::writeSingleInstanceScaleToCPU(const double* scale, int bodyUniqueId)
|
||||
{
|
||||
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
|
||||
|
||||
@@ -95,6 +95,7 @@ public:
|
||||
|
||||
}
|
||||
|
||||
|
||||
virtual void readSingleInstanceTransformFromCPU(int srcIndex, float* position, float* orientation);
|
||||
|
||||
virtual void writeSingleInstanceTransformToGPU(float* position, float* orientation, int srcIndex);
|
||||
@@ -102,6 +103,9 @@ public:
|
||||
virtual void writeSingleInstanceColorToCPU(const float* color, int srcIndex);
|
||||
virtual void writeSingleInstanceColorToCPU(const double* color, int srcIndex);
|
||||
|
||||
virtual void writeSingleInstanceSpecularColorToCPU(const double* specular, int srcIndex);
|
||||
virtual void writeSingleInstanceSpecularColorToCPU(const float* specular, int srcIndex);
|
||||
|
||||
virtual void writeSingleInstanceScaleToCPU(const float* scale, int srcIndex);
|
||||
virtual void writeSingleInstanceScaleToCPU(const double* scale, int srcIndex);
|
||||
|
||||
|
||||
@@ -39,6 +39,9 @@ public:
|
||||
virtual void writeSingleInstanceColorToCPU(const double* color, int srcIndex);
|
||||
virtual void writeSingleInstanceScaleToCPU(const float* scale, int srcIndex);
|
||||
virtual void writeSingleInstanceScaleToCPU(const double* scale, int srcIndex);
|
||||
virtual void writeSingleInstanceSpecularColorToCPU(const double* specular, int srcIndex){}
|
||||
virtual void writeSingleInstanceSpecularColorToCPU(const float* specular, int srcIndex){}
|
||||
|
||||
virtual void getCameraViewMatrix(float viewMat[16]) const;
|
||||
virtual void getCameraProjectionMatrix(float projMat[16]) const;
|
||||
virtual void drawTexturedTriangleMesh(float worldPosition[3], float worldOrientation[4], const float* vertices, int numvertices, const unsigned int* indices, int numIndices, float color[4], int textureIndex=-1, int vertexLayout=0)
|
||||
|
||||
Reference in New Issue
Block a user