regular OR wireframe rendering, not both

add option to perform filtering of 'getClosestPoints' using linkA/linkB.
don't use 'realtimesimulation' as default
add/remove debug items within same thread
pybullet, report contact points and normal as [x,y,z] triplet/vector, not 3 scalars
separate 'getClosestPointsAlgorithm': box-box doesn't report closest points with positive distance, and the query shouldn't impact regular 'closesst points'
This commit is contained in:
erwincoumans
2016-11-19 17:13:56 -08:00
parent 936a104fb2
commit 9ee1c4ec24
19 changed files with 417 additions and 222 deletions

View File

@@ -126,10 +126,6 @@ enum MultiThreadedGUIHelperCommunicationEnums
eGUIHelperRemoveAllGraphicsInstances,
eGUIHelperCopyCameraImageData,
eGUIHelperAutogenerateGraphicsObjects,
eGUIUserDebugAddText,
eGUIUserDebugAddLine,
eGUIUserDebugRemoveItem,
eGUIUserDebugRemoveAllItems,
};
#include <stdio.h>
@@ -701,43 +697,36 @@ public:
m_tmpText.m_textColorRGB[2] = textColorRGB[2];
m_cs->lock();
m_cs->setSharedParam(1, eGUIUserDebugAddText);
m_userDebugText.push_back(m_tmpText);
m_cs->unlock();
while (m_cs->getSharedParam(1) != eGUIHelperIdle)
{
b3Clock::usleep(150);
}
return m_userDebugText[m_userDebugText.size()-1].m_itemUniqueId;
}
btAlignedObjectArray<UserDebugDrawLine> m_userDebugLines;
UserDebugDrawLine m_tmpLine;
virtual int addUserDebugLine(const double debugLineFromXYZ[3], const double debugLineToXYZ[3], const double debugLineColorRGB[3], double lineWidth, double lifeTime )
{
m_tmpLine.m_lifeTime = lifeTime;
m_tmpLine.m_lineWidth = lineWidth;
m_tmpLine.m_itemUniqueId = m_uidGenerator++;
m_tmpLine.m_debugLineFromXYZ[0] = debugLineFromXYZ[0];
m_tmpLine.m_debugLineFromXYZ[1] = debugLineFromXYZ[1];
m_tmpLine.m_debugLineFromXYZ[2] = debugLineFromXYZ[2];
UserDebugDrawLine tmpLine;
m_tmpLine.m_debugLineToXYZ[0] = debugLineToXYZ[0];
m_tmpLine.m_debugLineToXYZ[1] = debugLineToXYZ[1];
m_tmpLine.m_debugLineToXYZ[2] = debugLineToXYZ[2];
tmpLine.m_lifeTime = lifeTime;
tmpLine.m_lineWidth = lineWidth;
tmpLine.m_itemUniqueId = m_uidGenerator++;
tmpLine.m_debugLineFromXYZ[0] = debugLineFromXYZ[0];
tmpLine.m_debugLineFromXYZ[1] = debugLineFromXYZ[1];
tmpLine.m_debugLineFromXYZ[2] = debugLineFromXYZ[2];
tmpLine.m_debugLineToXYZ[0] = debugLineToXYZ[0];
tmpLine.m_debugLineToXYZ[1] = debugLineToXYZ[1];
tmpLine.m_debugLineToXYZ[2] = debugLineToXYZ[2];
m_tmpLine.m_debugLineColorRGB[0] = debugLineColorRGB[0];
m_tmpLine.m_debugLineColorRGB[1] = debugLineColorRGB[1];
m_tmpLine.m_debugLineColorRGB[2] = debugLineColorRGB[2];
tmpLine.m_debugLineColorRGB[0] = debugLineColorRGB[0];
tmpLine.m_debugLineColorRGB[1] = debugLineColorRGB[1];
tmpLine.m_debugLineColorRGB[2] = debugLineColorRGB[2];
m_cs->lock();
m_cs->setSharedParam(1, eGUIUserDebugAddLine);
m_userDebugLines.push_back(tmpLine);
m_cs->unlock();
while (m_cs->getSharedParam(1) != eGUIHelperIdle)
{
b3Clock::usleep(150);
}
return m_userDebugLines[m_userDebugLines.size()-1].m_itemUniqueId;
}
@@ -747,23 +736,38 @@ public:
{
m_removeDebugItemUid = debugItemUniqueId;
m_cs->lock();
m_cs->setSharedParam(1, eGUIUserDebugRemoveItem);
m_cs->unlock();
while (m_cs->getSharedParam(1) != eGUIHelperIdle)
for (int i = 0; i<m_userDebugLines.size(); i++)
{
b3Clock::usleep(150);
if (m_userDebugLines[i].m_itemUniqueId == m_removeDebugItemUid)
{
m_userDebugLines.swap(i, m_userDebugLines.size() - 1);
m_userDebugLines.pop_back();
break;
}
}
for (int i = 0; i<m_userDebugText.size(); i++)
{
if (m_userDebugText[i].m_itemUniqueId == m_removeDebugItemUid)
{
m_userDebugText.swap(i, m_userDebugText.size() - 1);
m_userDebugText.pop_back();
break;
}
}
m_cs->unlock();
}
virtual void removeAllUserDebugItems( )
{
m_cs->lock();
m_cs->setSharedParam(1, eGUIUserDebugRemoveAllItems);
m_userDebugLines.clear();
m_userDebugText.clear();
m_uidGenerator = 0;
m_cs->unlock();
while (m_cs->getSharedParam(1) != eGUIHelperIdle)
{
b3Clock::usleep(150);
}
}
@@ -825,6 +829,7 @@ public:
virtual bool wantsTermination();
virtual bool isConnected();
virtual void renderScene();
void drawUserDebugLines();
virtual void exitPhysics();
virtual void physicsDebugDraw(int debugFlags);
@@ -1247,60 +1252,6 @@ void PhysicsServerExample::stepSimulation(float deltaTime)
break;
}
case eGUIUserDebugAddText:
{
m_multiThreadedHelper->m_userDebugText.push_back(m_multiThreadedHelper->m_tmpText);
m_multiThreadedHelper->getCriticalSection()->lock();
m_multiThreadedHelper->getCriticalSection()->setSharedParam(1, eGUIHelperIdle);
m_multiThreadedHelper->getCriticalSection()->unlock();
break;
}
case eGUIUserDebugAddLine:
{
m_multiThreadedHelper->m_userDebugLines.push_back(m_multiThreadedHelper->m_tmpLine);
m_multiThreadedHelper->getCriticalSection()->lock();
m_multiThreadedHelper->getCriticalSection()->setSharedParam(1, eGUIHelperIdle);
m_multiThreadedHelper->getCriticalSection()->unlock();
break;
}
case eGUIUserDebugRemoveItem:
{
for (int i=0;i<m_multiThreadedHelper->m_userDebugLines.size();i++)
{
if (m_multiThreadedHelper->m_userDebugLines[i].m_itemUniqueId == m_multiThreadedHelper->m_removeDebugItemUid)
{
m_multiThreadedHelper->m_userDebugLines.swap(i,m_multiThreadedHelper->m_userDebugLines.size()-1);
m_multiThreadedHelper->m_userDebugLines.pop_back();
break;
}
}
for (int i=0;i<m_multiThreadedHelper->m_userDebugText.size();i++)
{
if (m_multiThreadedHelper->m_userDebugText[i].m_itemUniqueId == m_multiThreadedHelper->m_removeDebugItemUid)
{
m_multiThreadedHelper->m_userDebugText.swap(i,m_multiThreadedHelper->m_userDebugText.size()-1);
m_multiThreadedHelper->m_userDebugText.pop_back();
break;
}
}
m_multiThreadedHelper->getCriticalSection()->lock();
m_multiThreadedHelper->getCriticalSection()->setSharedParam(1, eGUIHelperIdle);
m_multiThreadedHelper->getCriticalSection()->unlock();
break;
}
case eGUIUserDebugRemoveAllItems:
{
m_multiThreadedHelper->m_userDebugLines.clear();
m_multiThreadedHelper->m_userDebugText.clear();
m_multiThreadedHelper->m_uidGenerator = 0;
m_multiThreadedHelper->getCriticalSection()->lock();
m_multiThreadedHelper->getCriticalSection()->setSharedParam(1, eGUIHelperIdle);
m_multiThreadedHelper->getCriticalSection()->unlock();
break;
}
case eGUIHelperIdle:
{
break;
@@ -1353,7 +1304,53 @@ extern int gHuskyId;
extern btTransform huskyTr;
void PhysicsServerExample::drawUserDebugLines()
{
static char line0[1024];
static char line1[1024];
//draw all user-debug-lines
//add array of lines
//draw all user- 'text3d' messages
if (m_multiThreadedHelper)
{
m_args[0].m_cs->lock();
for (int i = 0; i<m_multiThreadedHelper->m_userDebugLines.size(); i++)
{
btVector3 from;
from.setValue(m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[0],
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[1],
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[2]);
btVector3 toX;
toX.setValue(m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[0],
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[1],
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[2]);
btVector3 color;
color.setValue(m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[0],
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[1],
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[2]);
m_guiHelper->getAppInterface()->m_renderer->drawLine(from, toX, color, m_multiThreadedHelper->m_userDebugLines[i].m_lineWidth);
}
for (int i = 0; i<m_multiThreadedHelper->m_userDebugText.size(); i++)
{
m_guiHelper->getAppInterface()->drawText3D(m_multiThreadedHelper->m_userDebugText[i].m_text,
m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[0],
m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[1],
m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[2],
m_multiThreadedHelper->m_userDebugText[i].textSize);
}
m_args[0].m_cs->unlock();
}
}
void PhysicsServerExample::renderScene()
{
@@ -1369,48 +1366,8 @@ void PhysicsServerExample::renderScene()
B3_PROFILE("PhysicsServerExample::RenderScene");
static char line0[1024];
static char line1[1024];
//draw all user-debug-lines
//add array of lines
//draw all user- 'text3d' messages
if (m_multiThreadedHelper)
{
for (int i=0;i<m_multiThreadedHelper->m_userDebugLines.size();i++)
{
btVector3 from;
from.setValue( m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[0],
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[1],
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineFromXYZ[2]);
btVector3 toX;
toX.setValue( m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[0],
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[1],
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineToXYZ[2]);
btVector3 color;
color.setValue( m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[0],
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[1],
m_multiThreadedHelper->m_userDebugLines[i].m_debugLineColorRGB[2]);
m_guiHelper->getAppInterface()->m_renderer->drawLine(from, toX, color, m_multiThreadedHelper->m_userDebugLines[i].m_lineWidth);
}
for (int i=0;i<m_multiThreadedHelper->m_userDebugText.size();i++)
{
m_guiHelper->getAppInterface()->drawText3D(m_multiThreadedHelper->m_userDebugText[i].m_text,
m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[0],
m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[1],
m_multiThreadedHelper->m_userDebugText[i].m_textPositionXYZ[2],
m_multiThreadedHelper->m_userDebugText[i].textSize);
}
}
drawUserDebugLines();
if (gEnableRealTimeSimVR)
{
@@ -1424,6 +1381,7 @@ void PhysicsServerExample::renderScene()
static int count = 0;
count++;
#if 0
if (0 == (count & 1))
{
btScalar curTime = m_clock.getTimeSeconds();
@@ -1444,6 +1402,7 @@ void PhysicsServerExample::renderScene()
worseFps = 1000000;
}
}
#endif
#ifdef BT_ENABLE_VR
if ((gInternalSimFlags&2 ) && m_tinyVrGui==0)
@@ -1544,6 +1503,8 @@ void PhysicsServerExample::renderScene()
void PhysicsServerExample::physicsDebugDraw(int debugDrawFlags)
{
drawUserDebugLines();
///debug rendering
m_physicsServer.physicsDebugDraw(debugDrawFlags);