Swap yaw and pitch in camera computation. Add functions to convert view matrix to camera position, and camera position to camera yaw pitch roll.
This commit is contained in:
@@ -1930,6 +1930,86 @@ void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, in
|
||||
command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_SHADOW;
|
||||
}
|
||||
|
||||
void b3ComputeYawPitchRollFromPosition(const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3], int upAxis, float* cameraDistance, float* cameraYaw, float* cameraPitch)
|
||||
{
|
||||
b3Vector3 camPos = b3MakeVector3(cameraPosition[0], cameraPosition[1], cameraPosition[2]);
|
||||
b3Vector3 camTargetPos = b3MakeVector3(cameraTargetPosition[0], cameraTargetPosition[1], cameraTargetPosition[2]);
|
||||
b3Vector3 camUpVector = b3MakeVector3(cameraUp[0], cameraUp[1], cameraUp[2]);
|
||||
camUpVector.normalize();
|
||||
|
||||
*cameraDistance = (camPos - camTargetPos).length();
|
||||
|
||||
b3Vector3 eyePos = camPos - camTargetPos;
|
||||
b3Vector3 eyeInitPos = b3MakeVector3(0, 0, 0);
|
||||
|
||||
int forwardAxis = -1;
|
||||
|
||||
switch (upAxis)
|
||||
{
|
||||
case 1:
|
||||
forwardAxis = 2;
|
||||
break;
|
||||
case 2:
|
||||
forwardAxis = 1;
|
||||
break;
|
||||
default:
|
||||
return;
|
||||
};
|
||||
|
||||
eyeInitPos[forwardAxis] = -(*cameraDistance);
|
||||
eyeInitPos.normalize();
|
||||
eyePos.normalize();
|
||||
|
||||
b3Quaternion rot = b3ShortestArcQuat(eyeInitPos, eyePos);
|
||||
btScalar yawRad;
|
||||
btScalar pitchRad;
|
||||
btScalar rollRad;
|
||||
|
||||
switch (upAxis)
|
||||
{
|
||||
case 1:
|
||||
rot.getEulerZYX(rollRad, yawRad, pitchRad);
|
||||
pitchRad = -pitchRad;
|
||||
break;
|
||||
case 2:
|
||||
rot.getEulerZYX(yawRad, rollRad, pitchRad);
|
||||
break;
|
||||
default:
|
||||
return;
|
||||
};
|
||||
|
||||
*cameraYaw = yawRad/b3Scalar(0.01745329251994329547);
|
||||
*cameraPitch = pitchRad/b3Scalar(0.01745329251994329547);
|
||||
float cameraRoll = rollRad/b3Scalar(0.01745329251994329547);
|
||||
printf("camera roll: %f\n", cameraRoll);
|
||||
}
|
||||
|
||||
void b3ComputePositionFromViewMatrix(const float viewMatrix[16], float cameraPosition[3], float cameraTargetPosition[3], float cameraUp[3])
|
||||
{
|
||||
b3Matrix3x3 r(viewMatrix[0], viewMatrix[4], viewMatrix[8], viewMatrix[1], viewMatrix[5], viewMatrix[9], viewMatrix[2], viewMatrix[6], viewMatrix[10]);
|
||||
b3Vector3 p = b3MakeVector3(viewMatrix[12], viewMatrix[13], viewMatrix[14]);
|
||||
b3Transform t(r,p);
|
||||
b3Transform tinv = t.inverse();
|
||||
b3Matrix3x3 basis = tinv.getBasis();
|
||||
b3Vector3 origin = tinv.getOrigin();
|
||||
printf("basis: %f, %f, %f, %f, %f, %f, %f, %f, %f\n", basis[0][0], basis[0][1], basis[0][2], basis[1][0], basis[1][1], basis[1][2], basis[2][0], basis[2][1], basis[2][2]);
|
||||
printf("origin: %f, %f, %f\n", origin[0], origin[1], origin[2]);
|
||||
b3Vector3 s = b3MakeVector3(basis[0][0], basis[1][0], basis[2][0]);
|
||||
b3Vector3 u = b3MakeVector3(basis[0][1], basis[1][1], basis[2][1]);
|
||||
b3Vector3 f = b3MakeVector3(-basis[0][2], -basis[1][2], -basis[2][2]);
|
||||
b3Vector3 eye = origin;
|
||||
cameraPosition[0] = eye[0];
|
||||
cameraPosition[1] = eye[1];
|
||||
cameraPosition[2] = eye[2];
|
||||
b3Vector3 center = f + eye;
|
||||
cameraTargetPosition[0] = center[0];
|
||||
cameraTargetPosition[1] = center[1];
|
||||
cameraTargetPosition[2] = center[2];
|
||||
cameraUp[0] = u[0];
|
||||
cameraUp[1] = u[1];
|
||||
cameraUp[2] = u[2];
|
||||
}
|
||||
|
||||
void b3ComputeViewMatrixFromPositions(const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3], float viewMatrix[16])
|
||||
{
|
||||
b3Vector3 eye = b3MakeVector3(cameraPosition[0], cameraPosition[1], cameraPosition[2]);
|
||||
@@ -1970,77 +2050,43 @@ void b3ComputeViewMatrixFromYawPitchRoll(const float cameraTargetPosition[3], fl
|
||||
b3Vector3 camPos;
|
||||
b3Vector3 camTargetPos = b3MakeVector3(cameraTargetPosition[0], cameraTargetPosition[1], cameraTargetPosition[2]);
|
||||
b3Vector3 eyePos = b3MakeVector3(0, 0, 0);
|
||||
|
||||
int forwardAxis(-1);
|
||||
|
||||
{
|
||||
|
||||
switch (upAxis)
|
||||
{
|
||||
|
||||
case 1:
|
||||
{
|
||||
|
||||
|
||||
forwardAxis = 0;
|
||||
eyePos[forwardAxis] = -distance;
|
||||
camForward = b3MakeVector3(eyePos[0], eyePos[1], eyePos[2]);
|
||||
if (camForward.length2() < B3_EPSILON)
|
||||
{
|
||||
camForward.setValue(1.f, 0.f, 0.f);
|
||||
}
|
||||
else
|
||||
{
|
||||
camForward.normalize();
|
||||
}
|
||||
b3Scalar rollRad = roll * b3Scalar(0.01745329251994329547);
|
||||
b3Quaternion rollRot(camForward, rollRad);
|
||||
|
||||
camUpVector = b3QuatRotate(rollRot, b3MakeVector3(0, 1, 0));
|
||||
//gLightPos = b3MakeVector3(-50.f,100,30);
|
||||
break;
|
||||
}
|
||||
case 2:
|
||||
{
|
||||
|
||||
|
||||
forwardAxis = 1;
|
||||
eyePos[forwardAxis] = -distance;
|
||||
camForward = b3MakeVector3(eyePos[0], eyePos[1], eyePos[2]);
|
||||
if (camForward.length2() < B3_EPSILON)
|
||||
{
|
||||
camForward.setValue(1.f, 0.f, 0.f);
|
||||
}
|
||||
else
|
||||
{
|
||||
camForward.normalize();
|
||||
}
|
||||
|
||||
b3Scalar rollRad = roll * b3Scalar(0.01745329251994329547);
|
||||
b3Quaternion rollRot(camForward, rollRad);
|
||||
|
||||
camUpVector = b3QuatRotate(rollRot, b3MakeVector3(0, 0, 1));
|
||||
//gLightPos = b3MakeVector3(-50.f,30,100);
|
||||
break;
|
||||
}
|
||||
default:
|
||||
{
|
||||
//b3Assert(0);
|
||||
return;
|
||||
}
|
||||
};
|
||||
}
|
||||
|
||||
|
||||
|
||||
b3Scalar yawRad = yaw * b3Scalar(0.01745329251994329547);// rads per deg
|
||||
b3Scalar pitchRad = pitch * b3Scalar(0.01745329251994329547);// rads per deg
|
||||
|
||||
b3Quaternion pitchRot(camUpVector, pitchRad);
|
||||
|
||||
b3Vector3 right = camUpVector.cross(camForward);
|
||||
b3Quaternion yawRot(right, -yawRad);
|
||||
|
||||
eyePos = b3Matrix3x3(pitchRot) * b3Matrix3x3(yawRot) * eyePos;
|
||||
b3Scalar rollRad = 0.0;
|
||||
b3Quaternion eyeRot;
|
||||
|
||||
int forwardAxis(-1);
|
||||
switch (upAxis)
|
||||
{
|
||||
case 1:
|
||||
forwardAxis = 2;
|
||||
camUpVector = b3MakeVector3(0,1,0);
|
||||
eyeRot.setEulerZYX(rollRad, yawRad, -pitchRad);
|
||||
break;
|
||||
case 2:
|
||||
forwardAxis = 1;
|
||||
camUpVector = b3MakeVector3(0,0,1);
|
||||
eyeRot.setEulerZYX(yawRad, rollRad, pitchRad);
|
||||
break;
|
||||
default:
|
||||
return;
|
||||
};
|
||||
|
||||
eyePos[forwardAxis] = -distance;
|
||||
|
||||
camForward = b3MakeVector3(eyePos[0],eyePos[1],eyePos[2]);
|
||||
if (camForward.length2() < B3_EPSILON)
|
||||
{
|
||||
camForward.setValue(1.f,0.f,0.f);
|
||||
} else
|
||||
{
|
||||
camForward.normalize();
|
||||
}
|
||||
|
||||
eyePos = b3Matrix3x3(eyeRot)*eyePos;
|
||||
camUpVector = b3Matrix3x3(eyeRot)*camUpVector;
|
||||
|
||||
camPos = eyePos;
|
||||
camPos += camTargetPos;
|
||||
|
||||
|
||||
@@ -161,6 +161,8 @@ void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImage
|
||||
///compute a view matrix, helper function for b3RequestCameraImageSetCameraMatrices
|
||||
void b3ComputeViewMatrixFromPositions(const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3], float viewMatrix[16]);
|
||||
void b3ComputeViewMatrixFromYawPitchRoll(const float cameraTargetPosition[3], float distance, float yaw, float pitch, float roll, int upAxis, float viewMatrix[16]);
|
||||
void b3ComputePositionFromViewMatrix(const float viewMatrix[16], float cameraPosition[3], float cameraTargetPosition[3], float cameraUp[3]);
|
||||
void b3ComputeYawPitchRollFromPosition(const float cameraPosition[3], const float cameraTargetPosition[3], const float cameraUp[3], int upAxis, float* cameraDistance, float* cameraYaw, float* cameraPitch);
|
||||
|
||||
///compute a projection matrix, helper function for b3RequestCameraImageSetCameraMatrices
|
||||
void b3ComputeProjectionMatrix(float left, float right, float bottom, float top, float nearVal, float farVal, float projectionMatrix[16]);
|
||||
|
||||
@@ -93,10 +93,10 @@ protected:
|
||||
virtual void resetCamera()
|
||||
{
|
||||
float dist = 3.45;
|
||||
float pitch = 287;
|
||||
float yaw = 16.2;
|
||||
float pitch = -16.2;
|
||||
float yaw = 287;
|
||||
float targetPos[3]={2.05,0.02,0.53};//-3,2.8,-2.5};
|
||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
||||
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||
|
||||
}
|
||||
|
||||
@@ -273,6 +273,30 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
||||
///request an image from a simulated camera, using a software renderer.
|
||||
|
||||
b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle);
|
||||
|
||||
float cameraPos[3] = {1.0, 1.0, 1.0};
|
||||
float cameraTarget[3] = {2.0, 1.0, 1.0};
|
||||
float cameraUp[3] = {0.0, 0.0, 1.0};
|
||||
float viewMat[16];
|
||||
b3ComputeViewMatrixFromPositions(cameraPos, cameraTarget, cameraUp, viewMat);
|
||||
printf("viewMat: %f, %f, %f, %f, %f, %f, %f, %f, %f, %f, %f, %f, %f, %f, %f, %f\n", viewMat[0], viewMat[1], viewMat[2], viewMat[3], viewMat[4], viewMat[5], viewMat[6], viewMat[7], viewMat[8], viewMat[9], viewMat[10], viewMat[11], viewMat[12], viewMat[13], viewMat[14], viewMat[15]);
|
||||
float cameraPos2[3];
|
||||
float cameraTarget2[3];
|
||||
float cameraUp2[3];
|
||||
b3ComputePositionFromViewMatrix(viewMat, cameraPos2, cameraTarget2, cameraUp2);
|
||||
printf("cameraPos2: %f, %f, %f\n", cameraPos2[0], cameraPos2[1], cameraPos2[2]);
|
||||
printf("cameraTarget2: %f, %f, %f\n", cameraTarget2[0], cameraTarget2[1], cameraTarget2[2]);
|
||||
printf("cameraUp2: %f, %f, %f\n", cameraUp2[0], cameraUp2[1], cameraUp2[2]);
|
||||
|
||||
float cameraDistance;
|
||||
float cameraYaw;
|
||||
float cameraPitch;
|
||||
b3ComputeYawPitchRollFromPosition(cameraPos2, cameraTarget2, cameraUp2, 2, &cameraDistance, &cameraYaw, &cameraPitch);
|
||||
printf("camera distance: %f\n", cameraDistance);
|
||||
printf("camera yaw: %f\n", cameraYaw);
|
||||
printf("camera pitch: %f\n", cameraPitch);
|
||||
|
||||
b3ComputeViewMatrixFromYawPitchRoll(cameraTarget2, 1.0, -90.0, 0.0, 0.0, 2, viewMat);
|
||||
//b3RequestCameraImageSelectRenderer(commandHandle,ER_BULLET_HARDWARE_OPENGL);
|
||||
|
||||
float viewMatrix[16];
|
||||
|
||||
@@ -4517,8 +4517,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
if (clientCmd.m_updateFlags&COV_SET_CAMERA_VIEW_MATRIX)
|
||||
{
|
||||
m_data->m_guiHelper->resetCamera( clientCmd.m_configureOpenGLVisualizerArguments.m_cameraDistance,
|
||||
clientCmd.m_configureOpenGLVisualizerArguments.m_cameraPitch,
|
||||
clientCmd.m_configureOpenGLVisualizerArguments.m_cameraYaw,
|
||||
clientCmd.m_configureOpenGLVisualizerArguments.m_cameraPitch,
|
||||
clientCmd.m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[0],
|
||||
clientCmd.m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[1],
|
||||
clientCmd.m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[2]);
|
||||
|
||||
@@ -1016,9 +1016,9 @@ public:
|
||||
{
|
||||
m_childGuiHelper->setUpAxis(axis);
|
||||
}
|
||||
virtual void resetCamera(float camDist, float pitch, float yaw, float camPosX,float camPosY, float camPosZ)
|
||||
virtual void resetCamera(float camDist, float yaw, float pitch, float camPosX,float camPosY, float camPosZ)
|
||||
{
|
||||
m_childGuiHelper->resetCamera(camDist,pitch,yaw,camPosX,camPosY,camPosZ);
|
||||
m_childGuiHelper->resetCamera(camDist,yaw,pitch,camPosX,camPosY,camPosZ);
|
||||
}
|
||||
|
||||
virtual bool getCameraInfo(int* width, int* height, float viewMatrix[16], float projectionMatrix[16], float camUp[3], float camForward[3],float hor[3], float vert[3] ) const
|
||||
@@ -1269,10 +1269,10 @@ public:
|
||||
virtual void resetCamera()
|
||||
{
|
||||
float dist = 5;
|
||||
float pitch = 50;
|
||||
float yaw = 35;
|
||||
float pitch = -35;
|
||||
float yaw = 50;
|
||||
float targetPos[3]={0,0,0};//-3,2.8,-2.5};
|
||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
||||
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||
}
|
||||
|
||||
virtual bool wantsTermination();
|
||||
|
||||
@@ -115,11 +115,11 @@ TinyRendererVisualShapeConverter::TinyRendererVisualShapeConverter()
|
||||
m_data = new TinyRendererVisualShapeConverterInternalData();
|
||||
|
||||
float dist = 1.5;
|
||||
float pitch = -80;
|
||||
float yaw = 10;
|
||||
float pitch = -10;
|
||||
float yaw = -80;
|
||||
float targetPos[3]={0,0,0};
|
||||
m_data->m_camera.setCameraUpAxis(m_data->m_upAxis);
|
||||
resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
||||
resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||
|
||||
|
||||
}
|
||||
@@ -678,7 +678,7 @@ void TinyRendererVisualShapeConverter::setUpAxis(int axis)
|
||||
m_data->m_camera.setCameraUpAxis(axis);
|
||||
m_data->m_camera.update();
|
||||
}
|
||||
void TinyRendererVisualShapeConverter::resetCamera(float camDist, float pitch, float yaw, float camPosX,float camPosY, float camPosZ)
|
||||
void TinyRendererVisualShapeConverter::resetCamera(float camDist, float yaw, float pitch, float camPosX,float camPosY, float camPosZ)
|
||||
{
|
||||
m_data->m_camera.setCameraDistance(camDist);
|
||||
m_data->m_camera.setCameraPitch(pitch);
|
||||
|
||||
@@ -26,7 +26,7 @@ struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter
|
||||
|
||||
void setUpAxis(int axis);
|
||||
|
||||
void resetCamera(float camDist, float pitch, float yaw, float camPosX,float camPosY, float camPosZ);
|
||||
void resetCamera(float camDist, float yaw, float pitch, float camPosX,float camPosY, float camPosZ);
|
||||
|
||||
void clearBuffers(struct TGAColor& clearColor);
|
||||
|
||||
|
||||
Reference in New Issue
Block a user