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

@@ -9,22 +9,34 @@ if (useGui):
else:
p.connect(p.DIRECT)
p.configureDebugVisualizer(p.COV_ENABLE_GUI,0)
#p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
p.loadURDF("samurai.urdf")
#p.loadURDF("samurai.urdf")
p.loadURDF("r2d2.urdf",[3,3,1])
rayFrom=[]
rayTo=[]
rayIds=[]
numRays = 1024
rayLen = 13
rayHitColor = [1,0,0]
rayMissColor = [0,1,0]
replaceLines = True
for i in range (numRays):
rayFrom.append([0,0,1])
rayTo.append([rayLen*math.sin(2.*math.pi*float(i)/numRays), rayLen*math.cos(2.*math.pi*float(i)/numRays),1])
if (replaceLines):
rayIds.append(p.addUserDebugLine(rayFrom[i], rayTo[i], rayMissColor))
else:
rayIds.append(-1)
if (not useGui):
timingLog = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS,"rayCastBench.json")
@@ -38,24 +50,26 @@ for i in range (numSteps):
for j in range (8):
results = p.rayTestBatch(rayFrom,rayTo,j+1)
for i in range (10):
p.removeAllUserDebugItems()
#for i in range (10):
# p.removeAllUserDebugItems()
rayHitColor = [1,0,0]
rayMissColor = [0,1,0]
if (useGui):
p.removeAllUserDebugItems()
if (not replaceLines):
p.removeAllUserDebugItems()
for i in range (numRays):
hitObjectUid=results[i][0]
if (hitObjectUid<0):
p.addUserDebugLine(rayFrom[i],rayTo[i], rayMissColor)
hitPosition =[0,0,0]
p.addUserDebugLine(rayFrom[i],rayTo[i], rayMissColor,replaceItemUniqueId=rayIds[i])
else:
hitPosition = results[i][3]
p.addUserDebugLine(rayFrom[i],hitPosition, rayHitColor)
p.addUserDebugLine(rayFrom[i],hitPosition, rayHitColor,replaceItemUniqueId=rayIds[i])
#time.sleep(1./240.)

View File

@@ -4261,10 +4261,11 @@ static PyObject* pybullet_addUserDebugLine(PyObject* self, PyObject* args, PyObj
double lifeTime = 0.f;
int physicsClientId = 0;
int debugItemUniqueId = -1;
int replaceItemUniqueId = -1;
b3PhysicsClientHandle sm = 0;
static char* kwlist[] = {"lineFromXYZ", "lineToXYZ", "lineColorRGB", "lineWidth", "lifeTime", "parentObjectUniqueId", "parentLinkIndex", "physicsClientId", NULL};
static char* kwlist[] = {"lineFromXYZ", "lineToXYZ", "lineColorRGB", "lineWidth", "lifeTime", "parentObjectUniqueId", "parentLinkIndex", "replaceItemUniqueId", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "OO|Oddiii", kwlist, &lineFromObj, &lineToObj, &lineColorRGBObj, &lineWidth, &lifeTime, &parentObjectUniqueId, &parentLinkIndex, &physicsClientId))
if (!PyArg_ParseTupleAndKeywords(args, keywds, "OO|Oddiiii", kwlist, &lineFromObj, &lineToObj, &lineColorRGBObj, &lineWidth, &lifeTime, &parentObjectUniqueId, &parentLinkIndex, &replaceItemUniqueId, &physicsClientId))
{
return NULL;
}
@@ -4293,6 +4294,7 @@ static PyObject* pybullet_addUserDebugLine(PyObject* self, PyObject* args, PyObj
res = pybullet_internalSetVectord(lineColorRGBObj, colorRGB);
}
commandHandle = b3InitUserDebugDrawAddLine3D(sm, fromXYZ, toXYZ, colorRGB, lineWidth, lifeTime);
if (parentObjectUniqueId>=0)
@@ -4300,6 +4302,11 @@ static PyObject* pybullet_addUserDebugLine(PyObject* self, PyObject* args, PyObj
b3UserDebugItemSetParentObject(commandHandle, parentObjectUniqueId,parentLinkIndex);
}
if (replaceItemUniqueId>=0)
{
b3UserDebugItemSetReplaceItemUniqueId(commandHandle,replaceItemUniqueId);
}
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
statusType = b3GetStatusType(statusHandle);
if (statusType == CMD_USER_DEBUG_DRAW_COMPLETED)