revert exposing getSharedMemoryStreamBuffer / adding to command structure
use 16k rays by default add uploadRaysToSharedMemory method
This commit is contained in:
@@ -2,9 +2,15 @@ import pybullet as p
|
||||
import time
|
||||
import math
|
||||
|
||||
p.connect(p.DIRECT)#GUI)
|
||||
useGui = True
|
||||
|
||||
if (useGui):
|
||||
p.connect(p.GUI)
|
||||
else:
|
||||
p.connect(p.DIRECT)
|
||||
|
||||
#p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||
|
||||
p.configureDebugVisualizer(p.COV_ENABLE_RENDERING,0)
|
||||
p.loadURDF("samurai.urdf")
|
||||
p.loadURDF("r2d2.urdf",[3,3,1])
|
||||
|
||||
@@ -12,7 +18,7 @@ p.loadURDF("r2d2.urdf",[3,3,1])
|
||||
rayFrom=[]
|
||||
rayTo=[]
|
||||
|
||||
numRays = 2048
|
||||
numRays = 1024
|
||||
rayLen = 13
|
||||
|
||||
|
||||
@@ -20,25 +26,38 @@ 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])
|
||||
|
||||
timingLog = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS,"rayCastBench.json")
|
||||
for i in range (10):
|
||||
if (not useGui):
|
||||
timingLog = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS,"rayCastBench.json")
|
||||
|
||||
numSteps = 10
|
||||
if (useGui):
|
||||
numSteps = 327680
|
||||
|
||||
for i in range (numSteps):
|
||||
p.stepSimulation()
|
||||
for j in range (8):
|
||||
results = p.rayTestBatch(rayFrom,rayTo,j+1)
|
||||
|
||||
for i in range (10):
|
||||
p.removeAllUserDebugItems()
|
||||
p.removeAllUserDebugItems()
|
||||
|
||||
|
||||
|
||||
rayHitColor = [1,0,0]
|
||||
rayMissColor = [0,1,0]
|
||||
#for i in range (numRays):
|
||||
# if (results[i][0]<0):
|
||||
# p.addUserDebugLine(rayFrom[i],rayTo[i], rayMissColor)
|
||||
# else:
|
||||
# p.addUserDebugLine(rayFrom[i],rayTo[i], rayHitColor)
|
||||
if (useGui):
|
||||
p.removeAllUserDebugItems()
|
||||
for i in range (numRays):
|
||||
hitObjectUid=results[i][0]
|
||||
|
||||
|
||||
if (hitObjectUid<0):
|
||||
p.addUserDebugLine(rayFrom[i],rayTo[i], rayMissColor)
|
||||
else:
|
||||
hitPosition = results[i][3]
|
||||
p.addUserDebugLine(rayFrom[i],hitPosition, rayHitColor)
|
||||
|
||||
#time.sleep(1./240.)
|
||||
|
||||
p.stopStateLogging(timingLog)
|
||||
if (not useGui):
|
||||
p.stopStateLogging(timingLog)
|
||||
@@ -4729,7 +4729,7 @@ static PyObject* pybullet_rayTestBatch(PyObject* self, PyObject* args, PyObject*
|
||||
} else
|
||||
{
|
||||
int i;
|
||||
|
||||
|
||||
if (lenFrom > MAX_RAY_INTERSECTION_BATCH_SIZE)
|
||||
{
|
||||
PyErr_SetString(SpamError, "Number of rays exceed the maximum batch size.");
|
||||
@@ -4748,7 +4748,7 @@ static PyObject* pybullet_rayTestBatch(PyObject* self, PyObject* args, PyObject*
|
||||
if ((pybullet_internalSetVectord(rayFromObj, rayFromWorld)) &&
|
||||
(pybullet_internalSetVectord(rayToObj, rayToWorld)))
|
||||
{
|
||||
b3RaycastBatchAddRay(commandHandle, rayFromWorld, rayToWorld);
|
||||
b3RaycastBatchAddRay(sm, commandHandle, rayFromWorld, rayToWorld);
|
||||
} else
|
||||
{
|
||||
PyErr_SetString(SpamError, "Items in the from/to positions need to be an [x,y,z] list of 3 floats/doubles");
|
||||
|
||||
Reference in New Issue
Block a user