Merge pull request #1167 from YunfeiBai/master
Swap yaw and pitch, and use setEulerZYX in camera computation. Add camera yaw, pitch, distance, and target to getDebugVisualizerCamera. Add rgba color reset for TinyRender.
This commit is contained in:
Binary file not shown.
@@ -39,10 +39,10 @@ struct BasicExample : public CommonRigidBodyBase
|
|||||||
void resetCamera()
|
void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 4;
|
float dist = 4;
|
||||||
float pitch = 52;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 52;
|
||||||
float targetPos[3]={0,0,0};
|
float targetPos[3]={0,0,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -109,10 +109,10 @@ class BenchmarkDemo : public CommonRigidBodyMTBase
|
|||||||
void resetCamera()
|
void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 120;
|
float dist = 120;
|
||||||
float pitch = 52;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 52;
|
||||||
float targetPos[3]={0,10.46,0};
|
float targetPos[3]={0,10.46,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -371,8 +371,8 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 10.5;
|
float dist = 10.5;
|
||||||
float pitch = 136;
|
float pitch = -32;
|
||||||
float yaw = 32;
|
float yaw = 136;
|
||||||
float targetPos[3]={0,0,0};
|
float targetPos[3]={0,0,0};
|
||||||
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -57,9 +57,9 @@ struct GUIHelperInterface
|
|||||||
|
|
||||||
virtual void setUpAxis(int axis)=0;
|
virtual void setUpAxis(int axis)=0;
|
||||||
|
|
||||||
virtual void resetCamera(float camDist, float pitch, float yaw, float camPosX,float camPosY, float camPosZ)=0;
|
virtual void resetCamera(float camDist, float yaw, float pitch, float camPosX,float camPosY, float camPosZ)=0;
|
||||||
|
|
||||||
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
|
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], float* yaw, float* pitch, float* camDist, float camTarget[3]) const
|
||||||
{
|
{
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
@@ -153,7 +153,7 @@ struct DummyGUIHelper : public GUIHelperInterface
|
|||||||
virtual void setUpAxis(int axis)
|
virtual void setUpAxis(int 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)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -201,10 +201,10 @@ struct CommonGraphicsApp
|
|||||||
{
|
{
|
||||||
// if (b3Fabs(xDelta)>b3Fabs(yDelta))
|
// if (b3Fabs(xDelta)>b3Fabs(yDelta))
|
||||||
// {
|
// {
|
||||||
pitch -= xDelta*m_mouseMoveMultiplier;
|
pitch -= yDelta*m_mouseMoveMultiplier;
|
||||||
// } else
|
// } else
|
||||||
// {
|
// {
|
||||||
yaw += yDelta*m_mouseMoveMultiplier;
|
yaw -= xDelta*m_mouseMoveMultiplier;
|
||||||
// }
|
// }
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -50,10 +50,10 @@ class AllConstraintDemo : public CommonRigidBodyBase
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 27;
|
float dist = 27;
|
||||||
float pitch = 720;
|
float pitch = -30;
|
||||||
float yaw = 30;
|
float yaw = 720;
|
||||||
float targetPos[3]={2,0,-10};
|
float targetPos[3]={2,0,-10};
|
||||||
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 keyboardCallback(int key, int state);
|
virtual bool keyboardCallback(int key, int state);
|
||||||
|
|||||||
@@ -18,10 +18,10 @@ struct ConstraintPhysicsSetup : public CommonRigidBodyBase
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 7;
|
float dist = 7;
|
||||||
float pitch = 721;
|
float pitch = -44;
|
||||||
float yaw = 44;
|
float yaw = 721;
|
||||||
float targetPos[3]={8,1,-11};
|
float targetPos[3]={8,1,-11};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -55,10 +55,10 @@ struct Dof6Spring2Setup : public CommonRigidBodyBase
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 5;
|
float dist = 5;
|
||||||
float pitch = 722;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 722;
|
||||||
float targetPos[3]={4,2,-11};
|
float targetPos[3]={4,2,-11};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -24,10 +24,10 @@ struct TestHingeTorque : public CommonRigidBodyBase
|
|||||||
{
|
{
|
||||||
|
|
||||||
float dist = 5;
|
float dist = 5;
|
||||||
float pitch = 270;
|
float pitch = -21;
|
||||||
float yaw = 21;
|
float yaw = 270;
|
||||||
float targetPos[3]={-1.34,3.4,-0.44};
|
float targetPos[3]={-1.34,3.4,-0.44};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -63,10 +63,10 @@ public:
|
|||||||
void resetCamera()
|
void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 11;
|
float dist = 11;
|
||||||
float pitch = 52;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 52;
|
||||||
float targetPos[3]={0,0.46,0};
|
float targetPos[3]={0,0.46,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -145,10 +145,10 @@ public:
|
|||||||
void resetCamera()
|
void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 11;
|
float dist = 11;
|
||||||
float pitch = 52;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 52;
|
||||||
float targetPos[3]={0,0.46,0};
|
float targetPos[3]={0,0.46,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Evaluation
|
// Evaluation
|
||||||
|
|||||||
@@ -979,7 +979,7 @@ void OpenGLGuiHelper::setVisualizerFlag(int flag, int enable)
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void OpenGLGuiHelper::resetCamera(float camDist, float pitch, float yaw, float camPosX,float camPosY, float camPosZ)
|
void OpenGLGuiHelper::resetCamera(float camDist, float yaw, float pitch, float camPosX,float camPosY, float camPosZ)
|
||||||
{
|
{
|
||||||
if (getRenderInterface() && getRenderInterface()->getActiveCamera())
|
if (getRenderInterface() && getRenderInterface()->getActiveCamera())
|
||||||
{
|
{
|
||||||
@@ -990,7 +990,7 @@ void OpenGLGuiHelper::resetCamera(float camDist, float pitch, float yaw, float c
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
bool OpenGLGuiHelper::getCameraInfo(int* width, int* height, float viewMatrix[16], float projectionMatrix[16], float camUp[3], float camForward[3],float hor[3], float vert[3] ) const
|
bool OpenGLGuiHelper::getCameraInfo(int* width, int* height, float viewMatrix[16], float projectionMatrix[16], float camUp[3], float camForward[3],float hor[3], float vert[3], float* yaw, float* pitch, float* camDist, float cameraTarget[3]) const
|
||||||
{
|
{
|
||||||
if (getRenderInterface() && getRenderInterface()->getActiveCamera())
|
if (getRenderInterface() && getRenderInterface()->getActiveCamera())
|
||||||
{
|
{
|
||||||
@@ -1036,6 +1036,13 @@ bool OpenGLGuiHelper::getCameraInfo(int* width, int* height, float viewMatrix[16
|
|||||||
vert[0] = vertical[0];
|
vert[0] = vertical[0];
|
||||||
vert[1] = vertical[1];
|
vert[1] = vertical[1];
|
||||||
vert[2] = vertical[2];
|
vert[2] = vertical[2];
|
||||||
|
|
||||||
|
*yaw = getRenderInterface()->getActiveCamera()->getCameraYaw();
|
||||||
|
*pitch = getRenderInterface()->getActiveCamera()->getCameraPitch();
|
||||||
|
*camDist = getRenderInterface()->getActiveCamera()->getCameraDistance();
|
||||||
|
cameraTarget[0] = camTarget[0];
|
||||||
|
cameraTarget[1] = camTarget[1];
|
||||||
|
cameraTarget[2] = camTarget[2];
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
return false;
|
return false;
|
||||||
|
|||||||
@@ -47,8 +47,8 @@ struct OpenGLGuiHelper : public GUIHelperInterface
|
|||||||
virtual void setUpAxis(int axis);
|
virtual void setUpAxis(int 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);
|
||||||
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;
|
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], float* yaw, float* pitch, float* camDist, float camTarget[3]) const;
|
||||||
|
|
||||||
virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16],
|
virtual void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16],
|
||||||
unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels,
|
unsigned char* pixelsRGBA, int rgbaBufferSizeInPixels,
|
||||||
|
|||||||
@@ -35,10 +35,10 @@ struct BridgeExample : public CommonRigidBodyBase
|
|||||||
void resetCamera()
|
void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 41;
|
float dist = 41;
|
||||||
float pitch = 52;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 52;
|
||||||
float targetPos[3]={0,0.46,0};
|
float targetPos[3]={0,0.46,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -35,10 +35,10 @@ struct ChainExample : public CommonRigidBodyBase
|
|||||||
void resetCamera()
|
void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 41;
|
float dist = 41;
|
||||||
float pitch = 52;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 52;
|
||||||
float targetPos[3]={0,0.46,0};
|
float targetPos[3]={0,0.46,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -62,10 +62,10 @@ struct InclinedPlaneExample : public CommonRigidBodyBase
|
|||||||
void resetCamera()
|
void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 41;
|
float dist = 41;
|
||||||
float pitch = 52;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 52;
|
||||||
float targetPos[3]={0,0.46,0};
|
float targetPos[3]={0,0.46,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -58,10 +58,10 @@ struct MultiPendulumExample: public CommonRigidBodyBase {
|
|||||||
virtual void applyPendulumForce(btScalar pendulumForce);
|
virtual void applyPendulumForce(btScalar pendulumForce);
|
||||||
void resetCamera() {
|
void resetCamera() {
|
||||||
float dist = 41;
|
float dist = 41;
|
||||||
float pitch = 52;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 52;
|
||||||
float targetPos[3] = { 0, 0.46, 0 };
|
float targetPos[3] = { 0, 0.46, 0 };
|
||||||
m_guiHelper->resetCamera(dist, pitch, yaw, targetPos[0], targetPos[1],
|
m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1],
|
||||||
targetPos[2]);
|
targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -35,10 +35,10 @@ struct MultipleBoxesExample : public CommonRigidBodyBase
|
|||||||
void resetCamera()
|
void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 41;
|
float dist = 41;
|
||||||
float pitch = 52;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 52;
|
||||||
float targetPos[3]={0,0.46,0};
|
float targetPos[3]={0,0.46,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -58,10 +58,10 @@ struct NewtonsCradleExample: public CommonRigidBodyBase {
|
|||||||
virtual void applyPendulumForce(btScalar pendulumForce);
|
virtual void applyPendulumForce(btScalar pendulumForce);
|
||||||
void resetCamera() {
|
void resetCamera() {
|
||||||
float dist = 41;
|
float dist = 41;
|
||||||
float pitch = 52;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 52;
|
||||||
float targetPos[3] = { 0, 0.46, 0 };
|
float targetPos[3] = { 0, 0.46, 0 };
|
||||||
m_guiHelper->resetCamera(dist, pitch, yaw, targetPos[0], targetPos[1],
|
m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1],
|
||||||
targetPos[2]);
|
targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -90,10 +90,10 @@ struct NewtonsRopeCradleExample : public CommonRigidBodyBase {
|
|||||||
void resetCamera()
|
void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 41;
|
float dist = 41;
|
||||||
float pitch = 52;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 52;
|
||||||
float targetPos[3]={0,0.46,0};
|
float targetPos[3]={0,0.46,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
std::vector<btSliderConstraint*> constraints;
|
std::vector<btSliderConstraint*> constraints;
|
||||||
|
|||||||
@@ -43,10 +43,10 @@ struct RigidBodyFromObjExample : public CommonRigidBodyBase
|
|||||||
void resetCamera()
|
void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 11;
|
float dist = 11;
|
||||||
float pitch = 52;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 52;
|
||||||
float targetPos[3]={0,0.46,0};
|
float targetPos[3]={0,0.46,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -35,10 +35,10 @@ struct SimpleBoxExample : public CommonRigidBodyBase
|
|||||||
void resetCamera()
|
void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 41;
|
float dist = 41;
|
||||||
float pitch = 52;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 52;
|
||||||
float targetPos[3]={0,0.46,0};
|
float targetPos[3]={0,0.46,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -61,10 +61,10 @@ struct SimpleClothExample : public CommonRigidBodyBase
|
|||||||
void resetCamera()
|
void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 41;
|
float dist = 41;
|
||||||
float pitch = 52;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 52;
|
||||||
float targetPos[3]={0,0.46,0};
|
float targetPos[3]={0,0.46,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
void createSoftBody(const btScalar size, const int num_x, const int num_z, const int fixed=1+2);
|
void createSoftBody(const btScalar size, const int num_x, const int num_z, const int fixed=1+2);
|
||||||
|
|||||||
@@ -35,10 +35,10 @@ struct SimpleJointExample : public CommonRigidBodyBase
|
|||||||
void resetCamera()
|
void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 41;
|
float dist = 41;
|
||||||
float pitch = 52;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 52;
|
||||||
float targetPos[3]={0,0.46,0};
|
float targetPos[3]={0,0.46,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -144,10 +144,10 @@ class ForkLiftDemo : public CommonExampleInterface
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 8;
|
float dist = 8;
|
||||||
float pitch = -45;
|
float pitch = -32;
|
||||||
float yaw = 32;
|
float yaw = -45;
|
||||||
float targetPos[3]={-0.33,-0.72,4.5};
|
float targetPos[3]={-0.33,-0.72,4.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]);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*static DemoApplication* Create()
|
/*static DemoApplication* Create()
|
||||||
|
|||||||
@@ -90,10 +90,10 @@ public:
|
|||||||
void resetCamera()
|
void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 41;
|
float dist = 41;
|
||||||
float pitch = 52;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 52;
|
||||||
float targetPos[3]={0,0.46,0};
|
float targetPos[3]={0,0.46,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -21,10 +21,10 @@ struct GyroscopicSetup : public CommonRigidBodyBase
|
|||||||
void resetCamera()
|
void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 20;
|
float dist = 20;
|
||||||
float pitch = 180;
|
float pitch = -16;
|
||||||
float yaw = 16;
|
float yaw = 180;
|
||||||
float targetPos[3]={-2.4,0.4,-0.24};
|
float targetPos[3]={-2.4,0.4,-0.24};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -67,10 +67,10 @@ class BspDemo : public CommonRigidBodyBase
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 43;
|
float dist = 43;
|
||||||
float pitch = -175;
|
float pitch = -12;
|
||||||
float yaw = 12;
|
float yaw = -175;
|
||||||
float targetPos[3]={4,-25,-6};
|
float targetPos[3]={4,-25,-6};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -22,10 +22,10 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 9.5;
|
float dist = 9.5;
|
||||||
float pitch = -2.8;
|
float pitch = -20;
|
||||||
float yaw = 20;
|
float yaw = -2.8;
|
||||||
float targetPos[3]={-0.2,-1.4,3.5};
|
float targetPos[3]={-0.2,-1.4,3.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]);
|
||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -41,10 +41,10 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 16;
|
float dist = 16;
|
||||||
float pitch = -140;
|
float pitch = -28;
|
||||||
float yaw = 28;
|
float yaw = -140;
|
||||||
float targetPos[3]={-4,-3,-3};
|
float targetPos[3]={-4,-3,-3};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -38,10 +38,10 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 3.5;
|
float dist = 3.5;
|
||||||
float pitch = -136;
|
float pitch = -28;
|
||||||
float yaw = 28;
|
float yaw = -136;
|
||||||
float targetPos[3]={0.47,0,-0.64};
|
float targetPos[3]={0.47,0,-0.64};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -29,10 +29,10 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 18;
|
float dist = 18;
|
||||||
float pitch = 120;
|
float pitch = -46;
|
||||||
float yaw = 46;
|
float yaw = 120;
|
||||||
float targetPos[3]={-2,-2,-2};
|
float targetPos[3]={-2,-2,-2};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -50,10 +50,10 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 3.5;
|
float dist = 3.5;
|
||||||
float pitch = -136;
|
float pitch = -28;
|
||||||
float yaw = 28;
|
float yaw = -136;
|
||||||
float targetPos[3]={0.47,0,-0.64};
|
float targetPos[3]={0.47,0,-0.64};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -25,10 +25,10 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 3.5;
|
float dist = 3.5;
|
||||||
float pitch = -136;
|
float pitch = -28;
|
||||||
float yaw = 28;
|
float yaw = -136;
|
||||||
float targetPos[3]={0.47,0,-0.64};
|
float targetPos[3]={0.47,0,-0.64};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -50,10 +50,10 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 3.5;
|
float dist = 3.5;
|
||||||
float pitch = -136;
|
float pitch = -28;
|
||||||
float yaw = 28;
|
float yaw = -136;
|
||||||
float targetPos[3]={0.47,0,-0.64};
|
float targetPos[3]={0.47,0,-0.64};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -87,10 +87,10 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 1.5;
|
float dist = 1.5;
|
||||||
float pitch = -80;
|
float pitch = -10;
|
||||||
float yaw = 10;
|
float yaw = -80;
|
||||||
float targetPos[3]={0,0,0};
|
float targetPos[3]={0,0,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -313,8 +313,8 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 1.3;
|
float dist = 1.3;
|
||||||
float pitch = 120;
|
float pitch = -13;
|
||||||
float yaw = 13;
|
float yaw = 120;
|
||||||
float targetPos[3]={-0.35,0.14,0.25};
|
float targetPos[3]={-0.35,0.14,0.25};
|
||||||
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -30,10 +30,10 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 5;
|
float dist = 5;
|
||||||
float pitch = 270;
|
float pitch = -21;
|
||||||
float yaw = 21;
|
float yaw = 270;
|
||||||
float targetPos[3]={-1.34,1.4,3.44};
|
float targetPos[3]={-1.34,1.4,3.44};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -26,10 +26,10 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 5;
|
float dist = 5;
|
||||||
float pitch = 270;
|
float pitch = -21;
|
||||||
float yaw = 21;
|
float yaw = 270;
|
||||||
float targetPos[3]={-1.34,3.4,-0.44};
|
float targetPos[3]={-1.34,3.4,-0.44};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -27,10 +27,10 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 5;
|
float dist = 5;
|
||||||
float pitch = 270;
|
float pitch = -21;
|
||||||
float yaw = 21;
|
float yaw = 270;
|
||||||
float targetPos[3]={0,0,0};
|
float targetPos[3]={0,0,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -34,10 +34,10 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 1;
|
float dist = 1;
|
||||||
float pitch = 50;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 50;
|
||||||
float targetPos[3]={-3,2.8,-2.5};
|
float targetPos[3]={-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]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -40,10 +40,10 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 5;
|
float dist = 5;
|
||||||
float pitch = 270;
|
float pitch = -21;
|
||||||
float yaw = 21;
|
float yaw = 270;
|
||||||
float targetPos[3]={0,0,0};
|
float targetPos[3]={0,0,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -27,10 +27,10 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 5;
|
float dist = 5;
|
||||||
float pitch = 270;
|
float pitch = -21;
|
||||||
float yaw = 21;
|
float yaw = 270;
|
||||||
float targetPos[3]={-1.34,3.4,-0.44};
|
float targetPos[3]={-1.34,3.4,-0.44};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -97,8 +97,8 @@ public:
|
|||||||
virtual void resetCamera() BT_OVERRIDE
|
virtual void resetCamera() BT_OVERRIDE
|
||||||
{
|
{
|
||||||
m_guiHelper->resetCamera( m_cameraDist,
|
m_guiHelper->resetCamera( m_cameraDist,
|
||||||
m_cameraPitch,
|
|
||||||
m_cameraYaw,
|
m_cameraYaw,
|
||||||
|
m_cameraPitch,
|
||||||
m_cameraTargetPos.x(),
|
m_cameraTargetPos.x(),
|
||||||
m_cameraTargetPos.y(),
|
m_cameraTargetPos.y(),
|
||||||
m_cameraTargetPos.z()
|
m_cameraTargetPos.z()
|
||||||
@@ -114,8 +114,8 @@ MultiThreadedDemo::MultiThreadedDemo(struct GUIHelperInterface* helper)
|
|||||||
m_groundBody = NULL;
|
m_groundBody = NULL;
|
||||||
m_groundMovePhase = 0.0f;
|
m_groundMovePhase = 0.0f;
|
||||||
m_cameraTargetPos = btVector3( 0.0f, 0.0f, 0.0f );
|
m_cameraTargetPos = btVector3( 0.0f, 0.0f, 0.0f );
|
||||||
m_cameraPitch = 90.0f;
|
m_cameraPitch = -30.0f;
|
||||||
m_cameraYaw = 30.0f;
|
m_cameraYaw = 90.0f;
|
||||||
m_cameraDist = 48.0f;
|
m_cameraDist = 48.0f;
|
||||||
helper->setUpAxis( kUpAxis );
|
helper->setUpAxis( kUpAxis );
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -304,8 +304,8 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 10.5;
|
float dist = 10.5;
|
||||||
float pitch = 136;
|
float pitch = -32;
|
||||||
float yaw = 32;
|
float yaw = 136;
|
||||||
float targetPos[3]={0,0,0};
|
float targetPos[3]={0,0,0};
|
||||||
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -71,10 +71,10 @@ public:
|
|||||||
dist = 130;
|
dist = 130;
|
||||||
}
|
}
|
||||||
|
|
||||||
float pitch = 62;
|
float pitch = -33;
|
||||||
float yaw = 33;
|
float yaw = 62;
|
||||||
float targetPos[4]={15.5,12.5,15.5,0};
|
float targetPos[4]={15.5,12.5,15.5,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -150,8 +150,8 @@ void GpuConvexScene::setupScene()
|
|||||||
m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraTargetPosition(camPos[0],camPos[1],camPos[2]);
|
m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraTargetPosition(camPos[0],camPos[1],camPos[2]);
|
||||||
m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraDistance(150);
|
m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraDistance(150);
|
||||||
//m_instancingRenderer->setCameraYaw(85);
|
//m_instancingRenderer->setCameraYaw(85);
|
||||||
m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraYaw(30);
|
m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraYaw(225);
|
||||||
m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraPitch(225);
|
m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraPitch(-30);
|
||||||
|
|
||||||
|
|
||||||
m_guiHelper->getRenderInterface()->updateCamera(1);//>updateCamera();
|
m_guiHelper->getRenderInterface()->updateCamera(1);//>updateCamera();
|
||||||
|
|||||||
@@ -86,10 +86,10 @@ m_window(0)
|
|||||||
void GpuRigidBodyDemo::resetCamera()
|
void GpuRigidBodyDemo::resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 114;
|
float dist = 114;
|
||||||
float pitch = 52;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 52;
|
||||||
float targetPos[3]={0,0,0};
|
float targetPos[3]={0,0,0};
|
||||||
m_data->m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_data->m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
GpuRigidBodyDemo::~GpuRigidBodyDemo()
|
GpuRigidBodyDemo::~GpuRigidBodyDemo()
|
||||||
|
|||||||
@@ -205,6 +205,10 @@ int SimpleCamera::getCameraUpAxis() const
|
|||||||
|
|
||||||
void SimpleCamera::update()
|
void SimpleCamera::update()
|
||||||
{
|
{
|
||||||
|
b3Scalar yawRad = m_data->m_yaw * b3Scalar(0.01745329251994329547);// rads per deg
|
||||||
|
b3Scalar pitchRad = m_data->m_pitch * b3Scalar(0.01745329251994329547);// rads per deg
|
||||||
|
b3Scalar rollRad = 0.0;
|
||||||
|
b3Quaternion eyeRot;
|
||||||
|
|
||||||
int forwardAxis(-1);
|
int forwardAxis(-1);
|
||||||
switch (m_data->m_cameraUpAxis)
|
switch (m_data->m_cameraUpAxis)
|
||||||
@@ -213,11 +217,13 @@ void SimpleCamera::update()
|
|||||||
forwardAxis = 2;
|
forwardAxis = 2;
|
||||||
m_data->m_cameraUp = b3MakeVector3(0,1,0);
|
m_data->m_cameraUp = b3MakeVector3(0,1,0);
|
||||||
//gLightPos = b3MakeVector3(-50.f,100,30);
|
//gLightPos = b3MakeVector3(-50.f,100,30);
|
||||||
|
eyeRot.setEulerZYX(rollRad, yawRad, -pitchRad);
|
||||||
break;
|
break;
|
||||||
case 2:
|
case 2:
|
||||||
forwardAxis = 1;
|
forwardAxis = 1;
|
||||||
m_data->m_cameraUp = b3MakeVector3(0,0,1);
|
m_data->m_cameraUp = b3MakeVector3(0,0,1);
|
||||||
//gLightPos = b3MakeVector3(-50.f,30,100);
|
//gLightPos = b3MakeVector3(-50.f,30,100);
|
||||||
|
eyeRot.setEulerZYX(yawRad, rollRad, pitchRad);
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
{
|
{
|
||||||
@@ -238,19 +244,7 @@ void SimpleCamera::update()
|
|||||||
m_data->m_cameraForward.normalize();
|
m_data->m_cameraForward.normalize();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
eyePos = b3Matrix3x3(eyeRot)*eyePos;
|
||||||
// m_azi=m_azi+0.01;
|
|
||||||
b3Scalar rele = m_data->m_yaw * b3Scalar(0.01745329251994329547);// rads per deg
|
|
||||||
b3Scalar razi = m_data->m_pitch * b3Scalar(0.01745329251994329547);// rads per deg
|
|
||||||
|
|
||||||
|
|
||||||
b3Quaternion rot(m_data->m_cameraUp,razi);
|
|
||||||
|
|
||||||
|
|
||||||
b3Vector3 right = m_data->m_cameraUp.cross(m_data->m_cameraForward);
|
|
||||||
b3Quaternion roll(right,-rele);
|
|
||||||
|
|
||||||
eyePos = b3Matrix3x3(rot) * b3Matrix3x3(roll) * eyePos;
|
|
||||||
|
|
||||||
m_data->m_cameraPosition = eyePos;
|
m_data->m_cameraPosition = eyePos;
|
||||||
m_data->m_cameraPosition+= m_data->m_cameraTargetPosition;
|
m_data->m_cameraPosition+= m_data->m_cameraTargetPosition;
|
||||||
|
|||||||
@@ -96,10 +96,10 @@ class Planar2D : public CommonRigidBodyBase
|
|||||||
void resetCamera()
|
void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 9;
|
float dist = 9;
|
||||||
float pitch = 539;
|
float pitch = -11;
|
||||||
float yaw = 11;
|
float yaw = 539;
|
||||||
float targetPos[3]={8.6,10.5,-20.6};
|
float targetPos[3]={8.6,10.5,-20.6};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -55,10 +55,10 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 18;
|
float dist = 18;
|
||||||
float pitch = 129;
|
float pitch = -30;
|
||||||
float yaw = 30;
|
float yaw = 129;
|
||||||
float targetPos[3]={-4.6,-4.7,-5.75};
|
float targetPos[3]={-4.6,-4.7,-5.75};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -143,8 +143,8 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 3.5;
|
float dist = 3.5;
|
||||||
float pitch = 136;
|
float pitch = -32;
|
||||||
float yaw = 32;
|
float yaw = 136;
|
||||||
float targetPos[3]={0,0,0};
|
float targetPos[3]={0,0,0};
|
||||||
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -121,8 +121,8 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 1.15;
|
float dist = 1.15;
|
||||||
float pitch = 396;
|
float pitch = -33.7;
|
||||||
float yaw = 33.7;
|
float yaw = 396;
|
||||||
float targetPos[3]={-0.5,0.7,1.45};
|
float targetPos[3]={-0.5,0.7,1.45};
|
||||||
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -128,8 +128,8 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 13;
|
float dist = 13;
|
||||||
float pitch = 50;
|
float pitch = -13;
|
||||||
float yaw = 13;
|
float yaw = 50;
|
||||||
float targetPos[3]={-1,0,-0.3};
|
float targetPos[3]={-1,0,-0.3};
|
||||||
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -137,10 +137,10 @@ struct TinyRendererSetup : public CommonExampleInterface
|
|||||||
void resetCamera()
|
void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 11;
|
float dist = 11;
|
||||||
float pitch = 52;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 52;
|
||||||
float targetPos[3]={0,0.46,0};
|
float targetPos[3]={0,0.46,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -47,10 +47,10 @@ struct RigidBodySoftContact : public CommonRigidBodyBase
|
|||||||
void resetCamera()
|
void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 3;
|
float dist = 3;
|
||||||
float pitch = 52;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 52;
|
||||||
float targetPos[3]={0,0.46,0};
|
float targetPos[3]={0,0.46,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -496,8 +496,8 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 1.5;
|
float dist = 1.5;
|
||||||
float pitch = 18;
|
float pitch = -10;
|
||||||
float yaw = 10;
|
float yaw = 18;
|
||||||
float targetPos[3]={-0.2,0.8,0.3};
|
float targetPos[3]={-0.2,0.8,0.3};
|
||||||
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -283,8 +283,8 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 3;
|
float dist = 3;
|
||||||
float pitch = 0;
|
float pitch = -30;
|
||||||
float yaw = 30;
|
float yaw = 0;
|
||||||
float targetPos[3]={-0.2,0.8,0.3};
|
float targetPos[3]={-0.2,0.8,0.3};
|
||||||
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -188,8 +188,8 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 3;
|
float dist = 3;
|
||||||
float pitch = -75;
|
float pitch = -30;
|
||||||
float yaw = 30;
|
float yaw = -75;
|
||||||
float targetPos[3]={-0.2,0.8,0.3};
|
float targetPos[3]={-0.2,0.8,0.3};
|
||||||
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -59,10 +59,10 @@ public:
|
|||||||
void resetCamera()
|
void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 35;
|
float dist = 35;
|
||||||
float pitch = 0;
|
float pitch = -14;
|
||||||
float yaw = 14;
|
float yaw = 0;
|
||||||
float targetPos[3]={0,0,0};
|
float targetPos[3]={0,0,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|||||||
@@ -1978,6 +1978,30 @@ void b3RequestCameraImageSetShadow(b3SharedMemoryCommandHandle commandHandle, in
|
|||||||
command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_SHADOW;
|
command->m_updateFlags |= REQUEST_PIXEL_ARGS_SET_SHADOW;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
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();
|
||||||
|
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])
|
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]);
|
b3Vector3 eye = b3MakeVector3(cameraPosition[0], cameraPosition[1], cameraPosition[2]);
|
||||||
@@ -2019,76 +2043,42 @@ void b3ComputeViewMatrixFromYawPitchRoll(const float cameraTargetPosition[3], fl
|
|||||||
b3Vector3 camTargetPos = b3MakeVector3(cameraTargetPosition[0], cameraTargetPosition[1], cameraTargetPosition[2]);
|
b3Vector3 camTargetPos = b3MakeVector3(cameraTargetPosition[0], cameraTargetPosition[1], cameraTargetPosition[2]);
|
||||||
b3Vector3 eyePos = b3MakeVector3(0, 0, 0);
|
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 yawRad = yaw * b3Scalar(0.01745329251994329547);// rads per deg
|
||||||
b3Scalar pitchRad = pitch * b3Scalar(0.01745329251994329547);// rads per deg
|
b3Scalar pitchRad = pitch * b3Scalar(0.01745329251994329547);// rads per deg
|
||||||
|
b3Scalar rollRad = 0.0;
|
||||||
|
b3Quaternion eyeRot;
|
||||||
|
|
||||||
b3Quaternion pitchRot(camUpVector, pitchRad);
|
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;
|
||||||
|
};
|
||||||
|
|
||||||
b3Vector3 right = camUpVector.cross(camForward);
|
eyePos[forwardAxis] = -distance;
|
||||||
b3Quaternion yawRot(right, -yawRad);
|
|
||||||
|
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;
|
||||||
|
|
||||||
eyePos = b3Matrix3x3(pitchRot) * b3Matrix3x3(yawRot) * eyePos;
|
|
||||||
camPos = eyePos;
|
camPos = eyePos;
|
||||||
camPos += camTargetPos;
|
camPos += camTargetPos;
|
||||||
|
|
||||||
|
|||||||
@@ -166,6 +166,7 @@ void b3GetCameraImageData(b3PhysicsClientHandle physClient, struct b3CameraImage
|
|||||||
///compute a view matrix, helper function for b3RequestCameraImageSetCameraMatrices
|
///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 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 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]);
|
||||||
|
|
||||||
///compute a projection matrix, helper function for b3RequestCameraImageSetCameraMatrices
|
///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]);
|
void b3ComputeProjectionMatrix(float left, float right, float bottom, float top, float nearVal, float farVal, float projectionMatrix[16]);
|
||||||
|
|||||||
@@ -94,10 +94,10 @@ protected:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 3.45;
|
float dist = 3.45;
|
||||||
float pitch = 287;
|
float pitch = -16.2;
|
||||||
float yaw = 16.2;
|
float yaw = 287;
|
||||||
float targetPos[3]={2.05,0.02,0.53};//-3,2.8,-2.5};
|
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]);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -272,7 +272,6 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
|||||||
case CMD_REQUEST_CAMERA_IMAGE_DATA:
|
case CMD_REQUEST_CAMERA_IMAGE_DATA:
|
||||||
{
|
{
|
||||||
///request an image from a simulated camera, using a software renderer.
|
///request an image from a simulated camera, using a software renderer.
|
||||||
|
|
||||||
b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle);
|
b3SharedMemoryCommandHandle commandHandle = b3InitRequestCameraImage(m_physicsClientHandle);
|
||||||
//b3RequestCameraImageSelectRenderer(commandHandle,ER_BULLET_HARDWARE_OPENGL);
|
//b3RequestCameraImageSelectRenderer(commandHandle,ER_BULLET_HARDWARE_OPENGL);
|
||||||
|
|
||||||
@@ -329,6 +328,7 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
|||||||
//b3Printf("Joint %d: %f", i, sensorState.m_jointMotorTorque);
|
//b3Printf("Joint %d: %f", i, sensorState.m_jointMotorTorque);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
break;
|
break;
|
||||||
};
|
};
|
||||||
|
|
||||||
@@ -511,6 +511,18 @@ void PhysicsClientExample::prepareAndSubmitCommand(int commandId)
|
|||||||
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
case CMD_UPDATE_VISUAL_SHAPE:
|
||||||
|
{
|
||||||
|
int objectUniqueId = 0;
|
||||||
|
int linkIndex = -1;
|
||||||
|
int shapeIndex = -1;
|
||||||
|
int textureIndex = -1;
|
||||||
|
double rgbaColor[4] = {0.0, 1.0, 0.0, 1.0};
|
||||||
|
b3SharedMemoryCommandHandle commandHandle = b3InitUpdateVisualShape(m_physicsClientHandle, objectUniqueId, linkIndex, shapeIndex, textureIndex);
|
||||||
|
b3UpdateVisualShapeRGBAColor(commandHandle, rgbaColor);
|
||||||
|
b3SubmitClientCommand(m_physicsClientHandle, commandHandle);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
default:
|
default:
|
||||||
{
|
{
|
||||||
@@ -606,6 +618,7 @@ void PhysicsClientExample::createButtons()
|
|||||||
createButton("Load SDF",CMD_LOAD_SDF, isTrigger);
|
createButton("Load SDF",CMD_LOAD_SDF, isTrigger);
|
||||||
createButton("Save World",CMD_SAVE_WORLD, isTrigger);
|
createButton("Save World",CMD_SAVE_WORLD, isTrigger);
|
||||||
createButton("Set Shadow",CMD_SET_SHADOW, isTrigger);
|
createButton("Set Shadow",CMD_SET_SHADOW, isTrigger);
|
||||||
|
createButton("Update Visual Shape",CMD_UPDATE_VISUAL_SHAPE, isTrigger);
|
||||||
createButton("Get Camera Image",CMD_REQUEST_CAMERA_IMAGE_DATA,isTrigger);
|
createButton("Get Camera Image",CMD_REQUEST_CAMERA_IMAGE_DATA,isTrigger);
|
||||||
createButton("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger);
|
createButton("Step Sim",CMD_STEP_FORWARD_SIMULATION, isTrigger);
|
||||||
createButton("Realtime Sim",CMD_CUSTOM_SET_REALTIME_SIMULATION, isTrigger);
|
createButton("Realtime Sim",CMD_CUSTOM_SET_REALTIME_SIMULATION, isTrigger);
|
||||||
|
|||||||
@@ -4545,7 +4545,11 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
|||||||
serverCmd.m_visualizerCameraResultArgs.m_camUp,
|
serverCmd.m_visualizerCameraResultArgs.m_camUp,
|
||||||
serverCmd.m_visualizerCameraResultArgs.m_camForward,
|
serverCmd.m_visualizerCameraResultArgs.m_camForward,
|
||||||
serverCmd.m_visualizerCameraResultArgs.m_horizontal,
|
serverCmd.m_visualizerCameraResultArgs.m_horizontal,
|
||||||
serverCmd.m_visualizerCameraResultArgs.m_vertical);
|
serverCmd.m_visualizerCameraResultArgs.m_vertical,
|
||||||
|
&serverCmd.m_visualizerCameraResultArgs.m_yaw,
|
||||||
|
&serverCmd.m_visualizerCameraResultArgs.m_pitch,
|
||||||
|
&serverCmd.m_visualizerCameraResultArgs.m_dist,
|
||||||
|
serverCmd.m_visualizerCameraResultArgs.m_target);
|
||||||
serverCmd.m_type = result ? CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_COMPLETED: CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_FAILED;
|
serverCmd.m_type = result ? CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_COMPLETED: CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_FAILED;
|
||||||
hasStatus = true;
|
hasStatus = true;
|
||||||
break;
|
break;
|
||||||
@@ -4566,8 +4570,8 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
|||||||
if (clientCmd.m_updateFlags&COV_SET_CAMERA_VIEW_MATRIX)
|
if (clientCmd.m_updateFlags&COV_SET_CAMERA_VIEW_MATRIX)
|
||||||
{
|
{
|
||||||
m_data->m_guiHelper->resetCamera( clientCmd.m_configureOpenGLVisualizerArguments.m_cameraDistance,
|
m_data->m_guiHelper->resetCamera( clientCmd.m_configureOpenGLVisualizerArguments.m_cameraDistance,
|
||||||
clientCmd.m_configureOpenGLVisualizerArguments.m_cameraPitch,
|
|
||||||
clientCmd.m_configureOpenGLVisualizerArguments.m_cameraYaw,
|
clientCmd.m_configureOpenGLVisualizerArguments.m_cameraYaw,
|
||||||
|
clientCmd.m_configureOpenGLVisualizerArguments.m_cameraPitch,
|
||||||
clientCmd.m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[0],
|
clientCmd.m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[0],
|
||||||
clientCmd.m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[1],
|
clientCmd.m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[1],
|
||||||
clientCmd.m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[2]);
|
clientCmd.m_configureOpenGLVisualizerArguments.m_cameraTargetPosition[2]);
|
||||||
@@ -5679,7 +5683,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
|||||||
{
|
{
|
||||||
if (bodyHandle->m_multiBody->getBaseCollider())
|
if (bodyHandle->m_multiBody->getBaseCollider())
|
||||||
{
|
{
|
||||||
//m_data->m_visualConverter.changeRGBAColor(...)
|
m_data->m_visualConverter.changeRGBAColor(bodyUniqueId,linkIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
|
||||||
int graphicsIndex = bodyHandle->m_multiBody->getBaseCollider()->getUserIndex();
|
int graphicsIndex = bodyHandle->m_multiBody->getBaseCollider()->getUserIndex();
|
||||||
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR)
|
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR)
|
||||||
{
|
{
|
||||||
@@ -5697,7 +5701,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
|||||||
{
|
{
|
||||||
if (bodyHandle->m_multiBody->getLink(linkIndex).m_collider)
|
if (bodyHandle->m_multiBody->getLink(linkIndex).m_collider)
|
||||||
{
|
{
|
||||||
//m_data->m_visualConverter.changeRGBAColor(...)
|
m_data->m_visualConverter.changeRGBAColor(bodyUniqueId,linkIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
|
||||||
int graphicsIndex = bodyHandle->m_multiBody->getLink(linkIndex).m_collider->getUserIndex();
|
int graphicsIndex = bodyHandle->m_multiBody->getLink(linkIndex).m_collider->getUserIndex();
|
||||||
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR)
|
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR)
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -957,14 +957,14 @@ public:
|
|||||||
{
|
{
|
||||||
m_childGuiHelper->setUpAxis(axis);
|
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
|
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], float* yaw, float* pitch, float* camDist, float camTarget[3]) const
|
||||||
{
|
{
|
||||||
return m_childGuiHelper->getCameraInfo(width,height,viewMatrix,projectionMatrix,camUp,camForward,hor,vert);
|
return m_childGuiHelper->getCameraInfo(width,height,viewMatrix,projectionMatrix,camUp,camForward,hor,vert,yaw,pitch,camDist,camTarget);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@@ -1208,10 +1208,10 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 5;
|
float dist = 5;
|
||||||
float pitch = 50;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 50;
|
||||||
float targetPos[3]={0,0,0};//-3,2.8,-2.5};
|
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();
|
virtual bool wantsTermination();
|
||||||
|
|||||||
@@ -286,6 +286,11 @@ struct b3OpenGLVisualizerCameraInfo
|
|||||||
|
|
||||||
float m_horizontal[3];
|
float m_horizontal[3];
|
||||||
float m_vertical[3];
|
float m_vertical[3];
|
||||||
|
|
||||||
|
float m_yaw;
|
||||||
|
float m_pitch;
|
||||||
|
float m_dist;
|
||||||
|
float m_target[3];
|
||||||
};
|
};
|
||||||
|
|
||||||
enum b3VREventType
|
enum b3VREventType
|
||||||
|
|||||||
@@ -115,11 +115,11 @@ TinyRendererVisualShapeConverter::TinyRendererVisualShapeConverter()
|
|||||||
m_data = new TinyRendererVisualShapeConverterInternalData();
|
m_data = new TinyRendererVisualShapeConverterInternalData();
|
||||||
|
|
||||||
float dist = 1.5;
|
float dist = 1.5;
|
||||||
float pitch = -80;
|
float pitch = -10;
|
||||||
float yaw = 10;
|
float yaw = -80;
|
||||||
float targetPos[3]={0,0,0};
|
float targetPos[3]={0,0,0};
|
||||||
m_data->m_camera.setCameraUpAxis(m_data->m_upAxis);
|
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]);
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
@@ -671,6 +671,34 @@ int TinyRendererVisualShapeConverter::getVisualShapesData(int bodyUniqueId, int
|
|||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void TinyRendererVisualShapeConverter::changeRGBAColor(int bodyUniqueId, int linkIndex, const double rgbaColor[4])
|
||||||
|
{
|
||||||
|
int start = -1;
|
||||||
|
for (int i = 0; i < m_data->m_visualShapes.size(); i++)
|
||||||
|
{
|
||||||
|
if (m_data->m_visualShapes[i].m_objectUniqueId == bodyUniqueId && m_data->m_visualShapes[i].m_linkIndex == linkIndex)
|
||||||
|
{
|
||||||
|
start = i;
|
||||||
|
m_data->m_visualShapes[i].m_rgbaColor[0] = rgbaColor[0];
|
||||||
|
m_data->m_visualShapes[i].m_rgbaColor[1] = rgbaColor[1];
|
||||||
|
m_data->m_visualShapes[i].m_rgbaColor[2] = rgbaColor[2];
|
||||||
|
m_data->m_visualShapes[i].m_rgbaColor[3] = rgbaColor[3];
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
TinyRendererObjectArray** visualArrayPtr = m_data->m_swRenderInstances.getAtIndex(start);
|
||||||
|
TinyRendererObjectArray* visualArray = *visualArrayPtr;
|
||||||
|
|
||||||
|
btHashPtr colObjHash = m_data->m_swRenderInstances.getKeyAtIndex(start);
|
||||||
|
const btCollisionObject* colObj = (btCollisionObject*) colObjHash.getPointer();
|
||||||
|
|
||||||
|
float rgba[4] = {rgbaColor[0], rgbaColor[1], rgbaColor[2], rgbaColor[3]};
|
||||||
|
for (int v=0;v<visualArray->m_renderObjects.size();v++)
|
||||||
|
{
|
||||||
|
visualArray->m_renderObjects[v]->m_model->setColorRGBA(rgba);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void TinyRendererVisualShapeConverter::setUpAxis(int axis)
|
void TinyRendererVisualShapeConverter::setUpAxis(int axis)
|
||||||
{
|
{
|
||||||
@@ -678,7 +706,7 @@ void TinyRendererVisualShapeConverter::setUpAxis(int axis)
|
|||||||
m_data->m_camera.setCameraUpAxis(axis);
|
m_data->m_camera.setCameraUpAxis(axis);
|
||||||
m_data->m_camera.update();
|
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.setCameraDistance(camDist);
|
||||||
m_data->m_camera.setCameraPitch(pitch);
|
m_data->m_camera.setCameraPitch(pitch);
|
||||||
|
|||||||
@@ -22,11 +22,13 @@ struct TinyRendererVisualShapeConverter : public LinkVisualShapesConverter
|
|||||||
|
|
||||||
virtual int getVisualShapesData(int bodyUniqueId, int shapeIndex, struct b3VisualShapeData* shapeData);
|
virtual int getVisualShapesData(int bodyUniqueId, int shapeIndex, struct b3VisualShapeData* shapeData);
|
||||||
|
|
||||||
|
virtual void changeRGBAColor(int bodyUniqueId, int shapeIndex, const double rgbaColor[4]);
|
||||||
|
|
||||||
virtual void removeVisualShape(class btCollisionObject* colObj);
|
virtual void removeVisualShape(class btCollisionObject* colObj);
|
||||||
|
|
||||||
void setUpAxis(int axis);
|
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);
|
void clearBuffers(struct TGAColor& clearColor);
|
||||||
|
|
||||||
|
|||||||
@@ -107,10 +107,10 @@ public:
|
|||||||
{
|
{
|
||||||
//@todo depends on current_demo?
|
//@todo depends on current_demo?
|
||||||
float dist = 45;
|
float dist = 45;
|
||||||
float pitch = 27;
|
float pitch = -31;
|
||||||
float yaw = 31;
|
float yaw = 27;
|
||||||
float targetPos[3]={10-1,0};
|
float targetPos[3]={10-1,0};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
SoftDemo(struct GUIHelperInterface* helper)
|
SoftDemo(struct GUIHelperInterface* helper)
|
||||||
|
|||||||
@@ -56,10 +56,10 @@ struct Dof6ConstraintTutorial : public CommonRigidBodyBase
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 5;
|
float dist = 5;
|
||||||
float pitch = 722;
|
float pitch = -35;
|
||||||
float yaw = 35;
|
float yaw = 722;
|
||||||
float targetPos[3]={4,2,-11};
|
float targetPos[3]={4,2,-11};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|||||||
@@ -614,8 +614,8 @@ public:
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 10.5;
|
float dist = 10.5;
|
||||||
float pitch = 136;
|
float pitch = -32;
|
||||||
float yaw = 32;
|
float yaw = 136;
|
||||||
float targetPos[3]={0,0,0};
|
float targetPos[3]={0,0,0};
|
||||||
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
if (m_app->m_renderer && m_app->m_renderer->getActiveCamera())
|
||||||
{
|
{
|
||||||
|
|||||||
@@ -121,10 +121,10 @@ class Hinge2Vehicle : public CommonRigidBodyBase
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 8;
|
float dist = 8;
|
||||||
float pitch = -45;
|
float pitch = -32;
|
||||||
float yaw = 32;
|
float yaw = -45;
|
||||||
float targetPos[3]={-0.33,-0.72,4.5};
|
float targetPos[3]={-0.33,-0.72,4.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]);
|
||||||
}
|
}
|
||||||
|
|
||||||
/*static DemoApplication* Create()
|
/*static DemoApplication* Create()
|
||||||
|
|||||||
@@ -108,10 +108,10 @@ class VoronoiFractureDemo : public CommonRigidBodyBase
|
|||||||
virtual void resetCamera()
|
virtual void resetCamera()
|
||||||
{
|
{
|
||||||
float dist = 18;
|
float dist = 18;
|
||||||
float pitch = 129;
|
float pitch = -30;
|
||||||
float yaw = 30;
|
float yaw = 129;
|
||||||
float targetPos[3]={-1.5,4.7,-2};
|
float targetPos[3]={-1.5,4.7,-2};
|
||||||
m_guiHelper->resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]);
|
m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -52,7 +52,7 @@ def readLogFile(filename, verbose = True):
|
|||||||
#clid = p.connect(p.SHARED_MEMORY)
|
#clid = p.connect(p.SHARED_MEMORY)
|
||||||
p.connect(p.GUI)
|
p.connect(p.GUI)
|
||||||
p.loadURDF("plane.urdf",[0,0,-0.3])
|
p.loadURDF("plane.urdf",[0,0,-0.3])
|
||||||
p.loadURDF("kuka_iiwa/model.urdf",[0,0,0])
|
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])
|
p.loadURDF("cube.urdf",[-2,-2,5])
|
||||||
p.loadURDF("cube.urdf",[2,-2,5])
|
p.loadURDF("cube.urdf",[2,-2,5])
|
||||||
|
|||||||
@@ -3963,7 +3963,7 @@ static PyObject* pybullet_getDebugVisualizerCamera(PyObject* self, PyObject* arg
|
|||||||
if (hasCamInfo)
|
if (hasCamInfo)
|
||||||
{
|
{
|
||||||
PyObject* item=0;
|
PyObject* item=0;
|
||||||
pyCameraList = PyTuple_New(8);
|
pyCameraList = PyTuple_New(12);
|
||||||
item = PyInt_FromLong(camera.m_width);
|
item = PyInt_FromLong(camera.m_width);
|
||||||
PyTuple_SetItem(pyCameraList,0,item);
|
PyTuple_SetItem(pyCameraList,0,item);
|
||||||
item = PyInt_FromLong(camera.m_height);
|
item = PyInt_FromLong(camera.m_height);
|
||||||
@@ -4007,6 +4007,23 @@ static PyObject* pybullet_getDebugVisualizerCamera(PyObject* self, PyObject* arg
|
|||||||
PyTuple_SetItem(pyCameraList,6,hor);
|
PyTuple_SetItem(pyCameraList,6,hor);
|
||||||
PyTuple_SetItem(pyCameraList,7,vert);
|
PyTuple_SetItem(pyCameraList,7,vert);
|
||||||
}
|
}
|
||||||
|
item = PyFloat_FromDouble(camera.m_yaw);
|
||||||
|
PyTuple_SetItem(pyCameraList,8,item);
|
||||||
|
item = PyFloat_FromDouble(camera.m_pitch);
|
||||||
|
PyTuple_SetItem(pyCameraList,9,item);
|
||||||
|
item = PyFloat_FromDouble(camera.m_dist);
|
||||||
|
PyTuple_SetItem(pyCameraList,10,item);
|
||||||
|
{
|
||||||
|
PyObject* item=0;
|
||||||
|
int i;
|
||||||
|
PyObject* camTarget = PyTuple_New(3);
|
||||||
|
for (i=0;i<3;i++)
|
||||||
|
{
|
||||||
|
item = PyFloat_FromDouble(camera.m_target[i]);
|
||||||
|
PyTuple_SetItem(camTarget,i,item);
|
||||||
|
}
|
||||||
|
PyTuple_SetItem(pyCameraList,11,camTarget);
|
||||||
|
}
|
||||||
return pyCameraList;
|
return pyCameraList;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -901,6 +901,7 @@ b3ShortestArcQuat(const b3Vector3& v0, const b3Vector3& v1) // Game Programming
|
|||||||
b3Scalar rs = 1.0f / s;
|
b3Scalar rs = 1.0f / s;
|
||||||
|
|
||||||
return b3Quaternion(c.getX()*rs,c.getY()*rs,c.getZ()*rs,s * 0.5f);
|
return b3Quaternion(c.getX()*rs,c.getY()*rs,c.getZ()*rs,s * 0.5f);
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
B3_FORCE_INLINE b3Quaternion
|
B3_FORCE_INLINE b3Quaternion
|
||||||
|
|||||||
@@ -66,7 +66,7 @@ btPersistentManifold* btCollisionDispatcherMt::getNewManifold( const btCollision
|
|||||||
{
|
{
|
||||||
// batch updater will update manifold pointers array after finishing, so
|
// batch updater will update manifold pointers array after finishing, so
|
||||||
// only need to update array when not batch-updating
|
// only need to update array when not batch-updating
|
||||||
btAssert( !btThreadsAreRunning() );
|
//btAssert( !btThreadsAreRunning() );
|
||||||
manifold->m_index1a = m_manifoldsPtr.size();
|
manifold->m_index1a = m_manifoldsPtr.size();
|
||||||
m_manifoldsPtr.push_back( manifold );
|
m_manifoldsPtr.push_back( manifold );
|
||||||
}
|
}
|
||||||
@@ -77,7 +77,7 @@ btPersistentManifold* btCollisionDispatcherMt::getNewManifold( const btCollision
|
|||||||
void btCollisionDispatcherMt::releaseManifold( btPersistentManifold* manifold )
|
void btCollisionDispatcherMt::releaseManifold( btPersistentManifold* manifold )
|
||||||
{
|
{
|
||||||
clearManifold( manifold );
|
clearManifold( manifold );
|
||||||
btAssert( !btThreadsAreRunning() );
|
//btAssert( !btThreadsAreRunning() );
|
||||||
if ( !m_batchUpdating )
|
if ( !m_batchUpdating )
|
||||||
{
|
{
|
||||||
// batch updater will update manifold pointers array after finishing, so
|
// batch updater will update manifold pointers array after finishing, so
|
||||||
|
|||||||
Reference in New Issue
Block a user