Improve debug text/line rendering, can be use to draw frames and text in local coordinate of an object / link.

example:
kuka = p.loadURDF("kuka_iiwa/model.urdf")
p.getNumJoints(kuka)
pybullet.addUserDebugLine([0,0,0],[0,0,0.1],[0,0,1],trackObjectUniqueId=2,trackLinkIndex=6)
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],trackObjectUniqueId=2,trackLinkIndex=6)
Also allow to render text using a given orientation (instead of pointing to the camera), example:
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],textOrientation=[0,0,0,1], trackObjectUniqueId=2,trackLinkIndex=6)
Add drawTexturedTriangleMesh, for drawing 3d text.
Expose readSingleInstanceTransformToCPU, to extract position/orientation from graphics index.
updateTexture: allow to not flip texels around up axis
This commit is contained in:
Erwin Coumans
2017-05-23 22:05:26 -07:00
parent 19933a9454
commit db008ab3c2
30 changed files with 1195 additions and 517 deletions

View File

@@ -33,7 +33,7 @@
#include <assert.h>
#include "GLRenderToTexture.h"
#include "Bullet3Common/b3Quaternion.h"
#include <string>//memset
#ifdef _WIN32
#define popen _popen
#define pclose _pclose
@@ -44,8 +44,14 @@ struct SimpleInternalData
GLuint m_fontTextureId;
GLuint m_largeFontTextureId;
struct sth_stash* m_fontStash;
OpenGL2RenderCallbacks* m_renderCallbacks;
struct sth_stash* m_fontStash2;
RenderCallbacks* m_renderCallbacks;
RenderCallbacks* m_renderCallbacks2;
int m_droidRegular;
int m_droidRegular2;
const char* m_frameDumpPngFileName;
FILE* m_ffmpegFile;
GLRenderToTexture* m_renderTexture;
@@ -117,8 +123,161 @@ static GLuint BindFont(const CTexFont *_Font)
return TexID;
}
//static unsigned int s_indexData[INDEX_COUNT];
//static GLuint s_indexArrayObject, s_indexBuffer;
//static GLuint s_vertexArrayObject,s_vertexBuffer;
extern unsigned char OpenSansData[];
struct MyRenderCallbacks : public RenderCallbacks
{
GLInstancingRenderer* m_instancingRenderer;
b3AlignedObjectArray<unsigned char> m_rgbaTexture;
float m_color[4];
float m_worldPosition[3];
float m_worldOrientation[4];
int m_textureIndex;
MyRenderCallbacks(GLInstancingRenderer* instancingRenderer)
:m_instancingRenderer(instancingRenderer),
m_textureIndex(-1)
{
for (int i=0;i<4;i++)
{
m_color[i] = 1;
m_worldOrientation[i]=0;
}
m_worldPosition[0]=0;
m_worldPosition[1]=0;
m_worldPosition[2]=0;
m_worldOrientation[0] = 0;
m_worldOrientation[1] = 0;
m_worldOrientation[2] = 0;
m_worldOrientation[3] = 1;
}
virtual ~MyRenderCallbacks()
{
m_rgbaTexture.clear();
}
virtual void setWorldPosition(float pos[3])
{
for (int i=0;i<3;i++)
{
m_worldPosition[i] = pos[i];
}
}
virtual void setWorldOrientation(float orn[4])
{
for (int i=0;i<4;i++)
{
m_worldOrientation[i] = orn[i];
}
}
virtual void setColorRGBA(float color[4])
{
for (int i=0;i<4;i++)
{
m_color[i] = color[i];
}
}
virtual void updateTexture(sth_texture* texture, sth_glyph* glyph, int textureWidth, int textureHeight)
{
if (glyph)
{
m_rgbaTexture.resize(textureWidth*textureHeight*3);
for (int i=0;i<textureWidth*textureHeight;i++)
{
m_rgbaTexture[i*3+0] = texture->m_texels[i];
m_rgbaTexture[i*3+1] = texture->m_texels[i];
m_rgbaTexture[i*3+2] = texture->m_texels[i];
}
bool flipPixelsY = false;
m_instancingRenderer->updateTexture(m_textureIndex, &m_rgbaTexture[0], flipPixelsY);
} else
{
if (textureWidth && textureHeight)
{
texture->m_texels = (unsigned char*)malloc(textureWidth*textureHeight);
memset(texture->m_texels,0,textureWidth*textureHeight);
if (m_textureIndex<0)
{
m_rgbaTexture.resize(textureWidth*textureHeight*3);
bool flipPixelsY = false;
m_textureIndex = m_instancingRenderer->registerTexture(&m_rgbaTexture[0],textureWidth,textureHeight,flipPixelsY);
int strideInBytes = 9*sizeof(float);
int numVertices = sizeof(cube_vertices_textured)/strideInBytes;
int numIndices = sizeof(cube_indices)/sizeof(int);
float halfExtentsX=1;
float halfExtentsY=1;
float halfExtentsZ=1;
float textureScaling = 4;
b3AlignedObjectArray<CommonGfxVertex3D> verts;
verts.resize(numVertices);
for (int i=0;i<numVertices;i++)
{
verts[i].x = halfExtentsX*cube_vertices_textured[i*9];
verts[i].y = halfExtentsY*cube_vertices_textured[i*9+1];
verts[i].z = halfExtentsZ*cube_vertices_textured[i*9+2];
verts[i].w = cube_vertices_textured[i*9+3];
verts[i].nx = cube_vertices_textured[i*9+4];
verts[i].ny = cube_vertices_textured[i*9+5];
verts[i].nz = cube_vertices_textured[i*9+6];
verts[i].u = cube_vertices_textured[i*9+7]*textureScaling;
verts[i].v = cube_vertices_textured[i*9+8]*textureScaling;
}
int shapeId = m_instancingRenderer->registerShape(&verts[0].x,numVertices,cube_indices,numIndices,B3_GL_TRIANGLES,m_textureIndex);
b3Vector3 pos = b3MakeVector3(0, 0, 0);
b3Quaternion orn(0, 0, 0, 1);
b3Vector4 color = b3MakeVector4(1, 1, 1,1);
b3Vector3 scaling = b3MakeVector3 (.1, .1, .1);
//m_instancingRenderer->registerGraphicsInstance(shapeId, pos, orn, color, scaling);
m_instancingRenderer->writeTransforms();
} else
{
b3Assert(0);
}
} else
{
delete texture->m_texels;
texture->m_texels = 0;
//there is no m_instancingRenderer->freeTexture (yet), all textures are released at reset/deletion of the renderer
}
}
}
virtual void render(sth_texture* texture)
{
int index=0;
float width = 1;
b3AlignedObjectArray< unsigned int> indices;
indices.resize(texture->nverts);
for (int i=0;i<indices.size();i++)
{
indices[i] = i;
}
m_instancingRenderer->drawTexturedTriangleMesh(m_worldPosition,m_worldOrientation, &texture->newverts[0].position.p[0],texture->nverts,&indices[0],indices.size(),m_color,m_textureIndex);
}
};
SimpleOpenGL3App::SimpleOpenGL3App( const char* title, int width,int height, bool allowRetina)
{
gApp = this;
@@ -207,9 +366,11 @@ SimpleOpenGL3App::SimpleOpenGL3App( const char* title, int width,int height, boo
{
m_data->m_renderCallbacks = new OpenGL2RenderCallbacks(m_primRenderer);
m_data->m_renderCallbacks2 = new MyRenderCallbacks(m_instancingRenderer);
m_data->m_fontStash2 = sth_create(512,512, m_data->m_renderCallbacks2);
m_data->m_fontStash = sth_create(512,512,m_data->m_renderCallbacks);//256,256);//,1024);//512,512);
b3Assert(glGetError() ==GL_NO_ERROR);
if (!m_data->m_fontStash)
@@ -218,6 +379,10 @@ SimpleOpenGL3App::SimpleOpenGL3App( const char* title, int width,int height, boo
//fprintf(stderr, "Could not create stash.\n");
}
if (!m_data->m_fontStash2)
{
b3Warning("Could not create fontStash2");
}
unsigned char* data2 = OpenSansData;
unsigned char* data = (unsigned char*) data2;
@@ -225,7 +390,12 @@ SimpleOpenGL3App::SimpleOpenGL3App( const char* title, int width,int height, boo
{
b3Warning("error!\n");
}
b3Assert(glGetError() ==GL_NO_ERROR);
if (!(m_data->m_droidRegular2 = sth_add_font_from_memory(m_data->m_fontStash2, data)))
{
b3Warning("error!\n");
}
b3Assert(glGetError() ==GL_NO_ERROR);
}
}
@@ -235,7 +405,7 @@ struct sth_stash* SimpleOpenGL3App::getFontStash()
return m_data->m_fontStash;
}
void SimpleOpenGL3App::drawText3D( const char* txt, float worldPosX, float worldPosY, float worldPosZ, float size1)
void SimpleOpenGL3App::drawText3D( const char* txt, float position[3], float orientation[4], float color[4], float size, int optionFlag)
{
B3_PROFILE("SimpleOpenGL3App::drawText3D");
float viewMat[16];
@@ -263,29 +433,54 @@ void SimpleOpenGL3App::drawText3D( const char* txt, float worldPosX, float world
glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
int viewport[4]={0,0,m_instancingRenderer->getScreenWidth(),m_instancingRenderer->getScreenHeight()};
float posX = 450.f;
float posY = 100.f;
float posX = position[0];
float posY = position[1];
float posZ = position[2];
float winx,winy, winz;
if (!projectWorldCoordToScreen(worldPosX, worldPosY, worldPosZ,viewMat,projMat,viewport,&winx, &winy, &winz))
{
return;
}
posX = winx;
posY = m_instancingRenderer->getScreenHeight()/2+(m_instancingRenderer->getScreenHeight()/2)-winy;
if (0)//m_useTrueTypeFont)
if (optionFlag&CommonGraphicsApp::eDrawText3D_OrtogonalFaceCamera)
{
if (!projectWorldCoordToScreen(position[0], position[1], position[2],viewMat,projMat,viewport,&winx, &winy, &winz))
{
return;
}
posX = winx;
posY = m_instancingRenderer->getScreenHeight()/2+(m_instancingRenderer->getScreenHeight()/2)-winy;
posZ = 0.f;
}
if (optionFlag&CommonGraphicsApp::eDrawText3D_TrueType)
{
bool measureOnly = false;
float fontSize= 32;//64;//512;//128;
float fontSize= 64;//512;//128;
sth_draw_text(m_data->m_fontStash,
m_data->m_droidRegular,fontSize,posX,posY,
txt,&dx, this->m_instancingRenderer->getScreenWidth(),this->m_instancingRenderer->getScreenHeight(),measureOnly,m_window->getRetinaScale());
sth_end_draw(m_data->m_fontStash);
sth_flush_draw(m_data->m_fontStash);
if (optionFlag&CommonGraphicsApp::eDrawText3D_OrtogonalFaceCamera)
{
sth_draw_text(m_data->m_fontStash,
m_data->m_droidRegular,fontSize,posX,posY,
txt,&dx, this->m_instancingRenderer->getScreenWidth(),this->m_instancingRenderer->getScreenHeight(),measureOnly,m_window->getRetinaScale(),color);
sth_end_draw(m_data->m_fontStash);
sth_flush_draw(m_data->m_fontStash);
} else
{
glEnable(GL_BLEND);
glBlendFunc(GL_SRC_ALPHA, GL_ONE_MINUS_SRC_ALPHA);
m_data->m_renderCallbacks2->setColorRGBA(color);
m_data->m_renderCallbacks2->setWorldPosition(position);
m_data->m_renderCallbacks2->setWorldOrientation(orientation);
sth_draw_text3D(m_data->m_fontStash2,
m_data->m_droidRegular2,fontSize,0,0,0,
txt,&dx,size,color,0);
sth_end_draw(m_data->m_fontStash2);
sth_flush_draw(m_data->m_fontStash2);
glDisable(GL_BLEND);
}
} else
{
//float width = 0.f;
@@ -298,26 +493,38 @@ void SimpleOpenGL3App::drawText3D( const char* txt, float worldPosX, float world
//float extraSpacing = 0.;
float startX = posX;
float startY = posY-g_DefaultLargeFont->m_CharHeight*size1;
float startY = posY+g_DefaultLargeFont->m_CharHeight*size;
float z = position[2];//2.f*winz-1.f;//*(far
if (optionFlag&CommonGraphicsApp::eDrawText3D_OrtogonalFaceCamera)
{
posX = winx;
posY = m_instancingRenderer->getScreenHeight()/2+(m_instancingRenderer->getScreenHeight()/2)-winy;
z = 2.f*winz-1.f;
startY = posY-g_DefaultLargeFont->m_CharHeight*size;
}
while (txt[pos])
{
int c = txt[pos];
//r.h = g_DefaultNormalFont->m_CharHeight;
//r.w = g_DefaultNormalFont->m_CharWidth[c]+extraSpacing;
float endX = startX+g_DefaultLargeFont->m_CharWidth[c]*size1;
float endX = startX+g_DefaultLargeFont->m_CharWidth[c]*size;
if (optionFlag&CommonGraphicsApp::eDrawText3D_OrtogonalFaceCamera)
{
endX = startX+g_DefaultLargeFont->m_CharWidth[c]*size;
}
float endY = posY;
float currentColor[]={1.f,0.2,0.2f,1.f};
//float currentColor[]={1.f,1.,0.2f,1.f};
// m_primRenderer->drawTexturedRect(startX, startY, endX, endY, currentColor,g_DefaultLargeFont->m_CharU0[c],g_DefaultLargeFont->m_CharV0[c],g_DefaultLargeFont->m_CharU1[c],g_DefaultLargeFont->m_CharV1[c]);
float u0 = g_DefaultLargeFont->m_CharU0[c];
float u1 = g_DefaultLargeFont->m_CharU1[c];
float v0 = g_DefaultLargeFont->m_CharV0[c];
float v1 = g_DefaultLargeFont->m_CharV1[c];
float color[4] = {currentColor[0],currentColor[1],currentColor[2],currentColor[3]};
//float color[4] = {currentColor[0],currentColor[1],currentColor[2],currentColor[3]};
float x0 = startX;
float x1 = endX;
float y0 = startY;
@@ -325,20 +532,31 @@ void SimpleOpenGL3App::drawText3D( const char* txt, float worldPosX, float world
int screenWidth = m_instancingRenderer->getScreenWidth();
int screenHeight = m_instancingRenderer->getScreenHeight();
float z = 2.f*winz-1.f;//*(far
float identity[16]={1,0,0,0,
0,1,0,0,
0,0,1,0,
0,0,0,1};
if (optionFlag&CommonGraphicsApp::eDrawText3D_OrtogonalFaceCamera)
{
PrimVertex vertexData[4] = {
PrimVertex(PrimVec4(-1.f+2.f*x0/float(screenWidth), 1.f-2.f*y0/float(screenHeight), z, 1.f ), PrimVec4( color[0], color[1], color[2], color[3] ) ,PrimVec2(u0,v0)),
PrimVertex(PrimVec4(-1.f+2.f*x0/float(screenWidth), 1.f-2.f*y1/float(screenHeight), z, 1.f ), PrimVec4( color[0], color[1], color[2], color[3] ) ,PrimVec2(u0,v1)),
PrimVertex(PrimVec4( -1.f+2.f*x1/float(screenWidth), 1.f-2.f*y1/float(screenHeight), z, 1.f ), PrimVec4(color[0], color[1], color[2], color[3]) ,PrimVec2(u1,v1)),
PrimVertex(PrimVec4( -1.f+2.f*x1/float(screenWidth), 1.f-2.f*y0/float(screenHeight), z, 1.f ), PrimVec4( color[0], color[1], color[2], color[3] ) ,PrimVec2(u1,v0))
};
m_primRenderer->drawTexturedRect3D(vertexData[0],vertexData[1],vertexData[2],vertexData[3],identity,identity,false);
} else
{
PrimVertex vertexData[4] = {
PrimVertex(PrimVec4(x0, y0, z, 1.f ), PrimVec4( color[0], color[1], color[2], color[3] ) ,PrimVec2(u0,v0)),
PrimVertex(PrimVec4(x0, y1, z, 1.f ), PrimVec4( color[0], color[1], color[2], color[3] ) ,PrimVec2(u0,v1)),
PrimVertex(PrimVec4( x1, y1, z, 1.f ), PrimVec4(color[0], color[1], color[2], color[3]) ,PrimVec2(u1,v1)),
PrimVertex(PrimVec4( x1, y0, z, 1.f ), PrimVec4( color[0], color[1], color[2], color[3] ) ,PrimVec2(u1,v0))
};
m_primRenderer->drawTexturedRect3D(vertexData[0],vertexData[1],vertexData[2],vertexData[3],viewMat,projMat,false);
}
//DrawTexturedRect(0,r,g_DefaultNormalFont->m_CharU0[c],g_DefaultNormalFont->m_CharV0[c],g_DefaultNormalFont->m_CharU1[c],g_DefaultNormalFont->m_CharV1[c]);
// DrawFilledRect(r);
@@ -353,12 +571,22 @@ void SimpleOpenGL3App::drawText3D( const char* txt, float worldPosX, float world
glDisable(GL_BLEND);
}
void SimpleOpenGL3App::drawText3D( const char* txt, float worldPosX, float worldPosY, float worldPosZ, float size1)
{
float position[3] = {worldPosX,worldPosY,worldPosZ};
float orientation[4] = {0,0,0,1};
float color[4] = {0,0,0,1};
int optionFlags = CommonGraphicsApp::eDrawText3D_OrtogonalFaceCamera;
drawText3D(txt,position,orientation,color,size1,optionFlags);
}
void SimpleOpenGL3App::drawText( const char* txt, int posXi, int posYi, float size)
void SimpleOpenGL3App::drawText( const char* txt, int posXi, int posYi, float size, float colorRGBA[4])
{
float posX = (float)posXi;
@@ -386,7 +614,7 @@ void SimpleOpenGL3App::drawText( const char* txt, int posXi, int posYi, float si
txt,&dx, this->m_instancingRenderer->getScreenWidth(),
this->m_instancingRenderer->getScreenHeight(),
measureOnly,
m_window->getRetinaScale());
m_window->getRetinaScale(),colorRGBA);
sth_end_draw(m_data->m_fontStash);
sth_flush_draw(m_data->m_fontStash);
@@ -445,12 +673,6 @@ void SimpleOpenGL3App::drawTexturedRect(float x0, float y0, float x1, float y1,
struct GfxVertex
{
float x,y,z,w;
float nx,ny,nz;
float u,v;
};
int SimpleOpenGL3App::registerCubeShape(float halfExtentsX,float halfExtentsY, float halfExtentsZ, int textureIndex, float textureScaling)
{
@@ -460,7 +682,7 @@ int SimpleOpenGL3App::registerCubeShape(float halfExtentsX,float halfExtentsY, f
int numVertices = sizeof(cube_vertices_textured)/strideInBytes;
int numIndices = sizeof(cube_indices)/sizeof(int);
b3AlignedObjectArray<GfxVertex> verts;
b3AlignedObjectArray<CommonGfxVertex3D> verts;
verts.resize(numVertices);
for (int i=0;i<numVertices;i++)
{
@@ -663,6 +885,10 @@ SimpleOpenGL3App::~SimpleOpenGL3App()
delete m_primRenderer ;
sth_delete(m_data->m_fontStash);
delete m_data->m_renderCallbacks;
sth_delete(m_data->m_fontStash2);
delete m_data->m_renderCallbacks2;
TwDeleteDefaultFonts();
m_window->closeWindow();