mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-13 13:20:07 +00:00
Remove debug code.
This commit is contained in:
parent
3506603d60
commit
e2a9fc33dc
@ -58,9 +58,9 @@ public:
|
||||
|
||||
void resetCamera()
|
||||
{
|
||||
float dist = 1;
|
||||
float pitch = 70;
|
||||
float yaw = 10;
|
||||
float dist = 35;
|
||||
float pitch = -14;
|
||||
float yaw = 0;
|
||||
float targetPos[3]={0,0,0};
|
||||
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||
}
|
||||
|
@ -1930,65 +1930,6 @@ 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();
|
||||
|
||||
eyeInitPos[0] = 0.0;
|
||||
eyeInitPos[1] = -1.0;
|
||||
eyeInitPos[2] = 0.0;
|
||||
b3Quaternion rot = b3ShortestArcQuat(eyeInitPos, eyePos);
|
||||
//rot[0] = 0.571393847;
|
||||
//rot[1] = 0.0499904789;
|
||||
//rot[2] = 0.0713938028;
|
||||
//rot[3] = 0.816034972;
|
||||
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);
|
||||
}
|
||||
|
||||
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]);
|
||||
@ -2013,14 +1954,6 @@ void b3ComputePositionFromViewMatrix(const float viewMatrix[16], float cameraPos
|
||||
cameraUp[2] = u[2];
|
||||
}
|
||||
|
||||
void b3ComputeYawPitchRollFromViewMatrix(const float viewMatrix[16], int upAxis, float& cameraDistance, float& cameraYaw, float& cameraPitch, float cameraTargetPosition[3])
|
||||
{
|
||||
float cameraPosition[3];
|
||||
float cameraUp[3];
|
||||
b3ComputePositionFromViewMatrix(viewMatrix, cameraPosition, cameraTargetPosition, cameraUp);
|
||||
b3ComputeYawPitchRollFromPosition(cameraPosition, cameraTargetPosition, cameraUp, upAxis, cameraDistance, cameraYaw, cameraPitch);
|
||||
}
|
||||
|
||||
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]);
|
||||
@ -2095,9 +2028,7 @@ void b3ComputeViewMatrixFromYawPitchRoll(const float cameraTargetPosition[3], fl
|
||||
camForward.normalize();
|
||||
}
|
||||
|
||||
eyePos[3] = 1.0;
|
||||
//eyePos = b3Matrix3x3(eyeRot)*eyePos;
|
||||
eyePos = b3QuatRotate(eyeRot, eyePos);
|
||||
eyePos = b3Matrix3x3(eyeRot)*eyePos;
|
||||
camUpVector = b3Matrix3x3(eyeRot)*camUpVector;
|
||||
|
||||
camPos = eyePos;
|
||||
|
@ -162,8 +162,6 @@ void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImage
|
||||
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);
|
||||
void b3ComputeYawPitchRollFromViewMatrix(const float viewMatrix[16], int upAxis, float& cameraDistance, float& cameraYaw, float& cameraPitch, float cameraTargetPosition[3]);
|
||||
|
||||
///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]);
|
||||
|
@ -276,22 +276,6 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
||||
//b3RequestCameraImageSelectRenderer(commandHandle,ER_BULLET_HARDWARE_OPENGL);
|
||||
|
||||
float viewMatrix[16];
|
||||
|
||||
float cameraTargetPosition[3] = {0.0, 0.0, 0.0};
|
||||
float distance = 1.0;
|
||||
float yaw = 10.0;
|
||||
float pitch = 70.0;
|
||||
float roll = 0.0;
|
||||
int upAxis = 2;
|
||||
float cameraDistance;
|
||||
float cameraYaw;
|
||||
float cameraPitch;
|
||||
float cameraTargetPositionNew[3];
|
||||
b3ComputeViewMatrixFromYawPitchRoll(cameraTargetPosition, distance, yaw, pitch, roll, upAxis, viewMatrix);
|
||||
b3ComputeYawPitchRollFromViewMatrix(viewMatrix, upAxis, cameraDistance, cameraYaw, cameraPitch, cameraTargetPositionNew);
|
||||
b3ComputeViewMatrixFromYawPitchRoll(cameraTargetPositionNew, cameraDistance, cameraYaw, cameraPitch, 0.0, upAxis, viewMatrix);
|
||||
|
||||
|
||||
float projectionMatrix[16];
|
||||
m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraProjectionMatrix(projectionMatrix);
|
||||
m_guiHelper->getRenderInterface()->getActiveCamera()->getCameraViewMatrix(viewMatrix);
|
||||
|
@ -52,10 +52,10 @@ def readLogFile(filename, verbose = True):
|
||||
#clid = p.connect(p.SHARED_MEMORY)
|
||||
p.connect(p.GUI)
|
||||
p.loadURDF("plane.urdf",[0,0,-0.3])
|
||||
p.loadURDF("kuka_iiwa/model.urdf",[0,0,10])
|
||||
p.loadURDF("cube.urdf",[2,2,50])
|
||||
p.loadURDF("cube.urdf",[-2,-2,50])
|
||||
p.loadURDF("cube.urdf",[2,-2,50])
|
||||
p.loadURDF("kuka_iiwa/model.urdf",[0,0,1])
|
||||
p.loadURDF("cube.urdf",[2,2,5])
|
||||
p.loadURDF("cube.urdf",[-2,-2,5])
|
||||
p.loadURDF("cube.urdf",[2,-2,5])
|
||||
|
||||
log = readLogFile("LOG0001.txt")
|
||||
|
||||
|
@ -887,16 +887,6 @@ b3QuatRotate(const b3Quaternion& rotation, const b3Vector3& v)
|
||||
B3_FORCE_INLINE b3Quaternion
|
||||
b3ShortestArcQuat(const b3Vector3& v0, const b3Vector3& v1) // Game Programming Gems 2.10. make sure v0,v1 are normalized
|
||||
{
|
||||
/*
|
||||
b3Quaternion q;
|
||||
b3Vector3 a = v0.cross(v1);
|
||||
q[0] = a[0];
|
||||
q[1] = a[1];
|
||||
q[2] = a[2];
|
||||
q[3] = b3Sqrt((v0.length()*v0.length()) * (v1.length()*v1.length())) + v0.dot(v1);
|
||||
return q;
|
||||
*/
|
||||
|
||||
b3Vector3 c = v0.cross(v1);
|
||||
b3Scalar d = v0.dot(v1);
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user