Merge branch 'master' of github.com:erwincoumans/bullet3

This commit is contained in:
Erwin Coumans 2020-08-20 09:37:30 -07:00
commit 53483a84fe
2 changed files with 45 additions and 15 deletions

View File

@ -130,6 +130,7 @@ enum MultiThreadedGUIHelperCommunicationEnums
eGUIHelperUpdateShape,
eGUIHelperChangeGraphicsInstanceScaling,
eGUIUserDebugRemoveAllParameters,
eGUIHelperResetCamera,
};
#include <stdio.h>
@ -1086,9 +1087,25 @@ public:
{
m_childGuiHelper->setUpAxis(axis);
}
float m_resetCameraCamDist;
float m_resetCameraYaw;
float m_resetCameraPitch;
float m_resetCameraCamPosX;
float m_resetCameraCamPosY;
float m_resetCameraCamPosZ;
virtual void resetCamera(float camDist, float yaw, float pitch, float camPosX, float camPosY, float camPosZ)
{
m_childGuiHelper->resetCamera(camDist, yaw, pitch, camPosX, camPosY, camPosZ);
m_cs->lock();
m_resetCameraCamDist = camDist;
m_resetCameraYaw = yaw;
m_resetCameraPitch = pitch;
m_resetCameraCamPosX = camPosX;
m_resetCameraCamPosY = camPosY;
m_resetCameraCamPosZ = camPosZ;
m_cs->setSharedParam(1, eGUIHelperResetCamera);
workerThreadWait();
//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], float* yaw, float* pitch, float* camDist, float camTarget[3]) const
@ -1424,7 +1441,7 @@ public:
float pitch = -35;
float yaw = 50;
float targetPos[3] = {0, 0, 0}; //-3,2.8,-2.5};
m_guiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]);
m_multiThreadedHelper->m_childGuiHelper->resetCamera(dist, yaw, pitch, targetPos[0], targetPos[1], targetPos[2]);
}
virtual bool wantsTermination();
@ -2360,6 +2377,19 @@ void PhysicsServerExample::updateGraphics()
m_multiThreadedHelper->mainThreadRelease();
break;
}
case eGUIHelperResetCamera:
{
m_multiThreadedHelper->m_childGuiHelper->resetCamera(
m_multiThreadedHelper->m_resetCameraCamDist,
m_multiThreadedHelper->m_resetCameraYaw,
m_multiThreadedHelper->m_resetCameraPitch,
m_multiThreadedHelper->m_resetCameraCamPosX,
m_multiThreadedHelper->m_resetCameraCamPosY,
m_multiThreadedHelper->m_resetCameraCamPosZ);
m_multiThreadedHelper->mainThreadRelease();
break;
}
case eGUIHelperAutogenerateGraphicsObjects:
{
B3_PROFILE("eGUIHelperAutogenerateGraphicsObjects");

View File

@ -7,7 +7,7 @@
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="13.715"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
<inertia ixx="0.22" ixy="0" ixz="0" iyy="0.431" iyz="0" izz="0.565"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz=" 0 0 0"/>
@ -32,7 +32,7 @@
<inertial>
<origin rpy="0 0 0" xyz="0.02 0 0"/>
<mass value="1.095"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
<inertia ixx="0.002" ixy="0" ixz="0" iyy=".002" iyz="0" izz=".001"/>
</inertial>
<visual>
@ -67,7 +67,7 @@
<inertial>
<origin rpy="0 0 0" xyz="0 -0.04 -0.04"/>
<mass value="1.527"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
<inertia ixx="0.015" ixy="0" ixz="0" iyy="0.007" iyz="0" izz="0.01"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
@ -102,7 +102,7 @@
<inertial>
<origin rpy="0 0 0" xyz="0 -0.16 -0.02"/>
<mass value="0.241"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
<inertia ixx="0.002" ixy="0" ixz="0" iyy="0.002" iyz="0" izz="0.002"/>
</inertial>
<visual>
<origin rpy="0 1.57079 0" xyz="0 0.0 0"/>
@ -137,7 +137,7 @@
<inertial>
<origin rpy="0 0 0" xyz="-.02 0 0"/>
<mass value="1.095"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
<inertia ixx="0.002" ixy="0" ixz="0" iyy="0.002" iyz="0" izz="0.001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
@ -174,7 +174,7 @@
<inertial>
<origin rpy="0 0 0" xyz="0 -0.04 -0.04"/>
<mass value="1.527"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
<inertia ixx="0.016" ixy="0" ixz="0" iyy="0.007" iyz="0" izz="0.011"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
@ -213,7 +213,7 @@
<inertial>
<origin rpy="0 0 0" xyz="0 -0.16 -0.02"/>
<mass value="0.241"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
<inertia ixx="0.002" ixy="0" ixz="0" iyy="0.002" iyz="0" izz="0.002"/>
</inertial>
<visual>
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
@ -254,7 +254,7 @@
<inertial>
<origin rpy="0 0 0" xyz="0.02 0 0"/>
<mass value="1.095"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
<inertia ixx="0.002" ixy="0" ixz="0" iyy="0.002" iyz="0" izz="0.001"/>
</inertial>
<visual>
@ -291,7 +291,7 @@
<inertial>
<origin rpy="0 0 0" xyz="0 -0.04 -0.04"/>
<mass value="1.527"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
<inertia ixx="0.016" ixy="0" ixz="0" iyy="0.007" iyz="0" izz="0.011"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
@ -326,7 +326,7 @@
<inertial>
<origin rpy="0 0 0" xyz="0 -0.16 -0.02"/>
<mass value="0.241"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
<inertia ixx="0.002" ixy="0" ixz="0" iyy="0.002" iyz="0" izz="0.002"/>
</inertial>
<visual>
<origin rpy="0 1.57079 0" xyz="0 0 0"/>
@ -362,7 +362,7 @@
<inertial>
<origin rpy="0 0 0" xyz="-.02 0 0"/>
<mass value="1.095"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
<inertia ixx="0.002" ixy="0" ixz="0" iyy="0.002" iyz="0" izz="0.001"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
@ -398,7 +398,7 @@
<inertial>
<origin rpy="0 0 0" xyz="0 -0.04 -0.04"/>
<mass value="1.527"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
<inertia ixx="0.016" ixy="0" ixz="0" iyy="0.007" iyz="0" izz="0.011"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
@ -435,7 +435,7 @@
<inertial>
<origin rpy="0 0 0" xyz="0 -0.16 -0.02"/>
<mass value="0.241"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
<inertia ixx="0.002" ixy="0" ixz="0" iyy="0.002" iyz="0" izz="0.002"/>
</inertial>
<visual>
<origin rpy="0 1.57079 0" xyz="0 0 0"/>