This commit is contained in:
Erwin Coumans
2017-03-13 11:02:10 -07:00
7 changed files with 73 additions and 33 deletions

View File

@@ -427,24 +427,32 @@ void OpenGLGuiHelper::copyCameraImageData(const float viewMatrix[16], const floa
SimpleCamera tempCam; SimpleCamera tempCam;
getRenderInterface()->setActiveCamera(&tempCam); getRenderInterface()->setActiveCamera(&tempCam);
getRenderInterface()->getActiveCamera()->setVRCamera(viewMatrix,projectionMatrix); getRenderInterface()->getActiveCamera()->setVRCamera(viewMatrix,projectionMatrix);
{
BT_PROFILE("renderScene");
getRenderInterface()->renderScene(); getRenderInterface()->renderScene();
}
getRenderInterface()->setActiveCamera(oldCam); getRenderInterface()->setActiveCamera(oldCam);
{ {
BT_PROFILE("copy pixels");
btAlignedObjectArray<unsigned char> sourceRgbaPixelBuffer; btAlignedObjectArray<unsigned char> sourceRgbaPixelBuffer;
btAlignedObjectArray<float> sourceDepthBuffer; btAlignedObjectArray<float> sourceDepthBuffer;
//copy the image into our local cache //copy the image into our local cache
sourceRgbaPixelBuffer.resize(sourceWidth*sourceHeight*numBytesPerPixel); sourceRgbaPixelBuffer.resize(sourceWidth*sourceHeight*numBytesPerPixel);
sourceDepthBuffer.resize(sourceWidth*sourceHeight); sourceDepthBuffer.resize(sourceWidth*sourceHeight);
{
BT_PROFILE("getScreenPixels");
m_data->m_glApp->getScreenPixels(&(sourceRgbaPixelBuffer[0]),sourceRgbaPixelBuffer.size(), &sourceDepthBuffer[0],sizeof(float)*sourceDepthBuffer.size()); m_data->m_glApp->getScreenPixels(&(sourceRgbaPixelBuffer[0]),sourceRgbaPixelBuffer.size(), &sourceDepthBuffer[0],sizeof(float)*sourceDepthBuffer.size());
}
m_data->m_rgbaPixelBuffer1.resize(destinationWidth*destinationHeight*numBytesPerPixel); m_data->m_rgbaPixelBuffer1.resize(destinationWidth*destinationHeight*numBytesPerPixel);
m_data->m_depthBuffer1.resize(destinationWidth*destinationHeight); m_data->m_depthBuffer1.resize(destinationWidth*destinationHeight);
//rescale and flip //rescale and flip
for (int i=0;i<destinationWidth;i++)
{ {
BT_PROFILE("resize and flip");
for (int j=0;j<destinationHeight;j++) for (int j=0;j<destinationHeight;j++)
{
for (int i=0;i<destinationWidth;i++)
{ {
int xIndex = int(float(i)*(float(sourceWidth)/float(destinationWidth))); int xIndex = int(float(i)*(float(sourceWidth)/float(destinationWidth)));
int yIndex = int(float(destinationHeight-1-j)*(float(sourceHeight)/float(destinationHeight))); int yIndex = int(float(destinationHeight-1-j)*(float(sourceHeight)/float(destinationHeight)));
@@ -454,20 +462,32 @@ void OpenGLGuiHelper::copyCameraImageData(const float viewMatrix[16], const floa
int sourcePixelIndex = (xIndex+yIndex*sourceWidth)*bytesPerPixel; int sourcePixelIndex = (xIndex+yIndex*sourceWidth)*bytesPerPixel;
int sourceDepthIndex = xIndex+yIndex*sourceWidth; int sourceDepthIndex = xIndex+yIndex*sourceWidth;
#define COPY4PIXELS 1
#ifdef COPY4PIXELS
int* dst = (int*)&m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+0];
int* src = (int*)&sourceRgbaPixelBuffer[sourcePixelIndex+0];
*dst = *src;
#else
m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+0] = sourceRgbaPixelBuffer[sourcePixelIndex+0]; m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+0] = sourceRgbaPixelBuffer[sourcePixelIndex+0];
m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+1] = sourceRgbaPixelBuffer[sourcePixelIndex+1]; m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+1] = sourceRgbaPixelBuffer[sourcePixelIndex+1];
m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+2] = sourceRgbaPixelBuffer[sourcePixelIndex+2]; m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+2] = sourceRgbaPixelBuffer[sourcePixelIndex+2];
m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+3] = 255; m_data->m_rgbaPixelBuffer1[(i+j*destinationWidth)*4+3] = 255;
#endif
if (depthBuffer)
{
m_data->m_depthBuffer1[i+j*destinationWidth] = sourceDepthBuffer[sourceDepthIndex]; m_data->m_depthBuffer1[i+j*destinationWidth] = sourceDepthBuffer[sourceDepthIndex];
}
} }
} }
} }
} }
}
if (pixelsRGBA) if (pixelsRGBA)
{ {
BT_PROFILE("copy rgba pixels");
for (int i=0;i<numRequestedPixels*numBytesPerPixel;i++) for (int i=0;i<numRequestedPixels*numBytesPerPixel;i++)
{ {
pixelsRGBA[i] = m_data->m_rgbaPixelBuffer1[i+startPixelIndex*numBytesPerPixel]; pixelsRGBA[i] = m_data->m_rgbaPixelBuffer1[i+startPixelIndex*numBytesPerPixel];
@@ -475,6 +495,8 @@ void OpenGLGuiHelper::copyCameraImageData(const float viewMatrix[16], const floa
} }
if (depthBuffer) if (depthBuffer)
{ {
BT_PROFILE("copy depth buffer pixels");
for (int i=0;i<numRequestedPixels;i++) for (int i=0;i<numRequestedPixels;i++)
{ {
depthBuffer[i] = m_data->m_depthBuffer1[i+startPixelIndex]; depthBuffer[i] = m_data->m_depthBuffer1[i+startPixelIndex];

View File

@@ -454,6 +454,7 @@ struct MinitaurStateLogger : public InternalStateLogger
m_logFileHandle(0), m_logFileHandle(0),
m_minitaurMultiBody(minitaurMultiBody) m_minitaurMultiBody(minitaurMultiBody)
{ {
m_loggingUniqueId = loggingUniqueId;
m_loggingType = STATE_LOGGING_MINITAUR; m_loggingType = STATE_LOGGING_MINITAUR;
m_motorIdList.resize(motorIdList.size()); m_motorIdList.resize(motorIdList.size());
for (int m=0;m<motorIdList.size();m++) for (int m=0;m<motorIdList.size();m++)
@@ -578,6 +579,7 @@ struct GenericRobotStateLogger : public InternalStateLogger
m_filterObjectUniqueId(false), m_filterObjectUniqueId(false),
m_maxLogDof(maxLogDof) m_maxLogDof(maxLogDof)
{ {
m_loggingUniqueId = loggingUniqueId;
m_loggingType = STATE_LOGGING_GENERIC_ROBOT; m_loggingType = STATE_LOGGING_GENERIC_ROBOT;
btAlignedObjectArray<std::string> structNames; btAlignedObjectArray<std::string> structNames;

View File

@@ -5380,6 +5380,10 @@ initpybullet(void)
PyModule_AddIntConstant(m, "COV_ENABLE_GUI", COV_ENABLE_GUI); PyModule_AddIntConstant(m, "COV_ENABLE_GUI", COV_ENABLE_GUI);
PyModule_AddIntConstant(m, "COV_ENABLE_SHADOWS", COV_ENABLE_SHADOWS); PyModule_AddIntConstant(m, "COV_ENABLE_SHADOWS", COV_ENABLE_SHADOWS);
PyModule_AddIntConstant(m, "COV_ENABLE_WIREFRAME", COV_ENABLE_WIREFRAME); PyModule_AddIntConstant(m, "COV_ENABLE_WIREFRAME", COV_ENABLE_WIREFRAME);
PyModule_AddIntConstant(m, "ER_TINY_RENDERER", ER_TINY_RENDERER);
PyModule_AddIntConstant(m, "ER_BULLET_HARDWARE_OPENGL", ER_BULLET_HARDWARE_OPENGL);
PyModule_AddIntConstant(m,"B3G_F1",B3G_F1); PyModule_AddIntConstant(m,"B3G_F1",B3G_F1);
PyModule_AddIntConstant(m,"B3G_F2",B3G_F2); PyModule_AddIntConstant(m,"B3G_F2",B3G_F2);
PyModule_AddIntConstant(m,"B3G_F3",B3G_F3); PyModule_AddIntConstant(m,"B3G_F3",B3G_F3);

View File

@@ -29,7 +29,8 @@ for pitch in range (0,360,10) :
viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex) viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex)
aspect = pixelWidth / pixelHeight; aspect = pixelWidth / pixelHeight;
projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane); projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane);
img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, lightDirection,lightColor) #getCameraImage can also use renderer=pybullet.ER_BULLET_HARDWARE_OPENGL
img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, lightDirection,lightColor,renderer=pybullet.ER_TINY_RENDERER)
w=img_arr[0] w=img_arr[0]
h=img_arr[1] h=img_arr[1]
rgb=img_arr[2] rgb=img_arr[2]

View File

@@ -6,7 +6,7 @@ import matplotlib.pyplot as plt
import pybullet import pybullet
import time import time
pybullet.connect(pybullet.DIRECT) pybullet.connect(pybullet.GUI)
pybullet.loadURDF("r2d2.urdf") pybullet.loadURDF("r2d2.urdf")
camTargetPos = [0,0,0] camTargetPos = [0,0,0]
@@ -18,8 +18,8 @@ pitch = 10.0
roll=0 roll=0
upAxisIndex = 2 upAxisIndex = 2
camDistance = 4 camDistance = 4
pixelWidth = 1920 pixelWidth = 1024
pixelHeight = 1080 pixelHeight = 768
nearPlane = 0.01 nearPlane = 0.01
farPlane = 1000 farPlane = 1000
@@ -31,7 +31,7 @@ for pitch in range (0,360,10) :
viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex) viewMatrix = pybullet.computeViewMatrixFromYawPitchRoll(camTargetPos, camDistance, yaw, pitch, roll, upAxisIndex)
aspect = pixelWidth / pixelHeight; aspect = pixelWidth / pixelHeight;
projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane); projectionMatrix = pybullet.computeProjectionMatrixFOV(fov, aspect, nearPlane, farPlane);
img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, [0,1,0]) img_arr = pybullet.getCameraImage(pixelWidth, pixelHeight, viewMatrix,projectionMatrix, [0,1,0],renderer=pybullet.ER_BULLET_HARDWARE_OPENGL)
stop = time.time() stop = time.time()
print ("renderImage %f" % (stop - start)) print ("renderImage %f" % (stop - start))
@@ -40,13 +40,12 @@ for pitch in range (0,360,10) :
rgb=img_arr[2] #color data RGB rgb=img_arr[2] #color data RGB
dep=img_arr[3] #depth data dep=img_arr[3] #depth data
print 'width = %d height = %d' % (w,h) print ('width = %d height = %d' % (w,h))
#note that sending the data to matplotlib is really slow #note that sending the data to matplotlib is really slow
#show
plt.imshow(rgb,interpolation='none') plt.imshow(rgb,interpolation='none')
#plt.show() plt.pause(0.001)
plt.pause(0.01)
main_stop = time.time() main_stop = time.time()

View File

@@ -53,15 +53,28 @@ def convertSensor(x):
b = (v-minV)/float(maxV-minV) b = (v-minV)/float(maxV-minV)
return (1.0-b) return (1.0-b)
controllerId = -1
serialSteps = 0
serialStepsUntilCheckVREvents = 3
ser = serial.Serial(port='COM9',baudrate=115200,parity=serial.PARITY_ODD,stopbits=serial.STOPBITS_TWO,bytesize=serial.SEVENBITS) ser = serial.Serial(port='COM9',baudrate=115200,parity=serial.PARITY_ODD,stopbits=serial.STOPBITS_TWO,bytesize=serial.SEVENBITS)
if (ser.isOpen()): if (ser.isOpen()):
while True: while True:
events = p.getVREvents() events = p.getVREvents()
for e in (events): for e in (events):
if (e[BUTTONS][33]&p.VR_BUTTON_IS_DOWN): if (e[BUTTONS][33]&p.VR_BUTTON_IS_DOWN):
controllerId = e[0]
if (e[0] == controllerId):
p.changeConstraint(hand_cid,e[POSITION],e[ORIENTATION], maxForce=50) p.changeConstraint(hand_cid,e[POSITION],e[ORIENTATION], maxForce=50)
serialSteps = 0
while ser.inWaiting() > 0: while ser.inWaiting() > 0:
serialSteps=serialSteps+1
if (serialSteps>serialStepsUntilCheckVREvents):
ser.flushInput()
break
line = str(ser.readline()) line = str(ser.readline())
words = line.split(",") words = line.split(",")
if (len(words)==6): if (len(words)==6):

View File

@@ -124,7 +124,6 @@ public:
btCollisionShape* getCollisionShapeByIndex(int index); btCollisionShape* getCollisionShapeByIndex(int index);
int getNumRigidBodies() const; int getNumRigidBodies() const;
btCollisionObject* getRigidBodyByIndex(int index) const; btCollisionObject* getRigidBodyByIndex(int index) const;
int getNumConstraints() const;
int getNumBvhs() const; int getNumBvhs() const;
btOptimizedBvh* getBvhByIndex(int index) const; btOptimizedBvh* getBvhByIndex(int index) const;