From e6d1a8cf9747283f98af41d9e30014380fa93e9a Mon Sep 17 00:00:00 2001 From: yunfeibai Date: Thu, 1 Jun 2017 15:30:37 -0700 Subject: [PATCH] Swap yaw and pitch in camera computation. Add functions to convert view matrix to camera position, and camera position to camera yaw pitch roll. --- data/multibody.bullet | Bin 14844 -> 14844 bytes examples/BasicDemo/BasicExample.cpp | 6 +- examples/Benchmarks/BenchmarkDemo.cpp | 8 +- .../Collision/CollisionTutorialBullet2.cpp | 4 +- .../CommonGUIHelperInterface.h | 4 +- .../CommonGraphicsAppInterface.h | 4 +- examples/Constraints/ConstraintDemo.cpp | 8 +- .../Constraints/ConstraintPhysicsSetup.cpp | 6 +- examples/Constraints/Dof6Spring2Setup.cpp | 6 +- examples/Constraints/TestHingeTorque.cpp | 6 +- examples/DynamicControlDemo/MotorDemo.cpp | 8 +- examples/Evolution/NN3DWalkers.cpp | 6 +- examples/ExampleBrowser/OpenGLGuiHelper.cpp | 4 +- examples/ExampleBrowser/OpenGLGuiHelper.h | 2 +- examples/ExtendedTutorials/Bridge.cpp | 6 +- examples/ExtendedTutorials/Chain.cpp | 6 +- examples/ExtendedTutorials/InclinedPlane.cpp | 6 +- examples/ExtendedTutorials/MultiPendulum.cpp | 6 +- examples/ExtendedTutorials/MultipleBoxes.cpp | 6 +- examples/ExtendedTutorials/NewtonsCradle.cpp | 6 +- .../ExtendedTutorials/NewtonsRopeCradle.cpp | 6 +- .../ExtendedTutorials/RigidBodyFromObj.cpp | 6 +- examples/ExtendedTutorials/SimpleBox.cpp | 6 +- examples/ExtendedTutorials/SimpleCloth.cpp | 6 +- examples/ExtendedTutorials/SimpleJoint.cpp | 6 +- examples/ForkLift/ForkLiftDemo.cpp | 6 +- examples/FractureDemo/FractureDemo.cpp | 6 +- examples/GyroscopicDemo/GyroscopicSetup.cpp | 8 +- .../Importers/ImportBsp/ImportBspExample.cpp | 8 +- .../Importers/ImportBullet/SerializeSetup.cpp | 6 +- .../ImportColladaDemo/ImportColladaSetup.cpp | 6 +- .../ImportMJCFDemo/ImportMJCFSetup.cpp | 6 +- .../ImportObjDemo/ImportObjExample.cpp | 6 +- .../ImportSDFDemo/ImportSDFSetup.cpp | 6 +- .../ImportSTLDemo/ImportSTLSetup.cpp | 6 +- .../ImportURDFDemo/ImportURDFSetup.cpp | 6 +- .../InverseDynamicsExample.cpp | 6 +- .../InverseKinematicsExample.cpp | 4 +- .../MultiBody/InvertedPendulumPDControl.cpp | 6 +- .../MultiBody/MultiBodyConstraintFeedback.cpp | 6 +- examples/MultiBody/MultiBodySoftContact.cpp | 6 +- examples/MultiBody/MultiDofDemo.cpp | 8 +- examples/MultiBody/Pendulum.cpp | 6 +- examples/MultiBody/TestJointTorqueSetup.cpp | 6 +- .../MultiThreadedDemo/MultiThreadedDemo.cpp | 6 +- .../MultiThreading/MultiThreadingExample.cpp | 4 +- examples/OpenCL/broadphase/PairBench.cpp | 6 +- examples/OpenCL/rigidbody/GpuConvexScene.cpp | 6 +- .../OpenCL/rigidbody/GpuRigidBodyDemo.cpp | 6 +- examples/OpenGLWindow/SimpleCamera.cpp | 22 +-- examples/Planar2D/Planar2D.cpp | 6 +- examples/Raycast/RaytestDemo.cpp | 6 +- .../CoordinateSystemDemo.cpp | 4 +- .../DynamicTexturedCubeDemo.cpp | 4 +- .../RenderInstancingDemo.cpp | 4 +- .../RenderingExamples/TinyRendererSetup.cpp | 6 +- examples/RigidBody/RigidBodySoftContact.cpp | 6 +- .../RoboticsLearning/GripperGraspExample.cpp | 4 +- .../RoboticsLearning/KukaGraspExample.cpp | 4 +- .../RoboticsLearning/R2D2GraspExample.cpp | 4 +- .../RollingFrictionDemo.cpp | 6 +- examples/SharedMemory/PhysicsClientC_API.cpp | 184 +++++++++++------- examples/SharedMemory/PhysicsClientC_API.h | 2 + .../SharedMemory/PhysicsClientExample.cpp | 30 ++- .../PhysicsServerCommandProcessor.cpp | 2 +- .../SharedMemory/PhysicsServerExample.cpp | 10 +- .../TinyRendererVisualShapeConverter.cpp | 8 +- .../TinyRendererVisualShapeConverter.h | 2 +- examples/SoftDemo/SoftDemo.cpp | 6 +- examples/Tutorial/Dof6ConstraintTutorial.cpp | 6 +- examples/Tutorial/Tutorial.cpp | 4 +- examples/Vehicles/Hinge2Vehicle.cpp | 6 +- .../VoronoiFracture/VoronoiFractureDemo.cpp | 6 +- .../examples/kuka_with_cube_playback.py | 2 +- 74 files changed, 347 insertions(+), 281 deletions(-) diff --git a/data/multibody.bullet b/data/multibody.bullet index 4b0debb4b5f8f3449adb320a1b9bd31b724242d5..0dee8f14afc067fbc54030a22bd9941df44f6edd 100644 GIT binary patch delta 510 zcmexU{HJ)r7FI3>1_tiQ6Im=LeyTD7vNr=U7~I$#YybcMe>*65OG;YWJ}8?3CJt1y zfARtr5etxFm?Vf^Qm_}U7{p)5c@D(4e-U(auj20Mc4=v8_OoWrw3~QAOq_wC!u=3X zw!xl(5eQ*mvLutbCIiDJ7@uLozlDk*X@lPj6+wavzC-vGv(7LuPM*jl%=-YUB4IC3 zX0jrSHV-pU9SE}k@#F(cCNe-849b2o*n${J&&&2L$e+5)Lf+M3vH`0|E=Vw&J1!PP zgTR5<1z=ktJXC%PP!JdtV1RHq14>AoJ#)sE!9m8231$G425Iu09LS+Oc?+|G4_MF= zDg~tf{}**;V2CgSikLz~&CDTUFg}EaiZMJ;U$&pgc;9}IwP+@w;oyL1R5-Xf VhQ)=M6U5u_5Ew9Xb}qrnM39Oc1wpr9IBO!^fwHF!n>5y`(FNFr zG;J)@`^lDE@bIs-bl|t_R=d@D%QtC^nQ|KTQRC;iR{6FHuQfK52VPjP;e#Im1QEgz zh7raHMlptQOrT$HmG+1FC}uE=7~+`2JQj@EGK(}zNFa%2tY8&uSVsyQ*mPpvRDPE( zgFWoy0EbW=;{>NTLl&y2`H$KAF^#8)vu(%2$|}E<^Xbjh)F`+Ds~@ascDkN|5AJoK z!C3({N8DEjPs#k~UmyR`1b+@lOEh|yHX3F6l zCFJpl0`75#8resetCamera(dist,pitch,yaw,targetPos[0],targetPos[1],targetPos[2]); + m_guiHelper->resetCamera(dist,yaw,pitch,targetPos[0],targetPos[1],targetPos[2]); } }; diff --git a/examples/Benchmarks/BenchmarkDemo.cpp b/examples/Benchmarks/BenchmarkDemo.cpp index d9a1b3ef0..a50967441 100644 --- a/examples/Benchmarks/BenchmarkDemo.cpp +++ b/examples/Benchmarks/BenchmarkDemo.cpp @@ -110,10 +110,10 @@ class BenchmarkDemo : public CommonRigidBodyMTBase void resetCamera() { float dist = 120; - float pitch = 52; - float yaw = 35; + float pitch = -35; + float yaw = 52; 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]); } }; @@ -1315,4 +1315,4 @@ void BenchmarkDemo::exitPhysics() CommonExampleInterface* BenchmarkCreateFunc(struct CommonExampleOptions& options) { return new BenchmarkDemo(options.m_guiHelper,options.m_option); -} \ No newline at end of file +} diff --git a/examples/Collision/CollisionTutorialBullet2.cpp b/examples/Collision/CollisionTutorialBullet2.cpp index 8fd3bf1a8..8159f89ee 100644 --- a/examples/Collision/CollisionTutorialBullet2.cpp +++ b/examples/Collision/CollisionTutorialBullet2.cpp @@ -371,8 +371,8 @@ public: virtual void resetCamera() { float dist = 10.5; - float pitch = 136; - float yaw = 32; + float pitch = -32; + float yaw = 136; float targetPos[3]={0,0,0}; if (m_app->m_renderer && m_app->m_renderer->getActiveCamera()) { diff --git a/examples/CommonInterfaces/CommonGUIHelperInterface.h b/examples/CommonInterfaces/CommonGUIHelperInterface.h index 24b4a301c..2a07e2cbc 100644 --- a/examples/CommonInterfaces/CommonGUIHelperInterface.h +++ b/examples/CommonInterfaces/CommonGUIHelperInterface.h @@ -55,7 +55,7 @@ struct GUIHelperInterface 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 { @@ -151,7 +151,7 @@ struct DummyGUIHelper : public GUIHelperInterface 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) { } diff --git a/examples/CommonInterfaces/CommonGraphicsAppInterface.h b/examples/CommonInterfaces/CommonGraphicsAppInterface.h index e1c4182c6..23118d1ac 100644 --- a/examples/CommonInterfaces/CommonGraphicsAppInterface.h +++ b/examples/CommonInterfaces/CommonGraphicsAppInterface.h @@ -201,10 +201,10 @@ struct CommonGraphicsApp { // if (b3Fabs(xDelta)>b3Fabs(yDelta)) // { - pitch -= xDelta*m_mouseMoveMultiplier; + pitch -= yDelta*m_mouseMoveMultiplier; // } else // { - yaw += yDelta*m_mouseMoveMultiplier; + yaw -= xDelta*m_mouseMoveMultiplier; // } } diff --git a/examples/Constraints/ConstraintDemo.cpp b/examples/Constraints/ConstraintDemo.cpp index 41a888cd4..72ad1a8a6 100644 --- a/examples/Constraints/ConstraintDemo.cpp +++ b/examples/Constraints/ConstraintDemo.cpp @@ -50,10 +50,10 @@ class AllConstraintDemo : public CommonRigidBodyBase virtual void resetCamera() { float dist = 27; - float pitch = 720; - float yaw = 30; + float pitch = -30; + float yaw = 720; 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); @@ -885,4 +885,4 @@ bool AllConstraintDemo::keyboardCallback(int key, int state) class CommonExampleInterface* AllConstraintCreateFunc(struct CommonExampleOptions& options) { return new AllConstraintDemo(options.m_guiHelper); -} \ No newline at end of file +} diff --git a/examples/Constraints/ConstraintPhysicsSetup.cpp b/examples/Constraints/ConstraintPhysicsSetup.cpp index 71b3b2e97..faf31e204 100644 --- a/examples/Constraints/ConstraintPhysicsSetup.cpp +++ b/examples/Constraints/ConstraintPhysicsSetup.cpp @@ -18,10 +18,10 @@ struct ConstraintPhysicsSetup : public CommonRigidBodyBase virtual void resetCamera() { float dist = 7; - float pitch = 721; - float yaw = 44; + float pitch = -44; + float yaw = 721; 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]); } diff --git a/examples/Constraints/Dof6Spring2Setup.cpp b/examples/Constraints/Dof6Spring2Setup.cpp index 0fd8975d4..89129f7a6 100644 --- a/examples/Constraints/Dof6Spring2Setup.cpp +++ b/examples/Constraints/Dof6Spring2Setup.cpp @@ -55,10 +55,10 @@ struct Dof6Spring2Setup : public CommonRigidBodyBase virtual void resetCamera() { float dist = 5; - float pitch = 722; - float yaw = 35; + float pitch = -35; + float yaw = 722; 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]); } }; diff --git a/examples/Constraints/TestHingeTorque.cpp b/examples/Constraints/TestHingeTorque.cpp index 86217de3f..b22cfb55e 100644 --- a/examples/Constraints/TestHingeTorque.cpp +++ b/examples/Constraints/TestHingeTorque.cpp @@ -24,10 +24,10 @@ struct TestHingeTorque : public CommonRigidBodyBase { float dist = 5; - float pitch = 270; - float yaw = 21; + float pitch = -21; + float yaw = 270; 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]); } diff --git a/examples/DynamicControlDemo/MotorDemo.cpp b/examples/DynamicControlDemo/MotorDemo.cpp index 84284c534..d4025461e 100644 --- a/examples/DynamicControlDemo/MotorDemo.cpp +++ b/examples/DynamicControlDemo/MotorDemo.cpp @@ -63,10 +63,10 @@ public: void resetCamera() { float dist = 11; - float pitch = 52; - float yaw = 35; + float pitch = -35; + float yaw = 52; 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]); } }; @@ -447,4 +447,4 @@ void MotorDemo::exitPhysics() class CommonExampleInterface* MotorControlCreateFunc(struct CommonExampleOptions& options) { return new MotorDemo(options.m_guiHelper); -} \ No newline at end of file +} diff --git a/examples/Evolution/NN3DWalkers.cpp b/examples/Evolution/NN3DWalkers.cpp index 8e1afca90..420ef7e22 100755 --- a/examples/Evolution/NN3DWalkers.cpp +++ b/examples/Evolution/NN3DWalkers.cpp @@ -145,10 +145,10 @@ public: void resetCamera() { float dist = 11; - float pitch = 52; - float yaw = 35; + float pitch = -35; + float yaw = 52; 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 diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.cpp b/examples/ExampleBrowser/OpenGLGuiHelper.cpp index 105ab64a6..3789532c4 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.cpp +++ b/examples/ExampleBrowser/OpenGLGuiHelper.cpp @@ -973,7 +973,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()) { @@ -1222,4 +1222,4 @@ void OpenGLGuiHelper::dumpFramesToVideo(const char* mp4FileName) { m_data->m_glApp->dumpFramesToVideo(mp4FileName); } -} \ No newline at end of file +} diff --git a/examples/ExampleBrowser/OpenGLGuiHelper.h b/examples/ExampleBrowser/OpenGLGuiHelper.h index 182027daa..9094fc3ac 100644 --- a/examples/ExampleBrowser/OpenGLGuiHelper.h +++ b/examples/ExampleBrowser/OpenGLGuiHelper.h @@ -46,7 +46,7 @@ struct OpenGLGuiHelper : public GUIHelperInterface 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 void copyCameraImageData(const float viewMatrix[16], const float projectionMatrix[16], diff --git a/examples/ExtendedTutorials/Bridge.cpp b/examples/ExtendedTutorials/Bridge.cpp index 269b5c4d0..41fe55290 100644 --- a/examples/ExtendedTutorials/Bridge.cpp +++ b/examples/ExtendedTutorials/Bridge.cpp @@ -35,10 +35,10 @@ struct BridgeExample : public CommonRigidBodyBase void resetCamera() { float dist = 41; - float pitch = 52; - float yaw = 35; + float pitch = -35; + float yaw = 52; 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]); } }; diff --git a/examples/ExtendedTutorials/Chain.cpp b/examples/ExtendedTutorials/Chain.cpp index e78952db9..73d2eb7e7 100644 --- a/examples/ExtendedTutorials/Chain.cpp +++ b/examples/ExtendedTutorials/Chain.cpp @@ -35,10 +35,10 @@ struct ChainExample : public CommonRigidBodyBase void resetCamera() { float dist = 41; - float pitch = 52; - float yaw = 35; + float pitch = -35; + float yaw = 52; 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]); } }; diff --git a/examples/ExtendedTutorials/InclinedPlane.cpp b/examples/ExtendedTutorials/InclinedPlane.cpp index 343ebc3ae..d6322f034 100644 --- a/examples/ExtendedTutorials/InclinedPlane.cpp +++ b/examples/ExtendedTutorials/InclinedPlane.cpp @@ -62,10 +62,10 @@ struct InclinedPlaneExample : public CommonRigidBodyBase void resetCamera() { float dist = 41; - float pitch = 52; - float yaw = 35; + float pitch = -35; + float yaw = 52; 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]); } diff --git a/examples/ExtendedTutorials/MultiPendulum.cpp b/examples/ExtendedTutorials/MultiPendulum.cpp index b45eee755..7dfdffea3 100644 --- a/examples/ExtendedTutorials/MultiPendulum.cpp +++ b/examples/ExtendedTutorials/MultiPendulum.cpp @@ -58,10 +58,10 @@ struct MultiPendulumExample: public CommonRigidBodyBase { virtual void applyPendulumForce(btScalar pendulumForce); void resetCamera() { float dist = 41; - float pitch = 52; - float yaw = 35; + float pitch = -35; + float yaw = 52; 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]); } diff --git a/examples/ExtendedTutorials/MultipleBoxes.cpp b/examples/ExtendedTutorials/MultipleBoxes.cpp index c9555936a..8db651aa0 100644 --- a/examples/ExtendedTutorials/MultipleBoxes.cpp +++ b/examples/ExtendedTutorials/MultipleBoxes.cpp @@ -35,10 +35,10 @@ struct MultipleBoxesExample : public CommonRigidBodyBase void resetCamera() { float dist = 41; - float pitch = 52; - float yaw = 35; + float pitch = -35; + float yaw = 52; 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]); } }; diff --git a/examples/ExtendedTutorials/NewtonsCradle.cpp b/examples/ExtendedTutorials/NewtonsCradle.cpp index 54be8367a..92924bc7d 100644 --- a/examples/ExtendedTutorials/NewtonsCradle.cpp +++ b/examples/ExtendedTutorials/NewtonsCradle.cpp @@ -58,10 +58,10 @@ struct NewtonsCradleExample: public CommonRigidBodyBase { virtual void applyPendulumForce(btScalar pendulumForce); void resetCamera() { float dist = 41; - float pitch = 52; - float yaw = 35; + float pitch = -35; + float yaw = 52; 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]); } diff --git a/examples/ExtendedTutorials/NewtonsRopeCradle.cpp b/examples/ExtendedTutorials/NewtonsRopeCradle.cpp index 76eb115ea..8786ebed7 100644 --- a/examples/ExtendedTutorials/NewtonsRopeCradle.cpp +++ b/examples/ExtendedTutorials/NewtonsRopeCradle.cpp @@ -90,10 +90,10 @@ struct NewtonsRopeCradleExample : public CommonRigidBodyBase { void resetCamera() { float dist = 41; - float pitch = 52; - float yaw = 35; + float pitch = -35; + float yaw = 52; 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 constraints; diff --git a/examples/ExtendedTutorials/RigidBodyFromObj.cpp b/examples/ExtendedTutorials/RigidBodyFromObj.cpp index 9e09f9dd9..7d2a59b91 100644 --- a/examples/ExtendedTutorials/RigidBodyFromObj.cpp +++ b/examples/ExtendedTutorials/RigidBodyFromObj.cpp @@ -43,10 +43,10 @@ struct RigidBodyFromObjExample : public CommonRigidBodyBase void resetCamera() { float dist = 11; - float pitch = 52; - float yaw = 35; + float pitch = -35; + float yaw = 52; 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]); } }; diff --git a/examples/ExtendedTutorials/SimpleBox.cpp b/examples/ExtendedTutorials/SimpleBox.cpp index 474a507f0..49e252739 100644 --- a/examples/ExtendedTutorials/SimpleBox.cpp +++ b/examples/ExtendedTutorials/SimpleBox.cpp @@ -35,10 +35,10 @@ struct SimpleBoxExample : public CommonRigidBodyBase void resetCamera() { float dist = 41; - float pitch = 52; - float yaw = 35; + float pitch = -35; + float yaw = 52; 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]); } }; diff --git a/examples/ExtendedTutorials/SimpleCloth.cpp b/examples/ExtendedTutorials/SimpleCloth.cpp index 33a3815b1..ec0dd337c 100644 --- a/examples/ExtendedTutorials/SimpleCloth.cpp +++ b/examples/ExtendedTutorials/SimpleCloth.cpp @@ -61,10 +61,10 @@ struct SimpleClothExample : public CommonRigidBodyBase void resetCamera() { float dist = 41; - float pitch = 52; - float yaw = 35; + float pitch = -35; + float yaw = 52; 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); diff --git a/examples/ExtendedTutorials/SimpleJoint.cpp b/examples/ExtendedTutorials/SimpleJoint.cpp index da30449b4..1a76f20ec 100644 --- a/examples/ExtendedTutorials/SimpleJoint.cpp +++ b/examples/ExtendedTutorials/SimpleJoint.cpp @@ -35,10 +35,10 @@ struct SimpleJointExample : public CommonRigidBodyBase void resetCamera() { float dist = 41; - float pitch = 52; - float yaw = 35; + float pitch = -35; + float yaw = 52; 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]); } }; diff --git a/examples/ForkLift/ForkLiftDemo.cpp b/examples/ForkLift/ForkLiftDemo.cpp index e993462ef..bac041662 100644 --- a/examples/ForkLift/ForkLiftDemo.cpp +++ b/examples/ForkLift/ForkLiftDemo.cpp @@ -144,10 +144,10 @@ class ForkLiftDemo : public CommonExampleInterface virtual void resetCamera() { float dist = 8; - float pitch = -45; - float yaw = 32; + float pitch = -32; + float yaw = -45; 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() diff --git a/examples/FractureDemo/FractureDemo.cpp b/examples/FractureDemo/FractureDemo.cpp index 849914e85..4e46f472c 100644 --- a/examples/FractureDemo/FractureDemo.cpp +++ b/examples/FractureDemo/FractureDemo.cpp @@ -90,10 +90,10 @@ public: void resetCamera() { float dist = 41; - float pitch = 52; - float yaw = 35; + float pitch = -35; + float yaw = 52; 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]); } diff --git a/examples/GyroscopicDemo/GyroscopicSetup.cpp b/examples/GyroscopicDemo/GyroscopicSetup.cpp index e8eb55026..5ef115678 100644 --- a/examples/GyroscopicDemo/GyroscopicSetup.cpp +++ b/examples/GyroscopicDemo/GyroscopicSetup.cpp @@ -21,10 +21,10 @@ struct GyroscopicSetup : public CommonRigidBodyBase void resetCamera() { float dist = 20; - float pitch = 180; - float yaw = 16; + float pitch = -16; + float yaw = 180; 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]); } }; @@ -135,4 +135,4 @@ void GyroscopicSetup::physicsDebugDraw(int debugFlags) class CommonExampleInterface* GyroscopicCreateFunc(CommonExampleOptions& options) { return new GyroscopicSetup(options.m_guiHelper); -} \ No newline at end of file +} diff --git a/examples/Importers/ImportBsp/ImportBspExample.cpp b/examples/Importers/ImportBsp/ImportBspExample.cpp index eec8a4fb9..31b4cb41b 100644 --- a/examples/Importers/ImportBsp/ImportBspExample.cpp +++ b/examples/Importers/ImportBsp/ImportBspExample.cpp @@ -67,10 +67,10 @@ class BspDemo : public CommonRigidBodyBase virtual void resetCamera() { float dist = 43; - float pitch = -175; - float yaw = 12; + float pitch = -12; + float yaw = -175; 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]); } @@ -301,4 +301,4 @@ static DemoApplication* Create() demo->initPhysics("BspDemo.bsp"); return demo; } - */ \ No newline at end of file + */ diff --git a/examples/Importers/ImportBullet/SerializeSetup.cpp b/examples/Importers/ImportBullet/SerializeSetup.cpp index 460d27192..0d6931e4f 100644 --- a/examples/Importers/ImportBullet/SerializeSetup.cpp +++ b/examples/Importers/ImportBullet/SerializeSetup.cpp @@ -22,10 +22,10 @@ public: virtual void resetCamera() { float dist = 9.5; - float pitch = -2.8; - float yaw = 20; + float pitch = -20; + float yaw = -2.8; 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]); } }; diff --git a/examples/Importers/ImportColladaDemo/ImportColladaSetup.cpp b/examples/Importers/ImportColladaDemo/ImportColladaSetup.cpp index 4b0292c74..453d16298 100644 --- a/examples/Importers/ImportColladaDemo/ImportColladaSetup.cpp +++ b/examples/Importers/ImportColladaDemo/ImportColladaSetup.cpp @@ -41,10 +41,10 @@ public: virtual void resetCamera() { float dist = 16; - float pitch = -140; - float yaw = 28; + float pitch = -28; + float yaw = -140; 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]); } }; diff --git a/examples/Importers/ImportMJCFDemo/ImportMJCFSetup.cpp b/examples/Importers/ImportMJCFDemo/ImportMJCFSetup.cpp index c533d8062..64c226811 100644 --- a/examples/Importers/ImportMJCFDemo/ImportMJCFSetup.cpp +++ b/examples/Importers/ImportMJCFDemo/ImportMJCFSetup.cpp @@ -38,10 +38,10 @@ public: virtual void resetCamera() { float dist = 3.5; - float pitch = -136; - float yaw = 28; + float pitch = -28; + float yaw = -136; 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]); } }; diff --git a/examples/Importers/ImportObjDemo/ImportObjExample.cpp b/examples/Importers/ImportObjDemo/ImportObjExample.cpp index 2fc11afa3..e049f5f0f 100644 --- a/examples/Importers/ImportObjDemo/ImportObjExample.cpp +++ b/examples/Importers/ImportObjDemo/ImportObjExample.cpp @@ -29,10 +29,10 @@ public: virtual void resetCamera() { float dist = 18; - float pitch = 120; - float yaw = 46; + float pitch = -46; + float yaw = 120; 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]); } }; diff --git a/examples/Importers/ImportSDFDemo/ImportSDFSetup.cpp b/examples/Importers/ImportSDFDemo/ImportSDFSetup.cpp index 4248cbdb3..412024c5e 100644 --- a/examples/Importers/ImportSDFDemo/ImportSDFSetup.cpp +++ b/examples/Importers/ImportSDFDemo/ImportSDFSetup.cpp @@ -50,10 +50,10 @@ public: virtual void resetCamera() { float dist = 3.5; - float pitch = -136; - float yaw = 28; + float pitch = -28; + float yaw = -136; 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]); } }; diff --git a/examples/Importers/ImportSTLDemo/ImportSTLSetup.cpp b/examples/Importers/ImportSTLDemo/ImportSTLSetup.cpp index c05138ef1..3edcd30bd 100644 --- a/examples/Importers/ImportSTLDemo/ImportSTLSetup.cpp +++ b/examples/Importers/ImportSTLDemo/ImportSTLSetup.cpp @@ -25,10 +25,10 @@ public: virtual void resetCamera() { float dist = 3.5; - float pitch = -136; - float yaw = 28; + float pitch = -28; + float yaw = -136; 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]); } }; diff --git a/examples/Importers/ImportURDFDemo/ImportURDFSetup.cpp b/examples/Importers/ImportURDFDemo/ImportURDFSetup.cpp index a3d8a608f..8149f59ec 100644 --- a/examples/Importers/ImportURDFDemo/ImportURDFSetup.cpp +++ b/examples/Importers/ImportURDFDemo/ImportURDFSetup.cpp @@ -50,10 +50,10 @@ public: virtual void resetCamera() { float dist = 3.5; - float pitch = -136; - float yaw = 28; + float pitch = -28; + float yaw = -136; 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]); } }; diff --git a/examples/InverseDynamics/InverseDynamicsExample.cpp b/examples/InverseDynamics/InverseDynamicsExample.cpp index f6e3af618..323f52dde 100644 --- a/examples/InverseDynamics/InverseDynamicsExample.cpp +++ b/examples/InverseDynamics/InverseDynamicsExample.cpp @@ -87,10 +87,10 @@ public: virtual void resetCamera() { float dist = 1.5; - float pitch = -80; - float yaw = 10; + float pitch = -10; + float yaw = -80; 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]); } }; diff --git a/examples/InverseKinematics/InverseKinematicsExample.cpp b/examples/InverseKinematics/InverseKinematicsExample.cpp index 496013188..9f2eae900 100644 --- a/examples/InverseKinematics/InverseKinematicsExample.cpp +++ b/examples/InverseKinematics/InverseKinematicsExample.cpp @@ -313,8 +313,8 @@ public: virtual void resetCamera() { float dist = 1.3; - float pitch = 120; - float yaw = 13; + float pitch = -13; + float yaw = 120; float targetPos[3]={-0.35,0.14,0.25}; if (m_app->m_renderer && m_app->m_renderer->getActiveCamera()) { diff --git a/examples/MultiBody/InvertedPendulumPDControl.cpp b/examples/MultiBody/InvertedPendulumPDControl.cpp index de9fc122f..8031e773d 100644 --- a/examples/MultiBody/InvertedPendulumPDControl.cpp +++ b/examples/MultiBody/InvertedPendulumPDControl.cpp @@ -30,10 +30,10 @@ public: virtual void resetCamera() { float dist = 5; - float pitch = 270; - float yaw = 21; + float pitch = -21; + float yaw = 270; 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]); } diff --git a/examples/MultiBody/MultiBodyConstraintFeedback.cpp b/examples/MultiBody/MultiBodyConstraintFeedback.cpp index 511aad6ec..c08d98f72 100644 --- a/examples/MultiBody/MultiBodyConstraintFeedback.cpp +++ b/examples/MultiBody/MultiBodyConstraintFeedback.cpp @@ -26,10 +26,10 @@ public: virtual void resetCamera() { float dist = 5; - float pitch = 270; - float yaw = 21; + float pitch = -21; + float yaw = 270; 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]); } diff --git a/examples/MultiBody/MultiBodySoftContact.cpp b/examples/MultiBody/MultiBodySoftContact.cpp index 7d5a17bc9..0ffcaf1f5 100644 --- a/examples/MultiBody/MultiBodySoftContact.cpp +++ b/examples/MultiBody/MultiBodySoftContact.cpp @@ -27,10 +27,10 @@ public: virtual void resetCamera() { float dist = 5; - float pitch = 270; - float yaw = 21; + float pitch = -21; + float yaw = 270; 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]); } diff --git a/examples/MultiBody/MultiDofDemo.cpp b/examples/MultiBody/MultiDofDemo.cpp index 4a6510e7d..86d893f73 100644 --- a/examples/MultiBody/MultiDofDemo.cpp +++ b/examples/MultiBody/MultiDofDemo.cpp @@ -34,10 +34,10 @@ public: virtual void resetCamera() { float dist = 1; - float pitch = 50; - float yaw = 35; + float pitch = -35; + float yaw = 50; 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]); } @@ -446,4 +446,4 @@ void MultiDofDemo::addBoxes_testMultiDof() class CommonExampleInterface* MultiDofCreateFunc(struct CommonExampleOptions& options) { return new MultiDofDemo(options.m_guiHelper); -} \ No newline at end of file +} diff --git a/examples/MultiBody/Pendulum.cpp b/examples/MultiBody/Pendulum.cpp index ecfe989ba..2a52c936f 100644 --- a/examples/MultiBody/Pendulum.cpp +++ b/examples/MultiBody/Pendulum.cpp @@ -40,10 +40,10 @@ public: virtual void resetCamera() { float dist = 5; - float pitch = 270; - float yaw = 21; + float pitch = -21; + float yaw = 270; 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]); } diff --git a/examples/MultiBody/TestJointTorqueSetup.cpp b/examples/MultiBody/TestJointTorqueSetup.cpp index 61142eaa7..25d0456d2 100644 --- a/examples/MultiBody/TestJointTorqueSetup.cpp +++ b/examples/MultiBody/TestJointTorqueSetup.cpp @@ -27,10 +27,10 @@ public: virtual void resetCamera() { float dist = 5; - float pitch = 270; - float yaw = 21; + float pitch = -21; + float yaw = 270; 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]); } diff --git a/examples/MultiThreadedDemo/MultiThreadedDemo.cpp b/examples/MultiThreadedDemo/MultiThreadedDemo.cpp index 3dff09ae8..c9190dff0 100644 --- a/examples/MultiThreadedDemo/MultiThreadedDemo.cpp +++ b/examples/MultiThreadedDemo/MultiThreadedDemo.cpp @@ -98,8 +98,8 @@ public: virtual void resetCamera() BT_OVERRIDE { m_guiHelper->resetCamera( m_cameraDist, - m_cameraPitch, m_cameraYaw, + m_cameraPitch, m_cameraTargetPos.x(), m_cameraTargetPos.y(), m_cameraTargetPos.z() @@ -115,8 +115,8 @@ MultiThreadedDemo::MultiThreadedDemo(struct GUIHelperInterface* helper) m_groundBody = NULL; m_groundMovePhase = 0.0f; m_cameraTargetPos = btVector3( 0.0f, 0.0f, 0.0f ); - m_cameraPitch = 90.0f; - m_cameraYaw = 30.0f; + m_cameraPitch = -30.0f; + m_cameraYaw = 90.0f; m_cameraDist = 48.0f; helper->setUpAxis( kUpAxis ); } diff --git a/examples/MultiThreading/MultiThreadingExample.cpp b/examples/MultiThreading/MultiThreadingExample.cpp index 381453c1e..92dea68c5 100644 --- a/examples/MultiThreading/MultiThreadingExample.cpp +++ b/examples/MultiThreading/MultiThreadingExample.cpp @@ -304,8 +304,8 @@ public: virtual void resetCamera() { float dist = 10.5; - float pitch = 136; - float yaw = 32; + float pitch = -32; + float yaw = 136; float targetPos[3]={0,0,0}; if (m_app->m_renderer && m_app->m_renderer->getActiveCamera()) { diff --git a/examples/OpenCL/broadphase/PairBench.cpp b/examples/OpenCL/broadphase/PairBench.cpp index f1c8ac5c5..55074f48f 100644 --- a/examples/OpenCL/broadphase/PairBench.cpp +++ b/examples/OpenCL/broadphase/PairBench.cpp @@ -71,10 +71,10 @@ public: dist = 130; } - float pitch = 62; - float yaw = 33; + float pitch = -33; + float yaw = 62; 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]); } }; diff --git a/examples/OpenCL/rigidbody/GpuConvexScene.cpp b/examples/OpenCL/rigidbody/GpuConvexScene.cpp index 796a9922d..78a3beb86 100644 --- a/examples/OpenCL/rigidbody/GpuConvexScene.cpp +++ b/examples/OpenCL/rigidbody/GpuConvexScene.cpp @@ -150,8 +150,8 @@ void GpuConvexScene::setupScene() m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraTargetPosition(camPos[0],camPos[1],camPos[2]); m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraDistance(150); //m_instancingRenderer->setCameraYaw(85); - m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraYaw(30); - m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraPitch(225); + m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraYaw(225); + m_guiHelper->getRenderInterface()->getActiveCamera()->setCameraPitch(-30); m_guiHelper->getRenderInterface()->updateCamera(1);//>updateCamera(); @@ -657,4 +657,4 @@ int GpuTetraScene::createDynamicsObjects() class CommonExampleInterface* OpenCLBoxBoxCreateFunc(struct CommonExampleOptions& options) { return new GpuBoxPlaneScene(options.m_guiHelper); -} \ No newline at end of file +} diff --git a/examples/OpenCL/rigidbody/GpuRigidBodyDemo.cpp b/examples/OpenCL/rigidbody/GpuRigidBodyDemo.cpp index 79504f331..004866850 100644 --- a/examples/OpenCL/rigidbody/GpuRigidBodyDemo.cpp +++ b/examples/OpenCL/rigidbody/GpuRigidBodyDemo.cpp @@ -86,10 +86,10 @@ m_window(0) void GpuRigidBodyDemo::resetCamera() { float dist = 114; - float pitch = 52; - float yaw = 35; + float pitch = -35; + float yaw = 52; 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() diff --git a/examples/OpenGLWindow/SimpleCamera.cpp b/examples/OpenGLWindow/SimpleCamera.cpp index 697f7ce65..62c48872b 100644 --- a/examples/OpenGLWindow/SimpleCamera.cpp +++ b/examples/OpenGLWindow/SimpleCamera.cpp @@ -205,7 +205,11 @@ int SimpleCamera::getCameraUpAxis() const 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); switch (m_data->m_cameraUpAxis) { @@ -213,11 +217,13 @@ void SimpleCamera::update() forwardAxis = 2; m_data->m_cameraUp = b3MakeVector3(0,1,0); //gLightPos = b3MakeVector3(-50.f,100,30); + eyeRot.setEulerZYX(rollRad, yawRad, -pitchRad); break; case 2: forwardAxis = 1; m_data->m_cameraUp = b3MakeVector3(0,0,1); //gLightPos = b3MakeVector3(-50.f,30,100); + eyeRot.setEulerZYX(yawRad, rollRad, pitchRad); break; default: { @@ -238,19 +244,7 @@ void SimpleCamera::update() m_data->m_cameraForward.normalize(); } - -// 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; + eyePos = b3Matrix3x3(eyeRot)*eyePos; m_data->m_cameraPosition = eyePos; m_data->m_cameraPosition+= m_data->m_cameraTargetPosition; diff --git a/examples/Planar2D/Planar2D.cpp b/examples/Planar2D/Planar2D.cpp index c9fa4959f..5b2c0eac8 100644 --- a/examples/Planar2D/Planar2D.cpp +++ b/examples/Planar2D/Planar2D.cpp @@ -96,10 +96,10 @@ class Planar2D : public CommonRigidBodyBase void resetCamera() { float dist = 9; - float pitch = 539; - float yaw = 11; + float pitch = -11; + float yaw = 539; 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]); } diff --git a/examples/Raycast/RaytestDemo.cpp b/examples/Raycast/RaytestDemo.cpp index 5bf458d7e..9ba1b74d8 100644 --- a/examples/Raycast/RaytestDemo.cpp +++ b/examples/Raycast/RaytestDemo.cpp @@ -55,10 +55,10 @@ public: virtual void resetCamera() { float dist = 18; - float pitch = 129; - float yaw = 30; + float pitch = -30; + float yaw = 129; 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]); } }; diff --git a/examples/RenderingExamples/CoordinateSystemDemo.cpp b/examples/RenderingExamples/CoordinateSystemDemo.cpp index 7f35af853..148db5674 100644 --- a/examples/RenderingExamples/CoordinateSystemDemo.cpp +++ b/examples/RenderingExamples/CoordinateSystemDemo.cpp @@ -143,8 +143,8 @@ public: virtual void resetCamera() { float dist = 3.5; - float pitch = 136; - float yaw = 32; + float pitch = -32; + float yaw = 136; float targetPos[3]={0,0,0}; if (m_app->m_renderer && m_app->m_renderer->getActiveCamera()) { diff --git a/examples/RenderingExamples/DynamicTexturedCubeDemo.cpp b/examples/RenderingExamples/DynamicTexturedCubeDemo.cpp index 607541b7f..44d005f18 100644 --- a/examples/RenderingExamples/DynamicTexturedCubeDemo.cpp +++ b/examples/RenderingExamples/DynamicTexturedCubeDemo.cpp @@ -121,8 +121,8 @@ public: virtual void resetCamera() { float dist = 1.15; - float pitch = 396; - float yaw = 33.7; + float pitch = -33.7; + float yaw = 396; float targetPos[3]={-0.5,0.7,1.45}; if (m_app->m_renderer && m_app->m_renderer->getActiveCamera()) { diff --git a/examples/RenderingExamples/RenderInstancingDemo.cpp b/examples/RenderingExamples/RenderInstancingDemo.cpp index aa0d40f2b..069ac46bb 100644 --- a/examples/RenderingExamples/RenderInstancingDemo.cpp +++ b/examples/RenderingExamples/RenderInstancingDemo.cpp @@ -128,8 +128,8 @@ public: virtual void resetCamera() { float dist = 13; - float pitch = 50; - float yaw = 13; + float pitch = -13; + float yaw = 50; float targetPos[3]={-1,0,-0.3}; if (m_app->m_renderer && m_app->m_renderer->getActiveCamera()) { diff --git a/examples/RenderingExamples/TinyRendererSetup.cpp b/examples/RenderingExamples/TinyRendererSetup.cpp index 0a3025a63..80584c9a8 100644 --- a/examples/RenderingExamples/TinyRendererSetup.cpp +++ b/examples/RenderingExamples/TinyRendererSetup.cpp @@ -137,10 +137,10 @@ struct TinyRendererSetup : public CommonExampleInterface void resetCamera() { float dist = 11; - float pitch = 52; - float yaw = 35; + float pitch = -35; + float yaw = 52; 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]); } }; diff --git a/examples/RigidBody/RigidBodySoftContact.cpp b/examples/RigidBody/RigidBodySoftContact.cpp index f44c8a987..2d2cf1fc3 100644 --- a/examples/RigidBody/RigidBodySoftContact.cpp +++ b/examples/RigidBody/RigidBodySoftContact.cpp @@ -47,10 +47,10 @@ struct RigidBodySoftContact : public CommonRigidBodyBase void resetCamera() { float dist = 3; - float pitch = 52; - float yaw = 35; + float pitch = -35; + float yaw = 52; 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]); } }; diff --git a/examples/RoboticsLearning/GripperGraspExample.cpp b/examples/RoboticsLearning/GripperGraspExample.cpp index a01993c93..075185d61 100644 --- a/examples/RoboticsLearning/GripperGraspExample.cpp +++ b/examples/RoboticsLearning/GripperGraspExample.cpp @@ -496,8 +496,8 @@ public: virtual void resetCamera() { float dist = 1.5; - float pitch = 18; - float yaw = 10; + float pitch = -10; + float yaw = 18; float targetPos[3]={-0.2,0.8,0.3}; if (m_app->m_renderer && m_app->m_renderer->getActiveCamera()) { diff --git a/examples/RoboticsLearning/KukaGraspExample.cpp b/examples/RoboticsLearning/KukaGraspExample.cpp index abb3005d1..1bf00785d 100644 --- a/examples/RoboticsLearning/KukaGraspExample.cpp +++ b/examples/RoboticsLearning/KukaGraspExample.cpp @@ -283,8 +283,8 @@ public: virtual void resetCamera() { float dist = 3; - float pitch = 0; - float yaw = 30; + float pitch = -30; + float yaw = 0; float targetPos[3]={-0.2,0.8,0.3}; if (m_app->m_renderer && m_app->m_renderer->getActiveCamera()) { diff --git a/examples/RoboticsLearning/R2D2GraspExample.cpp b/examples/RoboticsLearning/R2D2GraspExample.cpp index ad14ceec5..d5896ab4e 100644 --- a/examples/RoboticsLearning/R2D2GraspExample.cpp +++ b/examples/RoboticsLearning/R2D2GraspExample.cpp @@ -188,8 +188,8 @@ public: virtual void resetCamera() { float dist = 3; - float pitch = -75; - float yaw = 30; + float pitch = -30; + float yaw = -75; float targetPos[3]={-0.2,0.8,0.3}; if (m_app->m_renderer && m_app->m_renderer->getActiveCamera()) { diff --git a/examples/RollingFrictionDemo/RollingFrictionDemo.cpp b/examples/RollingFrictionDemo/RollingFrictionDemo.cpp index 65a2404d3..be837ab5a 100644 --- a/examples/RollingFrictionDemo/RollingFrictionDemo.cpp +++ b/examples/RollingFrictionDemo/RollingFrictionDemo.cpp @@ -59,10 +59,10 @@ public: void resetCamera() { float dist = 35; - float pitch = 0; - float yaw = 14; + float pitch = -14; + float yaw = 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]); } }; diff --git a/examples/SharedMemory/PhysicsClientC_API.cpp b/examples/SharedMemory/PhysicsClientC_API.cpp index d438a906f..b4f5c0a9d 100644 --- a/examples/SharedMemory/PhysicsClientC_API.cpp +++ b/examples/SharedMemory/PhysicsClientC_API.cpp @@ -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; diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h index 6dfe21718..bcb8d06f0 100644 --- a/examples/SharedMemory/PhysicsClientC_API.h +++ b/examples/SharedMemory/PhysicsClientC_API.h @@ -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]); diff --git a/examples/SharedMemory/PhysicsClientExample.cpp b/examples/SharedMemory/PhysicsClientExample.cpp index 0a3bc706c..7aa501b58 100644 --- a/examples/SharedMemory/PhysicsClientExample.cpp +++ b/examples/SharedMemory/PhysicsClientExample.cpp @@ -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]; diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 02635029e..d1e3d4ddc 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -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]); diff --git a/examples/SharedMemory/PhysicsServerExample.cpp b/examples/SharedMemory/PhysicsServerExample.cpp index 772dbd6d4..a372d6600 100644 --- a/examples/SharedMemory/PhysicsServerExample.cpp +++ b/examples/SharedMemory/PhysicsServerExample.cpp @@ -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(); diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp index 8c03556cf..a9bcd3256 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.cpp @@ -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); diff --git a/examples/SharedMemory/TinyRendererVisualShapeConverter.h b/examples/SharedMemory/TinyRendererVisualShapeConverter.h index 6771dc624..9af426fda 100644 --- a/examples/SharedMemory/TinyRendererVisualShapeConverter.h +++ b/examples/SharedMemory/TinyRendererVisualShapeConverter.h @@ -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); diff --git a/examples/SoftDemo/SoftDemo.cpp b/examples/SoftDemo/SoftDemo.cpp index 5e3fe7feb..c1e58dfd7 100644 --- a/examples/SoftDemo/SoftDemo.cpp +++ b/examples/SoftDemo/SoftDemo.cpp @@ -107,10 +107,10 @@ public: { //@todo depends on current_demo? float dist = 45; - float pitch = 27; - float yaw = 31; + float pitch = -31; + float yaw = 27; 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) diff --git a/examples/Tutorial/Dof6ConstraintTutorial.cpp b/examples/Tutorial/Dof6ConstraintTutorial.cpp index 7e3cfcf64..125fd4e61 100644 --- a/examples/Tutorial/Dof6ConstraintTutorial.cpp +++ b/examples/Tutorial/Dof6ConstraintTutorial.cpp @@ -56,10 +56,10 @@ struct Dof6ConstraintTutorial : public CommonRigidBodyBase virtual void resetCamera() { float dist = 5; - float pitch = 722; - float yaw = 35; + float pitch = -35; + float yaw = 722; 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]); } }; diff --git a/examples/Tutorial/Tutorial.cpp b/examples/Tutorial/Tutorial.cpp index 59888e875..f59209a7c 100644 --- a/examples/Tutorial/Tutorial.cpp +++ b/examples/Tutorial/Tutorial.cpp @@ -614,8 +614,8 @@ public: virtual void resetCamera() { float dist = 10.5; - float pitch = 136; - float yaw = 32; + float pitch = -32; + float yaw = 136; float targetPos[3]={0,0,0}; if (m_app->m_renderer && m_app->m_renderer->getActiveCamera()) { diff --git a/examples/Vehicles/Hinge2Vehicle.cpp b/examples/Vehicles/Hinge2Vehicle.cpp index 6ea9a179a..a7ecb07af 100644 --- a/examples/Vehicles/Hinge2Vehicle.cpp +++ b/examples/Vehicles/Hinge2Vehicle.cpp @@ -121,10 +121,10 @@ class Hinge2Vehicle : public CommonRigidBodyBase virtual void resetCamera() { float dist = 8; - float pitch = -45; - float yaw = 32; + float pitch = -32; + float yaw = -45; 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() diff --git a/examples/VoronoiFracture/VoronoiFractureDemo.cpp b/examples/VoronoiFracture/VoronoiFractureDemo.cpp index e9d097bb4..5e7212919 100644 --- a/examples/VoronoiFracture/VoronoiFractureDemo.cpp +++ b/examples/VoronoiFracture/VoronoiFractureDemo.cpp @@ -108,10 +108,10 @@ class VoronoiFractureDemo : public CommonRigidBodyBase virtual void resetCamera() { float dist = 18; - float pitch = 129; - float yaw = 30; + float pitch = -30; + float yaw = 129; 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]); } diff --git a/examples/pybullet/examples/kuka_with_cube_playback.py b/examples/pybullet/examples/kuka_with_cube_playback.py index f84fbc45c..12fdcebdd 100644 --- a/examples/pybullet/examples/kuka_with_cube_playback.py +++ b/examples/pybullet/examples/kuka_with_cube_playback.py @@ -77,4 +77,4 @@ for record in log: qIndex = jointInfo[3] if qIndex > -1: p.resetJointState(Id,i,record[qIndex-7+17]) - sleep(0.0005) \ No newline at end of file + sleep(0.0005)