PyBullet: allow to replace existing debug lines in addUserDebugLine through the replaceItemUniqueId argument

See batchRayCast.py for example usage
This commit is contained in:
erwincoumans
2018-06-22 16:47:20 -07:00
parent 6b2cae1b1d
commit 49b0ec08e1
7 changed files with 66 additions and 19 deletions

View File

@@ -3063,7 +3063,6 @@ B3_SHARED_API void b3UserDebugItemSetReplaceItemUniqueId(b3SharedMemoryCommandHa
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_USER_DEBUG_DRAW);
b3Assert(command->m_updateFlags & USER_DEBUG_HAS_TEXT);
command->m_userDebugDrawArgs.m_replaceItemUniqueId = replaceItemUniqueId;
command->m_updateFlags |= USER_DEBUG_HAS_REPLACE_ITEM_UNIQUE_ID;
}

View File

@@ -4582,13 +4582,21 @@ bool PhysicsServerCommandProcessor::processUserDebugDrawCommand(const struct Sha
if (clientCmd.m_updateFlags & USER_DEBUG_HAS_LINE)
{
int replaceItemUid = -1;
if (clientCmd.m_updateFlags&USER_DEBUG_HAS_REPLACE_ITEM_UNIQUE_ID)
{
replaceItemUid = clientCmd.m_userDebugDrawArgs.m_replaceItemUniqueId;
}
int uid = m_data->m_guiHelper->addUserDebugLine(
clientCmd.m_userDebugDrawArgs.m_debugLineFromXYZ,
clientCmd.m_userDebugDrawArgs.m_debugLineToXYZ,
clientCmd.m_userDebugDrawArgs.m_debugLineColorRGB,
clientCmd.m_userDebugDrawArgs.m_lineWidth,
clientCmd.m_userDebugDrawArgs.m_lifeTime,
trackingVisualShapeIndex);
trackingVisualShapeIndex,
replaceItemUid
);
if (uid>=0)
{

View File

@@ -515,6 +515,7 @@ struct UserDebugDrawLine
double m_lifeTime;
int m_itemUniqueId;
int m_trackingVisualShapeIndex;
int m_replaceItemUid;
};
struct UserDebugParameter
@@ -1275,11 +1276,14 @@ public:
btAlignedObjectArray<UserDebugDrawLine> m_userDebugLines;
UserDebugDrawLine m_tmpLine;
int m_resultDebugLineUid;
virtual int addUserDebugLine(const double debugLineFromXYZ[3], const double debugLineToXYZ[3], const double debugLineColorRGB[3], double lineWidth, double lifeTime , int trackingVisualShapeIndex)
virtual int addUserDebugLine(const double debugLineFromXYZ[3], const double debugLineToXYZ[3], const double debugLineColorRGB[3], double lineWidth, double lifeTime , int trackingVisualShapeIndex, int replaceItemUid)
{
m_tmpLine.m_lifeTime = lifeTime;
m_tmpLine.m_lineWidth = lineWidth;
m_tmpLine.m_itemUniqueId = m_uidGenerator++;
m_tmpLine.m_itemUniqueId = replaceItemUid<0? m_uidGenerator++ : replaceItemUid;
m_tmpLine.m_debugLineFromXYZ[0] = debugLineFromXYZ[0];
m_tmpLine.m_debugLineFromXYZ[1] = debugLineFromXYZ[1];
m_tmpLine.m_debugLineFromXYZ[2] = debugLineFromXYZ[2];
@@ -1292,6 +1296,7 @@ public:
m_tmpLine.m_debugLineColorRGB[1] = debugLineColorRGB[1];
m_tmpLine.m_debugLineColorRGB[2] = debugLineColorRGB[2];
m_tmpLine.m_trackingVisualShapeIndex = trackingVisualShapeIndex;
m_tmpLine.m_replaceItemUid = replaceItemUid;
m_cs->lock();
m_cs->setSharedParam(1, eGUIUserDebugAddLine);
m_resultDebugLineUid=-1;
@@ -2365,10 +2370,23 @@ void PhysicsServerExample::updateGraphics()
{
B3_PROFILE("eGUIUserDebugAddLine");
m_multiThreadedHelper->m_userDebugLines.push_back(m_multiThreadedHelper->m_tmpLine);
m_multiThreadedHelper->m_resultDebugLineUid = m_multiThreadedHelper->m_userDebugLines[m_multiThreadedHelper->m_userDebugLines.size()-1].m_itemUniqueId;
if (m_multiThreadedHelper->m_tmpLine.m_replaceItemUid>=0)
{
for (int i=0;i<m_multiThreadedHelper->m_userDebugLines.size();i++)
{
if (m_multiThreadedHelper->m_userDebugLines[i].m_itemUniqueId == m_multiThreadedHelper->m_tmpLine.m_replaceItemUid)
{
m_multiThreadedHelper->m_userDebugLines[i] = m_multiThreadedHelper->m_tmpLine;
m_multiThreadedHelper->m_resultDebugLineUid = m_multiThreadedHelper->m_tmpLine.m_replaceItemUid;
}
}
} else
{
m_multiThreadedHelper->m_userDebugLines.push_back(m_multiThreadedHelper->m_tmpLine);
m_multiThreadedHelper->m_resultDebugLineUid = m_multiThreadedHelper->m_userDebugLines[m_multiThreadedHelper->m_userDebugLines.size()-1].m_itemUniqueId;
}
m_multiThreadedHelper->mainThreadRelease();
break;
break;
}
case eGUIUserDebugRemoveItem:
{