Merge pull request #2136 from erwincoumans/master

fix issue with retina scale and picking in createVisualShape.py example, meshScale issue
This commit is contained in:
erwincoumans
2019-03-02 15:14:06 -08:00
committed by GitHub
3 changed files with 13 additions and 13 deletions

View File

@@ -1009,8 +1009,8 @@ bool OpenGLGuiHelper::getCameraInfo(int* width, int* height, float viewMatrix[16
{ {
if (getRenderInterface() && getRenderInterface()->getActiveCamera()) if (getRenderInterface() && getRenderInterface()->getActiveCamera())
{ {
*width = m_data->m_glApp->m_window->getWidth() * m_data->m_glApp->m_window->getRetinaScale(); *width = m_data->m_glApp->m_window->getWidth();
*height = m_data->m_glApp->m_window->getHeight() * m_data->m_glApp->m_window->getRetinaScale(); *height = m_data->m_glApp->m_window->getHeight();
getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix); getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix);
getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix); getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix);
getRenderInterface()->getActiveCamera()->getCameraUpVector(camUp); getRenderInterface()->getActiveCamera()->getCameraUpVector(camUp);
@@ -1043,12 +1043,12 @@ bool OpenGLGuiHelper::getCameraInfo(int* width, int* height, float viewMatrix[16
btScalar aspect = float(*width) / float(*height); btScalar aspect = float(*width) / float(*height);
hori *= aspect; hori *= aspect;
//compute 'hor' and 'vert' vectors, useful to generate raytracer rays //compute 'hor' and 'vert' vectors, useful to generate raytracer rays
hor[0] = hori[0]* m_data->m_glApp->m_window->getRetinaScale(); hor[0] = hori[0];
hor[1] = hori[1]* m_data->m_glApp->m_window->getRetinaScale(); hor[1] = hori[1];
hor[2] = hori[2]* m_data->m_glApp->m_window->getRetinaScale(); hor[2] = hori[2];
vert[0] = vertical[0]* m_data->m_glApp->m_window->getRetinaScale(); vert[0] = vertical[0];
vert[1] = vertical[1]* m_data->m_glApp->m_window->getRetinaScale(); vert[1] = vertical[1];
vert[2] = vertical[2]* m_data->m_glApp->m_window->getRetinaScale(); vert[2] = vertical[2];
*yaw = getRenderInterface()->getActiveCamera()->getCameraYaw(); *yaw = getRenderInterface()->getActiveCamera()->getCameraYaw();
*pitch = getRenderInterface()->getActiveCamera()->getCameraPitch(); *pitch = getRenderInterface()->getActiveCamera()->getCameraPitch();

View File

@@ -125,7 +125,7 @@ indices=[ 0, 1, 2, 0, 2, 3, #//ground face
20, 21, 22, 20, 22, 23] 20, 21, 22, 20, 22, 23]
#the visual shape and collision shape can be re-used by all createMultiBody instances (instancing) #the visual shape and collision shape can be re-used by all createMultiBody instances (instancing)
visualShapeId = p.createVisualShape(shapeType=p.GEOM_MESH,rgbaColor=[1,1,1,1], specularColor=[0.4,.4,0], visualFramePosition=shift, meshScale=[1,1,1], vertices=vertices, indices=indices, uvs=uvs, normals=normals) visualShapeId = p.createVisualShape(shapeType=p.GEOM_MESH,rgbaColor=[1,1,1,1], specularColor=[0.4,.4,0], visualFramePosition=shift, meshScale=meshScale, vertices=vertices, indices=indices, uvs=uvs, normals=normals)
#visualShapeId = p.createVisualShape(shapeType=p.GEOM_BOX,rgbaColor=[1,1,1,1], halfExtents=[0.5,0.5,0.5],specularColor=[0.4,.4,0], visualFramePosition=shift, meshScale=[1,1,1], vertices=vertices, indices=indices) #visualShapeId = p.createVisualShape(shapeType=p.GEOM_BOX,rgbaColor=[1,1,1,1], halfExtents=[0.5,0.5,0.5],specularColor=[0.4,.4,0], visualFramePosition=shift, meshScale=[1,1,1], vertices=vertices, indices=indices)
#visualShapeId = p.createVisualShape(shapeType=p.GEOM_MESH,rgbaColor=[1,1,1,1], specularColor=[0.4,.4,0], visualFramePosition=shift, meshScale=meshScale, fileName="duck.obj") #visualShapeId = p.createVisualShape(shapeType=p.GEOM_MESH,rgbaColor=[1,1,1,1], specularColor=[0.4,.4,0], visualFramePosition=shift, meshScale=meshScale, fileName="duck.obj")

View File

@@ -3,6 +3,7 @@ import time
import math import math
def getRayFromTo(mouseX,mouseY): def getRayFromTo(mouseX,mouseY):
width, height, viewMat, projMat, cameraUp, camForward, horizon,vertical, _,_,dist, camTarget = p.getDebugVisualizerCamera() width, height, viewMat, projMat, cameraUp, camForward, horizon,vertical, _,_,dist, camTarget = p.getDebugVisualizerCamera()
camPos = [camTarget[0] - dist*camForward[0],camTarget[1] - dist*camForward[1],camTarget[2] - dist*camForward[2]] camPos = [camTarget[0] - dist*camForward[0],camTarget[1] - dist*camForward[1],camTarget[2] - dist*camForward[2]]
farPlane = 10000 farPlane = 10000
@@ -15,9 +16,9 @@ def getRayFromTo(mouseX,mouseY):
dHor = [horizon[0] * oneOverWidth,horizon[1] * oneOverWidth,horizon[2] * oneOverWidth] dHor = [horizon[0] * oneOverWidth,horizon[1] * oneOverWidth,horizon[2] * oneOverWidth]
dVer = [vertical[0] * oneOverHeight,vertical[1] * oneOverHeight,vertical[2] * oneOverHeight] dVer = [vertical[0] * oneOverHeight,vertical[1] * oneOverHeight,vertical[2] * oneOverHeight]
rayToCenter=[rayFrom[0]+rayForward[0],rayFrom[1]+rayForward[1],rayFrom[2]+rayForward[2]] rayToCenter=[rayFrom[0]+rayForward[0],rayFrom[1]+rayForward[1],rayFrom[2]+rayForward[2]]
rayTo = [rayFrom[0]+rayForward[0] - 0.5 * horizon[0] + 0.5 * vertical[0]+float(mouseX)*dHor[0]-float(mouseY)*dVer[0], rayTo = [rayToCenter[0] - 0.5 * horizon[0] + 0.5 * vertical[0]+float(mouseX)*dHor[0]-float(mouseY)*dVer[0],
rayFrom[1]+rayForward[1] - 0.5 * horizon[1] + 0.5 * vertical[1]+float(mouseX)*dHor[1]-float(mouseY)*dVer[1], rayToCenter[1] - 0.5 * horizon[1] + 0.5 * vertical[1]+float(mouseX)*dHor[1]-float(mouseY)*dVer[1],
rayFrom[2]+rayForward[2] - 0.5 * horizon[2] + 0.5 * vertical[2]+float(mouseX)*dHor[2]-float(mouseY)*dVer[2]] rayToCenter[2] - 0.5 * horizon[2] + 0.5 * vertical[2]+float(mouseX)*dHor[2]-float(mouseY)*dVer[2]]
return rayFrom,rayTo return rayFrom,rayTo
cid = p.connect(p.SHARED_MEMORY) cid = p.connect(p.SHARED_MEMORY)
@@ -66,7 +67,6 @@ while (1):
hit = rayInfo[l] hit = rayInfo[l]
objectUid = hit[0] objectUid = hit[0]
if (objectUid>=1): if (objectUid>=1):
#p.removeBody(objectUid)
p.changeVisualShape(objectUid,-1,rgbaColor=colors[currentColor]) p.changeVisualShape(objectUid,-1,rgbaColor=colors[currentColor])
currentColor+=1 currentColor+=1
if (currentColor>=len(colors)): if (currentColor>=len(colors)):