update tutorial for SIGGRAPH course
allow multiple graphing windows at the same time
This commit is contained in:
Binary file not shown.
@@ -4,4 +4,4 @@ Ka 0.2 0.2 0.2
|
|||||||
Ks 0.2 0.2 0.2
|
Ks 0.2 0.2 0.2
|
||||||
Ns 16
|
Ns 16
|
||||||
Tr 0
|
Tr 0
|
||||||
map_Kd uvmap.png
|
map_Kd bullet_logo.png
|
||||||
|
|||||||
@@ -119,7 +119,7 @@ struct CommonGraphicsApp
|
|||||||
virtual void swapBuffer() = 0;
|
virtual void swapBuffer() = 0;
|
||||||
virtual void drawText( const char* txt, int posX, int posY) = 0;
|
virtual void drawText( const char* txt, int posX, int posY) = 0;
|
||||||
virtual void drawText3D( const char* txt, float posX, float posZY, float posZ, float size)=0;
|
virtual void drawText3D( const char* txt, float posX, float posZY, float posZ, float size)=0;
|
||||||
virtual int registerCubeShape(float halfExtentsX,float halfExtentsY, float halfExtentsZ, int textureIndex = -1)=0;
|
virtual int registerCubeShape(float halfExtentsX,float halfExtentsY, float halfExtentsZ, int textureIndex = -1, float textureScaling = 1)=0;
|
||||||
virtual int registerGraphicsUnitSphereShape(EnumSphereLevelOfDetail lod, int textureId=-1) = 0;
|
virtual int registerGraphicsUnitSphereShape(EnumSphereLevelOfDetail lod, int textureId=-1) = 0;
|
||||||
|
|
||||||
virtual void registerGrid(int xres, int yres, float color0[4], float color1[4])=0;
|
virtual void registerGrid(int xres, int yres, float color0[4], float color1[4])=0;
|
||||||
|
|||||||
@@ -109,8 +109,15 @@ static ExampleEntry gDefaultExamples[]=
|
|||||||
ExampleEntry(1,"Constraint Feedback", "The example shows how to receive joint reaction forces in a btMultiBody. Also the applied impulse is available for a btMultiBodyJointMotor", MultiBodyConstraintFeedbackCreateFunc),
|
ExampleEntry(1,"Constraint Feedback", "The example shows how to receive joint reaction forces in a btMultiBody. Also the applied impulse is available for a btMultiBodyJointMotor", MultiBodyConstraintFeedbackCreateFunc),
|
||||||
ExampleEntry(1,"Inverted Pendulum PD","Keep an inverted pendulum up using open loop PD control", InvertedPendulumPDControlCreateFunc),
|
ExampleEntry(1,"Inverted Pendulum PD","Keep an inverted pendulum up using open loop PD control", InvertedPendulumPDControlCreateFunc),
|
||||||
|
|
||||||
|
|
||||||
ExampleEntry(0,"Tutorial"),
|
ExampleEntry(0,"Tutorial"),
|
||||||
ExampleEntry(1,"Free Rigid Body","(Preliminary work in progress) Free moving rigid body, without external or constraint forces", TutorialCreateFunc,0),
|
ExampleEntry(1,"Constant Velocity","Free moving rigid body, without external or constraint forces", TutorialCreateFunc,TUT_VELOCITY),
|
||||||
|
ExampleEntry(1,"Gravity Acceleration","Motion of a free falling rigid body under constant gravitational acceleration", TutorialCreateFunc,TUT_ACCELERATION),
|
||||||
|
ExampleEntry(1,"Contact Computation","Discrete Collision Detection for sphere-sphere", TutorialCreateFunc,TUT_COLLISION),
|
||||||
|
ExampleEntry(1,"Solve Contact Constraint","Compute and apply the impulses needed to satisfy non-penetrating contact constraints", TutorialCreateFunc,TUT_SOLVE_CONTACT_CONSTRAINT),
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
ExampleEntry(1,"Spring constraint","A rigid body with a spring constraint attached", Dof6ConstraintTutorialCreateFunc,0),
|
ExampleEntry(1,"Spring constraint","A rigid body with a spring constraint attached", Dof6ConstraintTutorialCreateFunc,0),
|
||||||
|
|
||||||
#ifdef INCLUDE_CLOTH_DEMOS
|
#ifdef INCLUDE_CLOTH_DEMOS
|
||||||
|
|||||||
@@ -603,14 +603,18 @@ struct QuickCanvas : public Common2dCanvasInterface
|
|||||||
if (m_curNumGraphWindows<MAX_GRAPH_WINDOWS)
|
if (m_curNumGraphWindows<MAX_GRAPH_WINDOWS)
|
||||||
{
|
{
|
||||||
//find a slot
|
//find a slot
|
||||||
int slot = 0;//hardcoded for now
|
int slot = m_curNumGraphWindows;
|
||||||
|
btAssert(slot<MAX_GRAPH_WINDOWS);
|
||||||
|
if (slot>=MAX_GRAPH_WINDOWS)
|
||||||
|
return 0;//don't crash
|
||||||
|
|
||||||
m_curNumGraphWindows++;
|
m_curNumGraphWindows++;
|
||||||
|
|
||||||
MyGraphInput input(gui->getInternalData());
|
MyGraphInput input(gui->getInternalData());
|
||||||
input.m_width=width;
|
input.m_width=width;
|
||||||
input.m_height=height;
|
input.m_height=height;
|
||||||
input.m_xPos = 300;
|
input.m_xPos = 10000;//GUI will clamp it to the right//300;
|
||||||
input.m_yPos = height-input.m_height;
|
input.m_yPos = 10000;//GUI will clamp it to bottom
|
||||||
input.m_name=canvasName;
|
input.m_name=canvasName;
|
||||||
input.m_texName = canvasName;
|
input.m_texName = canvasName;
|
||||||
m_gt[slot] = new GraphingTexture;
|
m_gt[slot] = new GraphingTexture;
|
||||||
@@ -625,22 +629,21 @@ struct QuickCanvas : public Common2dCanvasInterface
|
|||||||
}
|
}
|
||||||
virtual void destroyCanvas(int canvasId)
|
virtual void destroyCanvas(int canvasId)
|
||||||
{
|
{
|
||||||
btAssert(canvasId==0);//hardcoded to zero for now, only a single canvas
|
btAssert(canvasId>=0);
|
||||||
btAssert(m_curNumGraphWindows==1);
|
|
||||||
destroyTextureWindow(m_gw[canvasId]);
|
destroyTextureWindow(m_gw[canvasId]);
|
||||||
m_curNumGraphWindows--;
|
m_curNumGraphWindows--;
|
||||||
}
|
}
|
||||||
virtual void setPixel(int canvasId, int x, int y, unsigned char red, unsigned char green,unsigned char blue, unsigned char alpha)
|
virtual void setPixel(int canvasId, int x, int y, unsigned char red, unsigned char green,unsigned char blue, unsigned char alpha)
|
||||||
{
|
{
|
||||||
btAssert(canvasId==0);//hardcoded
|
btAssert(canvasId>=0);
|
||||||
btAssert(m_curNumGraphWindows==1);
|
btAssert(canvasId<m_curNumGraphWindows);
|
||||||
m_gt[canvasId]->setPixel(x,y,red,green,blue,alpha);
|
m_gt[canvasId]->setPixel(x,y,red,green,blue,alpha);
|
||||||
}
|
}
|
||||||
|
|
||||||
virtual void getPixel(int canvasId, int x, int y, unsigned char& red, unsigned char& green,unsigned char& blue, unsigned char& alpha)
|
virtual void getPixel(int canvasId, int x, int y, unsigned char& red, unsigned char& green,unsigned char& blue, unsigned char& alpha)
|
||||||
{
|
{
|
||||||
btAssert(canvasId==0);//hardcoded
|
btAssert(canvasId>=0);
|
||||||
btAssert(m_curNumGraphWindows==1);
|
btAssert(canvasId<m_curNumGraphWindows);
|
||||||
m_gt[canvasId]->getPixel(x,y,red,green,blue,alpha);
|
m_gt[canvasId]->getPixel(x,y,red,green,blue,alpha);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -982,7 +985,7 @@ void OpenGLExampleBrowser::update(float deltaTime)
|
|||||||
|
|
||||||
static int skip = 0;
|
static int skip = 0;
|
||||||
skip++;
|
skip++;
|
||||||
if (skip>10)
|
if (skip>4)
|
||||||
{
|
{
|
||||||
skip=0;
|
skip=0;
|
||||||
//printf("gPngFileName=%s\n",gPngFileName);
|
//printf("gPngFileName=%s\n",gPngFileName);
|
||||||
|
|||||||
@@ -1297,7 +1297,7 @@ void GLInstancingRenderer::renderSceneInternal(int renderMode)
|
|||||||
//glDepthFunc(GL_LESS);
|
//glDepthFunc(GL_LESS);
|
||||||
|
|
||||||
// Cull triangles which normal is not towards the camera
|
// Cull triangles which normal is not towards the camera
|
||||||
//glEnable(GL_CULL_FACE);
|
glEnable(GL_CULL_FACE);
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -19,7 +19,7 @@ public:
|
|||||||
virtual void swapBuffer();
|
virtual void swapBuffer();
|
||||||
virtual void drawText( const char* txt, int posX, int posY);
|
virtual void drawText( const char* txt, int posX, int posY);
|
||||||
virtual void setBackgroundColor(float red, float green, float blue);
|
virtual void setBackgroundColor(float red, float green, float blue);
|
||||||
virtual int registerCubeShape(float halfExtentsX,float halfExtentsY, float halfExtentsZ, int textureIndex = -1)
|
virtual int registerCubeShape(float halfExtentsX,float halfExtentsY, float halfExtentsZ, int textureIndex = -1, float textureScaling = 1)
|
||||||
{
|
{
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -421,27 +421,27 @@ struct GfxVertex
|
|||||||
float u,v;
|
float u,v;
|
||||||
};
|
};
|
||||||
|
|
||||||
int SimpleOpenGL3App::registerCubeShape(float halfExtentsX,float halfExtentsY, float halfExtentsZ, int textureIndex)
|
int SimpleOpenGL3App::registerCubeShape(float halfExtentsX,float halfExtentsY, float halfExtentsZ, int textureIndex, float textureScaling)
|
||||||
{
|
{
|
||||||
|
|
||||||
|
|
||||||
int strideInBytes = 9*sizeof(float);
|
int strideInBytes = 9*sizeof(float);
|
||||||
int numVertices = sizeof(cube_vertices)/strideInBytes;
|
int numVertices = sizeof(cube_vertices_textured)/strideInBytes;
|
||||||
int numIndices = sizeof(cube_indices)/sizeof(int);
|
int numIndices = sizeof(cube_indices)/sizeof(int);
|
||||||
|
|
||||||
b3AlignedObjectArray<GfxVertex> verts;
|
b3AlignedObjectArray<GfxVertex> verts;
|
||||||
verts.resize(numVertices);
|
verts.resize(numVertices);
|
||||||
for (int i=0;i<numVertices;i++)
|
for (int i=0;i<numVertices;i++)
|
||||||
{
|
{
|
||||||
verts[i].x = halfExtentsX*cube_vertices[i*9];
|
verts[i].x = halfExtentsX*cube_vertices_textured[i*9];
|
||||||
verts[i].y = halfExtentsY*cube_vertices[i*9+1];
|
verts[i].y = halfExtentsY*cube_vertices_textured[i*9+1];
|
||||||
verts[i].z = halfExtentsZ*cube_vertices[i*9+2];
|
verts[i].z = halfExtentsZ*cube_vertices_textured[i*9+2];
|
||||||
verts[i].w = cube_vertices[i*9+3];
|
verts[i].w = cube_vertices_textured[i*9+3];
|
||||||
verts[i].nx = cube_vertices[i*9+4];
|
verts[i].nx = cube_vertices_textured[i*9+4];
|
||||||
verts[i].ny = cube_vertices[i*9+5];
|
verts[i].ny = cube_vertices_textured[i*9+5];
|
||||||
verts[i].nz = cube_vertices[i*9+6];
|
verts[i].nz = cube_vertices_textured[i*9+6];
|
||||||
verts[i].u = cube_vertices[i*9+7];
|
verts[i].u = cube_vertices_textured[i*9+7]*textureScaling;
|
||||||
verts[i].v = cube_vertices[i*9+8];
|
verts[i].v = cube_vertices_textured[i*9+8]*textureScaling;
|
||||||
}
|
}
|
||||||
|
|
||||||
int shapeId = m_instancingRenderer->registerShape(&verts[0].x,numVertices,cube_indices,numIndices,B3_GL_TRIANGLES,textureIndex);
|
int shapeId = m_instancingRenderer->registerShape(&verts[0].x,numVertices,cube_indices,numIndices,B3_GL_TRIANGLES,textureIndex);
|
||||||
@@ -709,10 +709,10 @@ void SimpleOpenGL3App::swapBuffer()
|
|||||||
(int) m_window->getRetinaScale()*this->m_instancingRenderer->getScreenHeight(),m_data->m_frameDumpPngFileName,
|
(int) m_window->getRetinaScale()*this->m_instancingRenderer->getScreenHeight(),m_data->m_frameDumpPngFileName,
|
||||||
m_data->m_ffmpegFile);
|
m_data->m_ffmpegFile);
|
||||||
m_data->m_renderTexture->disable();
|
m_data->m_renderTexture->disable();
|
||||||
//if (m_data->m_ffmpegFile==0)
|
if (m_data->m_ffmpegFile==0)
|
||||||
//{
|
{
|
||||||
m_data->m_frameDumpPngFileName = 0;
|
m_data->m_frameDumpPngFileName = 0;
|
||||||
//}
|
}
|
||||||
}
|
}
|
||||||
m_window->startRendering();
|
m_window->startRendering();
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -19,7 +19,7 @@ struct SimpleOpenGL3App : public CommonGraphicsApp
|
|||||||
SimpleOpenGL3App(const char* title, int width,int height, bool allowRetina);
|
SimpleOpenGL3App(const char* title, int width,int height, bool allowRetina);
|
||||||
virtual ~SimpleOpenGL3App();
|
virtual ~SimpleOpenGL3App();
|
||||||
|
|
||||||
virtual int registerCubeShape(float halfExtentsX=1.f,float halfExtentsY=1.f, float halfExtentsZ = 1.f, int textureIndex = -1);
|
virtual int registerCubeShape(float halfExtentsX=1.f,float halfExtentsY=1.f, float halfExtentsZ = 1.f, int textureIndex = -1, float textureScaling = 1);
|
||||||
virtual int registerGraphicsUnitSphereShape(EnumSphereLevelOfDetail lod, int textureId=-1);
|
virtual int registerGraphicsUnitSphereShape(EnumSphereLevelOfDetail lod, int textureId=-1);
|
||||||
virtual void registerGrid(int xres, int yres, float color0[4], float color1[4]);
|
virtual void registerGrid(int xres, int yres, float color0[4], float color1[4]);
|
||||||
void dumpNextFrameToPng(const char* pngFilename);
|
void dumpNextFrameToPng(const char* pngFilename);
|
||||||
|
|||||||
@@ -268,8 +268,8 @@ void TimeSeriesCanvas::shift1PixelToLeft()
|
|||||||
{
|
{
|
||||||
char buf[1024];
|
char buf[1024];
|
||||||
float time = m_internalData->getTime();
|
float time = m_internalData->getTime();
|
||||||
sprintf(buf,"%3.2f",time);
|
sprintf(buf,"%2.0f",time);
|
||||||
grapicalPrintf(buf, sTimeSeriesFontData, m_internalData->m_width-53,m_internalData->m_zero+3,0,0,0,255);
|
grapicalPrintf(buf, sTimeSeriesFontData, m_internalData->m_width-25,m_internalData->m_zero+3,0,0,0,255);
|
||||||
|
|
||||||
m_internalData->m_bar=m_internalData->m_ticksPerSecond;
|
m_internalData->m_bar=m_internalData->m_ticksPerSecond;
|
||||||
|
|
||||||
|
|||||||
@@ -9,52 +9,182 @@
|
|||||||
#include "../CommonInterfaces/CommonGUIHelperInterface.h"
|
#include "../CommonInterfaces/CommonGUIHelperInterface.h"
|
||||||
#include "../RenderingExamples/TimeSeriesCanvas.h"
|
#include "../RenderingExamples/TimeSeriesCanvas.h"
|
||||||
#include "stb_image/stb_image.h"
|
#include "stb_image/stb_image.h"
|
||||||
|
#include "Bullet3Common/b3Quaternion.h"
|
||||||
|
#include "Bullet3Common/b3Matrix3x3.h"
|
||||||
|
#include "../CommonInterfaces/CommonParameterInterface.h"
|
||||||
|
|
||||||
|
#include "LinearMath/btAlignedObjectArray.h"
|
||||||
|
#define stdvector btAlignedObjectArray
|
||||||
|
|
||||||
|
#define SPHERE_RADIUS 1
|
||||||
|
static btScalar gRestitution = 0.f;
|
||||||
|
static btScalar gMassA = 1.f;
|
||||||
|
static btScalar gMassB = 0.f;
|
||||||
|
|
||||||
|
enum LWEnumCollisionTypes
|
||||||
|
{
|
||||||
|
LW_PLANE_TYPE,
|
||||||
|
LW_SPHERE_TYPE,
|
||||||
|
LW_BOX_TYPE
|
||||||
|
};
|
||||||
|
|
||||||
|
struct LWPlane
|
||||||
|
{
|
||||||
|
b3Vector3 m_normal;
|
||||||
|
btScalar m_planeConstant;
|
||||||
|
};
|
||||||
|
|
||||||
|
struct LWSphere
|
||||||
|
{
|
||||||
|
btScalar m_radius;
|
||||||
|
|
||||||
|
void computeLocalInertia(b3Scalar mass, b3Vector3& localInertia)
|
||||||
|
{
|
||||||
|
btScalar elem = b3Scalar(0.4) * mass * m_radius*m_radius;
|
||||||
|
localInertia.setValue(elem,elem,elem);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
struct LWBox
|
||||||
|
{
|
||||||
|
b3Vector3 m_halfExtents;
|
||||||
|
};
|
||||||
|
|
||||||
|
struct LWCollisionShape
|
||||||
|
{
|
||||||
|
LWEnumCollisionTypes m_type;
|
||||||
|
union
|
||||||
|
{
|
||||||
|
LWPlane m_plane;
|
||||||
|
LWSphere m_sphere;
|
||||||
|
LWBox m_box;
|
||||||
|
};
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
struct LWPose
|
struct LWPose
|
||||||
{
|
{
|
||||||
btVector3 m_worldPosition;
|
b3Vector3 m_position;
|
||||||
btQuaternion m_worldOrientation;
|
b3Quaternion m_orientation;
|
||||||
LWPose()
|
LWPose()
|
||||||
:m_worldPosition(0,0,0),
|
:m_position(b3MakeVector3(0,0,0)),
|
||||||
m_worldOrientation(0,0,0,1)
|
m_orientation(0,0,0,1)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
|
b3Vector3 transformPoint(const b3Vector3& pointIn)
|
||||||
|
{
|
||||||
|
b3Vector3 rotPoint = b3QuatRotate(m_orientation,pointIn);
|
||||||
|
return rotPoint+m_position;
|
||||||
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
struct LWContactPoint
|
||||||
|
{
|
||||||
|
b3Vector3 m_ptOnAWorld;
|
||||||
|
b3Vector3 m_ptOnBWorld;
|
||||||
|
b3Vector3 m_normalOnB;
|
||||||
|
btScalar m_distance;
|
||||||
|
};
|
||||||
|
|
||||||
|
///returns true if we found a pair of closest points
|
||||||
|
void ComputeClosestPointsPlaneSphere(const LWPlane& planeWorld, const LWSphere& sphere, const LWPose& spherePose, LWContactPoint& pointOut) {
|
||||||
|
b3Vector3 spherePosWorld = spherePose.m_position;
|
||||||
|
btScalar t = -(spherePosWorld.dot(-planeWorld.m_normal)+planeWorld.m_planeConstant);
|
||||||
|
b3Vector3 intersectionPoint = spherePosWorld+t*-planeWorld.m_normal;
|
||||||
|
b3Scalar distance = t-sphere.m_radius;
|
||||||
|
pointOut.m_distance = distance;
|
||||||
|
pointOut.m_ptOnBWorld = intersectionPoint;
|
||||||
|
pointOut.m_ptOnAWorld = spherePosWorld+sphere.m_radius*-planeWorld.m_normal;
|
||||||
|
pointOut.m_normalOnB = planeWorld.m_normal;
|
||||||
|
}
|
||||||
|
|
||||||
|
void ComputeClosestPointsSphereSphere(const LWSphere& sphereA, const LWPose& sphereAPose, const LWSphere& sphereB, const LWPose& sphereBPose, LWContactPoint& pointOut) {
|
||||||
|
b3Vector3 diff = sphereAPose.m_position-sphereBPose.m_position;
|
||||||
|
btScalar len = diff.length();
|
||||||
|
pointOut.m_distance = len - (sphereA.m_radius+sphereB.m_radius);
|
||||||
|
pointOut.m_normalOnB = b3MakeVector3(1,0,0);
|
||||||
|
if (len > B3_EPSILON) {
|
||||||
|
pointOut.m_normalOnB = diff / len;
|
||||||
|
}
|
||||||
|
pointOut.m_ptOnAWorld = sphereAPose.m_position - sphereA.m_radius*pointOut.m_normalOnB;
|
||||||
|
pointOut.m_ptOnBWorld = pointOut.m_ptOnAWorld-pointOut.m_normalOnB*pointOut.m_distance;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
enum LWRIGIDBODY_FLAGS
|
enum LWRIGIDBODY_FLAGS
|
||||||
{
|
{
|
||||||
LWFLAG_USE_QUATERNION_DERIVATIVE = 1,
|
LWFLAG_USE_QUATERNION_DERIVATIVE = 1,
|
||||||
|
|
||||||
};
|
};
|
||||||
struct LWRightBody
|
struct LWRigidBody
|
||||||
{
|
{
|
||||||
LWPose m_worldPose;
|
LWPose m_worldPose;
|
||||||
btVector3 m_linearVelocity;
|
b3Vector3 m_linearVelocity;
|
||||||
btVector3 m_angularVelocity;
|
b3Vector3 m_angularVelocity;
|
||||||
|
b3Vector3 m_gravityAcceleration;
|
||||||
|
b3Vector3 m_localInertia;
|
||||||
|
b3Scalar m_invMass;
|
||||||
|
|
||||||
|
b3Matrix3x3 m_invInertiaTensorWorld;
|
||||||
|
|
||||||
|
void computeInvInertiaTensorWorld()
|
||||||
|
{
|
||||||
|
b3Vector3 invInertiaLocal;
|
||||||
|
invInertiaLocal.setValue(m_localInertia.x != btScalar(0.0) ? btScalar(1.0) / m_localInertia.x: btScalar(0.0),
|
||||||
|
m_localInertia.y != btScalar(0.0) ? btScalar(1.0) / m_localInertia.y: btScalar(0.0),
|
||||||
|
m_localInertia.z != btScalar(0.0) ? btScalar(1.0) / m_localInertia.z: btScalar(0.0));
|
||||||
|
b3Matrix3x3 m (m_worldPose.m_orientation);
|
||||||
|
m_invInertiaTensorWorld = m.scaled(invInertiaLocal) * m.transpose();
|
||||||
|
}
|
||||||
|
|
||||||
int m_graphicsIndex;
|
int m_graphicsIndex;
|
||||||
int m_flags;
|
LWCollisionShape m_collisionShape;
|
||||||
|
|
||||||
LWRightBody()
|
|
||||||
:m_linearVelocity(0,0,0),
|
LWRIGIDBODY_FLAGS m_flags;
|
||||||
m_angularVelocity(0,0,0),
|
|
||||||
|
LWRigidBody()
|
||||||
|
:m_linearVelocity(b3MakeVector3(0,0,0)),
|
||||||
|
m_angularVelocity(b3MakeVector3(0,0,0)),
|
||||||
|
m_gravityAcceleration(b3MakeVector3(0,0,0)),//-10,0)),
|
||||||
m_flags(LWFLAG_USE_QUATERNION_DERIVATIVE)
|
m_flags(LWFLAG_USE_QUATERNION_DERIVATIVE)
|
||||||
{
|
{
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void integrateTransform(double deltaTime)
|
const b3Vector3& getPosition() const
|
||||||
|
{
|
||||||
|
return m_worldPose.m_position;
|
||||||
|
}
|
||||||
|
|
||||||
|
b3Vector3 getVelocity(const b3Vector3& relPos) const
|
||||||
|
{
|
||||||
|
return m_linearVelocity + m_angularVelocity.cross(relPos);
|
||||||
|
}
|
||||||
|
|
||||||
|
void integrateAcceleration(double deltaTime) {
|
||||||
|
m_linearVelocity += m_gravityAcceleration*deltaTime;
|
||||||
|
}
|
||||||
|
|
||||||
|
void applyImpulse(const b3Vector3& impulse, const b3Vector3& rel_pos)
|
||||||
|
{
|
||||||
|
m_linearVelocity += impulse * m_invMass;
|
||||||
|
b3Vector3 torqueImpulse = rel_pos.cross(impulse);
|
||||||
|
m_angularVelocity += m_invInertiaTensorWorld * torqueImpulse;
|
||||||
|
}
|
||||||
|
|
||||||
|
void integrateVelocity(double deltaTime)
|
||||||
{
|
{
|
||||||
LWPose newPose;
|
LWPose newPose;
|
||||||
|
|
||||||
newPose.m_worldPosition = m_worldPose.m_worldPosition + m_linearVelocity*deltaTime;
|
newPose.m_position = m_worldPose.m_position + m_linearVelocity*deltaTime;
|
||||||
|
|
||||||
if (m_flags & LWFLAG_USE_QUATERNION_DERIVATIVE)
|
if (m_flags & LWFLAG_USE_QUATERNION_DERIVATIVE)
|
||||||
{
|
{
|
||||||
newPose.m_worldOrientation = m_worldPose.m_worldOrientation;
|
newPose.m_orientation = m_worldPose.m_orientation;
|
||||||
newPose.m_worldOrientation += (m_angularVelocity * newPose.m_worldOrientation) * (deltaTime * btScalar(0.5));
|
newPose.m_orientation += (m_angularVelocity * newPose.m_orientation) * (deltaTime * btScalar(0.5));
|
||||||
newPose.m_worldOrientation.normalize();
|
newPose.m_orientation.normalize();
|
||||||
m_worldPose = newPose;
|
m_worldPose = newPose;
|
||||||
} else
|
} else
|
||||||
{
|
{
|
||||||
@@ -64,8 +194,8 @@ struct LWRightBody
|
|||||||
//btQuaternion q_w = [ sin(|w|*dt/2) * w/|w| , cos(|w|*dt/2)]
|
//btQuaternion q_w = [ sin(|w|*dt/2) * w/|w| , cos(|w|*dt/2)]
|
||||||
//btQuaternion q_new = q_w * q_old;
|
//btQuaternion q_new = q_w * q_old;
|
||||||
|
|
||||||
btVector3 axis;
|
b3Vector3 axis;
|
||||||
btScalar fAngle = m_angularVelocity.length();
|
b3Scalar fAngle = m_angularVelocity.length();
|
||||||
//limit the angular motion
|
//limit the angular motion
|
||||||
const btScalar angularMotionThreshold = btScalar(0.5)*SIMD_HALF_PI;
|
const btScalar angularMotionThreshold = btScalar(0.5)*SIMD_HALF_PI;
|
||||||
|
|
||||||
@@ -84,12 +214,12 @@ struct LWRightBody
|
|||||||
// sync(fAngle) = sin(c*fAngle)/t
|
// sync(fAngle) = sin(c*fAngle)/t
|
||||||
axis = m_angularVelocity*( btSin(btScalar(0.5)*fAngle*deltaTime)/fAngle );
|
axis = m_angularVelocity*( btSin(btScalar(0.5)*fAngle*deltaTime)/fAngle );
|
||||||
}
|
}
|
||||||
btQuaternion dorn (axis.x(),axis.y(),axis.z(),btCos( fAngle*deltaTime*btScalar(0.5) ));
|
b3Quaternion dorn (axis.x,axis.y,axis.z,btCos( fAngle*deltaTime*b3Scalar(0.5) ));
|
||||||
btQuaternion orn0 = m_worldPose.m_worldOrientation;
|
b3Quaternion orn0 = m_worldPose.m_orientation;
|
||||||
|
|
||||||
btQuaternion predictedOrn = dorn * orn0;
|
b3Quaternion predictedOrn = dorn * orn0;
|
||||||
predictedOrn.normalize();
|
predictedOrn.normalize();
|
||||||
m_worldPose.m_worldOrientation = predictedOrn;
|
m_worldPose.m_orientation = predictedOrn;
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
@@ -97,54 +227,170 @@ struct LWRightBody
|
|||||||
|
|
||||||
void stepSimulation(double deltaTime)
|
void stepSimulation(double deltaTime)
|
||||||
{
|
{
|
||||||
integrateTransform(deltaTime);
|
integrateVelocity(deltaTime);
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
b3Scalar resolveCollision(LWRigidBody& bodyA,
|
||||||
|
LWRigidBody& bodyB,
|
||||||
|
LWContactPoint& contactPoint)
|
||||||
|
{
|
||||||
|
b3Assert(contactPoint.m_distance<=0);
|
||||||
|
|
||||||
|
|
||||||
|
btScalar appliedImpulse = 0.f;
|
||||||
|
|
||||||
|
b3Vector3 rel_pos1 = contactPoint.m_ptOnAWorld - bodyA.m_worldPose.m_position;
|
||||||
|
b3Vector3 rel_pos2 = contactPoint.m_ptOnBWorld - bodyB.getPosition();
|
||||||
|
|
||||||
|
btScalar rel_vel = contactPoint.m_normalOnB.dot(bodyA.getVelocity(rel_pos1) - bodyB.getVelocity(rel_pos2));
|
||||||
|
if (rel_vel < -B3_EPSILON)
|
||||||
|
{
|
||||||
|
b3Vector3 temp1 = bodyA.m_invInertiaTensorWorld * rel_pos1.cross(contactPoint.m_normalOnB);
|
||||||
|
b3Vector3 temp2 = bodyB.m_invInertiaTensorWorld * rel_pos2.cross(contactPoint.m_normalOnB);
|
||||||
|
|
||||||
|
btScalar impulse = -(1.0f + gRestitution) * rel_vel /
|
||||||
|
(bodyA.m_invMass + bodyB.m_invMass + contactPoint.m_normalOnB.dot(temp1.cross(rel_pos1) + temp2.cross(rel_pos2)));
|
||||||
|
|
||||||
|
b3Vector3 impulse_vector = contactPoint.m_normalOnB * impulse;
|
||||||
|
b3Printf("impulse = %f\n", impulse);
|
||||||
|
appliedImpulse = impulse;
|
||||||
|
bodyA.applyImpulse(impulse_vector, rel_pos1);
|
||||||
|
bodyB.applyImpulse(-impulse_vector, rel_pos2);
|
||||||
|
}
|
||||||
|
return appliedImpulse;
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
class Tutorial : public CommonExampleInterface
|
class Tutorial : public CommonExampleInterface
|
||||||
{
|
{
|
||||||
CommonGraphicsApp* m_app;
|
CommonGraphicsApp* m_app;
|
||||||
|
GUIHelperInterface* m_guiHelper;
|
||||||
int m_tutorialIndex;
|
int m_tutorialIndex;
|
||||||
|
|
||||||
LWRightBody* m_body;
|
stdvector<LWRigidBody*> m_bodies;
|
||||||
|
|
||||||
TimeSeriesCanvas* m_timeSeriesCanvas;
|
TimeSeriesCanvas* m_timeSeriesCanvas0;
|
||||||
|
TimeSeriesCanvas* m_timeSeriesCanvas1;
|
||||||
|
|
||||||
|
stdvector<LWContactPoint> m_contactPoints;
|
||||||
|
|
||||||
|
int m_stage;
|
||||||
|
int m_counter;
|
||||||
public:
|
public:
|
||||||
|
|
||||||
Tutorial(CommonGraphicsApp* app, int tutorialIndex)
|
Tutorial(GUIHelperInterface* guiHelper, int tutorialIndex)
|
||||||
:m_app(app),
|
:m_app(guiHelper->getAppInterface()),
|
||||||
m_tutorialIndex(tutorialIndex)
|
m_guiHelper(guiHelper),
|
||||||
|
m_tutorialIndex(tutorialIndex),
|
||||||
|
m_stage(0),
|
||||||
|
m_counter(0),
|
||||||
|
m_timeSeriesCanvas0(0),
|
||||||
|
m_timeSeriesCanvas1(0)
|
||||||
{
|
{
|
||||||
m_app->setUpAxis(2);
|
int numBodies = 1;
|
||||||
|
|
||||||
m_timeSeriesCanvas = new TimeSeriesCanvas(app->m_2dCanvasInterface,512,256,"Position and Velocity");
|
|
||||||
m_timeSeriesCanvas ->setupTimeSeries(5,100, 0);
|
|
||||||
m_timeSeriesCanvas->addDataSource("X position (m)", 255,0,0);
|
|
||||||
m_timeSeriesCanvas->addDataSource("X velocity (m/s)", 0,0,255);
|
|
||||||
m_timeSeriesCanvas->addDataSource("dX/dt (m/s)", 0,0,0);
|
|
||||||
|
|
||||||
|
m_app->setUpAxis(1);
|
||||||
|
m_app->m_renderer->enableBlend(true);
|
||||||
|
|
||||||
switch (m_tutorialIndex)
|
switch (m_tutorialIndex)
|
||||||
{
|
{
|
||||||
|
case TUT_VELOCITY:
|
||||||
|
{
|
||||||
|
numBodies=10;
|
||||||
|
m_timeSeriesCanvas0 = new TimeSeriesCanvas(m_app->m_2dCanvasInterface,512,256,"Constant Velocity");
|
||||||
|
|
||||||
|
m_timeSeriesCanvas0 ->setupTimeSeries(2,60, 0);
|
||||||
|
m_timeSeriesCanvas0->addDataSource("X position (m)", 255,0,0);
|
||||||
|
m_timeSeriesCanvas0->addDataSource("X velocity (m/s)", 0,0,255);
|
||||||
|
m_timeSeriesCanvas0->addDataSource("dX/dt (m/s)", 0,0,0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case TUT_ACCELERATION:
|
||||||
|
{
|
||||||
|
numBodies=10;
|
||||||
|
m_timeSeriesCanvas1 = new TimeSeriesCanvas(m_app->m_2dCanvasInterface,256,512,"Constant Acceleration");
|
||||||
|
|
||||||
|
m_timeSeriesCanvas1 ->setupTimeSeries(50,60, 0);
|
||||||
|
m_timeSeriesCanvas1->addDataSource("Y position (m)", 255,0,0);
|
||||||
|
m_timeSeriesCanvas1->addDataSource("Y velocity (m/s)", 0,0,255);
|
||||||
|
m_timeSeriesCanvas1->addDataSource("dY/dt (m/s)", 0,0,0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case TUT_COLLISION:
|
||||||
|
{
|
||||||
|
numBodies=2;
|
||||||
|
m_timeSeriesCanvas1 = new TimeSeriesCanvas(m_app->m_2dCanvasInterface,512,200,"Distance");
|
||||||
|
m_timeSeriesCanvas1 ->setupTimeSeries(1.5,60, 0);
|
||||||
|
m_timeSeriesCanvas1->addDataSource("distance", 255,0,0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
case TUT_SOLVE_CONTACT_CONSTRAINT:
|
||||||
|
{
|
||||||
|
numBodies=2;
|
||||||
|
m_timeSeriesCanvas1 = new TimeSeriesCanvas(m_app->m_2dCanvasInterface,512,200,"Collision Impulse");
|
||||||
|
m_timeSeriesCanvas1 ->setupTimeSeries(1.5,60, 0);
|
||||||
|
m_timeSeriesCanvas1->addDataSource("Distance", 0,0,255);
|
||||||
|
m_timeSeriesCanvas1->addDataSource("Impulse magnutide", 255,0,0);
|
||||||
|
|
||||||
|
{
|
||||||
|
SliderParams slider("Restitution",&gRestitution);
|
||||||
|
slider.m_minVal=0;
|
||||||
|
slider.m_maxVal=1;
|
||||||
|
m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
|
||||||
}
|
}
|
||||||
{
|
{
|
||||||
|
SliderParams slider("Mass A",&gMassA);
|
||||||
|
slider.m_minVal=0;
|
||||||
|
slider.m_maxVal=100;
|
||||||
|
m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
|
||||||
|
}
|
||||||
|
|
||||||
int boxId = m_app->registerCubeShape(100,100,1);
|
{
|
||||||
btVector3 pos(0,0,-1);
|
SliderParams slider("Mass B",&gMassB);
|
||||||
|
slider.m_minVal=0;
|
||||||
|
slider.m_maxVal=100;
|
||||||
|
m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
default:
|
||||||
|
{
|
||||||
|
|
||||||
|
m_timeSeriesCanvas0 = new TimeSeriesCanvas(m_app->m_2dCanvasInterface,512,256,"Unknown");
|
||||||
|
m_timeSeriesCanvas0 ->setupTimeSeries(1,60, 0);
|
||||||
|
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
if (m_tutorialIndex==TUT_VELOCITY)
|
||||||
|
{
|
||||||
|
|
||||||
|
int boxId = m_app->registerCubeShape(100,1,100);
|
||||||
|
b3Vector3 pos = b3MakeVector3(0,-3.5,0);
|
||||||
btQuaternion orn(0,0,0,1);
|
btQuaternion orn(0,0,0,1);
|
||||||
btVector4 color(1,1,1,1);
|
btVector4 color(1,1,1,1);
|
||||||
btVector3 scaling(1,1,1);
|
b3Vector3 scaling = b3MakeVector3(1,1,1);
|
||||||
m_app->m_renderer->registerGraphicsInstance(boxId,pos,orn,color,scaling);
|
m_app->m_renderer->registerGraphicsInstance(boxId,pos,orn,color,scaling);
|
||||||
}
|
}
|
||||||
|
|
||||||
m_body = new LWRightBody();
|
for (int i=0;i<numBodies;i++)
|
||||||
m_body->m_worldPose.m_worldPosition.setValue(0,0,3);
|
{
|
||||||
|
m_bodies.push_back(new LWRigidBody());
|
||||||
|
}
|
||||||
|
for (int i=0;i<m_bodies.size();i++)
|
||||||
|
{
|
||||||
|
m_bodies[i]->m_worldPose.m_position.setValue((i/4)*5,3,(i&3)*5);
|
||||||
|
}
|
||||||
{
|
{
|
||||||
int textureIndex = -1;
|
int textureIndex = -1;
|
||||||
|
|
||||||
@@ -172,19 +418,48 @@ public:
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
int boxId = m_app->registerCubeShape(1,1,1,textureIndex);//>registerGraphicsUnitSphereShape(SPHERE_LOD_HIGH, textureIndex);
|
// int boxId = m_app->registerCubeShape(1,1,1,textureIndex);
|
||||||
btVector4 color(1,1,1,1);
|
int boxId = m_app->registerGraphicsUnitSphereShape(SPHERE_LOD_HIGH, textureIndex);
|
||||||
btVector3 scaling(1,1,1);
|
btVector4 color(1,1,1,0.8);
|
||||||
m_body->m_graphicsIndex = m_app->m_renderer->registerGraphicsInstance(boxId,m_body->m_worldPose.m_worldPosition, m_body->m_worldPose.m_worldOrientation,color,scaling);
|
b3Vector3 scaling = b3MakeVector3(SPHERE_RADIUS,SPHERE_RADIUS,SPHERE_RADIUS);
|
||||||
m_app->m_renderer->writeSingleInstanceTransformToCPU(m_body->m_worldPose.m_worldPosition, m_body->m_worldPose.m_worldOrientation, m_body->m_graphicsIndex);
|
for (int i=0;i<m_bodies.size();i++)
|
||||||
|
{
|
||||||
|
m_bodies[i]->m_collisionShape.m_sphere.m_radius = SPHERE_RADIUS;
|
||||||
|
m_bodies[i]->m_collisionShape.m_type = LW_SPHERE_TYPE;
|
||||||
|
|
||||||
|
m_bodies[i]->m_graphicsIndex = m_app->m_renderer->registerGraphicsInstance(boxId,m_bodies[i]->m_worldPose.m_position, m_bodies[i]->m_worldPose.m_orientation,color,scaling);
|
||||||
|
m_app->m_renderer->writeSingleInstanceTransformToCPU(m_bodies[i]->m_worldPose.m_position, m_bodies[i]->m_worldPose.m_orientation, m_bodies[i]->m_graphicsIndex);
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
if (m_tutorialIndex == TUT_SOLVE_CONTACT_CONSTRAINT)
|
||||||
|
{
|
||||||
|
m_bodies[0]->m_invMass = gMassA? 1./gMassA : 0;
|
||||||
|
m_bodies[0]->m_collisionShape.m_sphere.computeLocalInertia(gMassA,m_bodies[0]->m_localInertia);
|
||||||
|
|
||||||
|
m_bodies[1]->m_invMass =gMassB? 1./gMassB : 0;
|
||||||
|
m_bodies[1]->m_collisionShape.m_sphere.computeLocalInertia(gMassB,m_bodies[1]->m_localInertia);
|
||||||
|
|
||||||
|
if (gMassA)
|
||||||
|
m_bodies[0]->m_linearVelocity.setValue(0,0,1);
|
||||||
|
if (gMassB)
|
||||||
|
m_bodies[1]->m_linearVelocity.setValue(0,0,-1);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
m_app->m_renderer->writeTransforms();
|
m_app->m_renderer->writeTransforms();
|
||||||
}
|
}
|
||||||
virtual ~Tutorial()
|
virtual ~Tutorial()
|
||||||
{
|
{
|
||||||
delete m_timeSeriesCanvas;
|
delete m_timeSeriesCanvas0;
|
||||||
m_timeSeriesCanvas = 0;
|
delete m_timeSeriesCanvas1;
|
||||||
|
|
||||||
|
m_timeSeriesCanvas0 = 0;
|
||||||
|
m_timeSeriesCanvas1 = 0;
|
||||||
|
|
||||||
m_app->m_renderer->enableBlend(false);
|
m_app->m_renderer->enableBlend(false);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -196,27 +471,96 @@ public:
|
|||||||
{
|
{
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void tutorial1Update(float deltaTime);
|
||||||
|
void tutorial2Update(float deltaTime);
|
||||||
|
void tutorialCollisionUpdate(float deltaTime,LWContactPoint& contact);
|
||||||
|
void tutorialSolveContactConstraintUpdate(float deltaTime,LWContactPoint& contact);
|
||||||
|
|
||||||
virtual void stepSimulation(float deltaTime)
|
virtual void stepSimulation(float deltaTime)
|
||||||
{
|
{
|
||||||
|
switch (m_tutorialIndex)
|
||||||
|
{
|
||||||
|
case TUT_VELOCITY:
|
||||||
|
{
|
||||||
|
tutorial1Update(deltaTime);
|
||||||
|
float xPos = m_bodies[0]->m_worldPose.m_position.x;
|
||||||
|
float xVel = m_bodies[0]->m_linearVelocity.x;
|
||||||
|
m_timeSeriesCanvas0->insertDataAtCurrentTime(xPos,0,true);
|
||||||
|
m_timeSeriesCanvas0->insertDataAtCurrentTime(xVel,1,true);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case TUT_ACCELERATION:
|
||||||
|
{
|
||||||
|
tutorial2Update(deltaTime);
|
||||||
|
float yPos = m_bodies[0]->m_worldPose.m_position.y;
|
||||||
|
float yVel = m_bodies[0]->m_linearVelocity.y;
|
||||||
|
m_timeSeriesCanvas1->insertDataAtCurrentTime(yPos,0,true);
|
||||||
|
m_timeSeriesCanvas1->insertDataAtCurrentTime(yVel,1,true);
|
||||||
|
|
||||||
m_body->m_linearVelocity=btVector3(1,0,0);
|
break;
|
||||||
|
}
|
||||||
|
case TUT_COLLISION:
|
||||||
|
{
|
||||||
|
m_contactPoints.clear();
|
||||||
|
LWContactPoint contactPoint;
|
||||||
|
tutorialCollisionUpdate(deltaTime, contactPoint);
|
||||||
|
m_contactPoints.push_back(contactPoint);
|
||||||
|
m_timeSeriesCanvas1->insertDataAtCurrentTime(contactPoint.m_distance,0,true);
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case TUT_SOLVE_CONTACT_CONSTRAINT:
|
||||||
|
{
|
||||||
|
m_contactPoints.clear();
|
||||||
|
LWContactPoint contactPoint;
|
||||||
|
tutorialSolveContactConstraintUpdate(deltaTime, contactPoint);
|
||||||
|
m_contactPoints.push_back(contactPoint);
|
||||||
|
if (contactPoint.m_distance<0)
|
||||||
|
{
|
||||||
|
m_bodies[0]->computeInvInertiaTensorWorld();
|
||||||
|
m_bodies[1]->computeInvInertiaTensorWorld();
|
||||||
|
|
||||||
|
b3Scalar appliedImpulse = resolveCollision(*m_bodies[0],
|
||||||
|
*m_bodies[1],
|
||||||
|
contactPoint
|
||||||
|
);
|
||||||
|
|
||||||
|
m_timeSeriesCanvas1->insertDataAtCurrentTime(appliedImpulse,1,true);
|
||||||
|
|
||||||
|
} else
|
||||||
|
{
|
||||||
|
m_timeSeriesCanvas1->insertDataAtCurrentTime(0.,1,true);
|
||||||
|
}
|
||||||
|
m_timeSeriesCanvas1->insertDataAtCurrentTime(contactPoint.m_distance,0,true);
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
default:
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
float time = m_timeSeriesCanvas->getCurrentTime();
|
if (m_timeSeriesCanvas0)
|
||||||
|
m_timeSeriesCanvas0->nextTick();
|
||||||
|
|
||||||
float xPos = m_body->m_worldPose.m_worldPosition.x();
|
if (m_timeSeriesCanvas1)
|
||||||
|
m_timeSeriesCanvas1->nextTick();
|
||||||
float xVel = m_body->m_linearVelocity.x();
|
|
||||||
|
|
||||||
m_timeSeriesCanvas->insertDataAtCurrentTime(xPos,0,true);
|
|
||||||
m_timeSeriesCanvas->insertDataAtCurrentTime(xVel,1,true);
|
|
||||||
|
|
||||||
m_timeSeriesCanvas->nextTick();
|
|
||||||
|
|
||||||
|
|
||||||
m_body->integrateTransform(deltaTime);
|
for (int i=0;i<m_bodies.size();i++)
|
||||||
|
{
|
||||||
|
|
||||||
|
m_bodies[i]->integrateAcceleration(deltaTime);
|
||||||
|
m_bodies[i]->integrateVelocity(deltaTime);
|
||||||
|
|
||||||
|
m_app->m_renderer->writeSingleInstanceTransformToCPU(m_bodies[i]->m_worldPose.m_position, m_bodies[i]->m_worldPose.m_orientation, m_bodies[i]->m_graphicsIndex);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
m_app->m_renderer->writeSingleInstanceTransformToCPU(m_body->m_worldPose.m_worldPosition, m_body->m_worldPose.m_worldOrientation, m_body->m_graphicsIndex);
|
|
||||||
m_app->m_renderer->writeTransforms();
|
m_app->m_renderer->writeTransforms();
|
||||||
}
|
}
|
||||||
virtual void renderScene()
|
virtual void renderScene()
|
||||||
@@ -225,6 +569,18 @@ public:
|
|||||||
m_app->drawText3D("X",1,0,0,1);
|
m_app->drawText3D("X",1,0,0,1);
|
||||||
m_app->drawText3D("Y",0,1,0,1);
|
m_app->drawText3D("Y",0,1,0,1);
|
||||||
m_app->drawText3D("Z",0,0,1,1);
|
m_app->drawText3D("Z",0,0,1,1);
|
||||||
|
|
||||||
|
for (int i=0;i<m_contactPoints.size();i++)
|
||||||
|
{
|
||||||
|
const LWContactPoint& contact = m_contactPoints[i];
|
||||||
|
b3Vector3 color=b3MakeVector3(1,1,0);
|
||||||
|
float lineWidth=3;
|
||||||
|
if (contact.m_distance<0)
|
||||||
|
{
|
||||||
|
color.setValue(1,0,0);
|
||||||
|
}
|
||||||
|
m_app->m_renderer->drawLine(contact.m_ptOnAWorld,contact.m_ptOnBWorld,color,lineWidth);
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
@@ -264,8 +620,174 @@ public:
|
|||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
class CommonExampleInterface* TutorialCreateFunc(struct CommonExampleOptions& options)
|
void Tutorial::tutorial2Update(float deltaTime)
|
||||||
{
|
{
|
||||||
return new Tutorial(options.m_guiHelper->getAppInterface(), options.m_option);
|
for (int i=0;i<m_bodies.size();i++)
|
||||||
|
{
|
||||||
|
m_bodies[i]->m_gravityAcceleration.setValue(0,-10,0);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
void Tutorial::tutorial1Update(float deltaTime)
|
||||||
|
{
|
||||||
|
for (int i=0;i<m_bodies.size();i++)
|
||||||
|
{
|
||||||
|
switch (m_stage)
|
||||||
|
{
|
||||||
|
case 0:
|
||||||
|
{
|
||||||
|
m_bodies[i]->m_angularVelocity=b3MakeVector3(0,0,0);
|
||||||
|
m_bodies[i]->m_linearVelocity=b3MakeVector3(1,0,0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 1:
|
||||||
|
{
|
||||||
|
m_bodies[i]->m_linearVelocity=b3MakeVector3(-1,0,0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 2:
|
||||||
|
{
|
||||||
|
m_bodies[i]->m_linearVelocity=b3MakeVector3(0,1,0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 3:
|
||||||
|
{
|
||||||
|
m_bodies[i]->m_linearVelocity=b3MakeVector3(0,-1,0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 4:
|
||||||
|
{
|
||||||
|
m_bodies[i]->m_linearVelocity=b3MakeVector3(0,0,1);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 5:
|
||||||
|
{
|
||||||
|
m_bodies[i]->m_linearVelocity=b3MakeVector3(0,0,-1);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 6:
|
||||||
|
{
|
||||||
|
m_bodies[i]->m_linearVelocity=b3MakeVector3(0,0,0);
|
||||||
|
m_bodies[i]->m_angularVelocity=b3MakeVector3(1,0,0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 7:
|
||||||
|
{
|
||||||
|
m_bodies[i]->m_angularVelocity=b3MakeVector3(-1,0,0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 8:
|
||||||
|
{
|
||||||
|
m_bodies[i]->m_angularVelocity=b3MakeVector3(0,1,0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 9:
|
||||||
|
{
|
||||||
|
m_bodies[i]->m_angularVelocity=b3MakeVector3(0,-1,0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 10:
|
||||||
|
{
|
||||||
|
m_bodies[i]->m_angularVelocity=b3MakeVector3(0,0,1);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 11:
|
||||||
|
{
|
||||||
|
m_bodies[i]->m_angularVelocity=b3MakeVector3(0,0,-1);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
default:
|
||||||
|
{
|
||||||
|
m_bodies[i]->m_angularVelocity=b3MakeVector3(0,0,0);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
}
|
||||||
|
|
||||||
|
m_counter++;
|
||||||
|
if (m_counter>60)
|
||||||
|
{
|
||||||
|
m_counter=0;
|
||||||
|
m_stage++;
|
||||||
|
if (m_stage>11)
|
||||||
|
m_stage=0;
|
||||||
|
b3Printf("Stage = %d\n",m_stage);
|
||||||
|
b3Printf("linVel = %f,%f,%f\n",m_bodies[0]->m_linearVelocity.x,m_bodies[0]->m_linearVelocity.y,m_bodies[0]->m_linearVelocity.z);
|
||||||
|
b3Printf("angVel = %f,%f,%f\n",m_bodies[0]->m_angularVelocity.x,m_bodies[0]->m_angularVelocity.y,m_bodies[0]->m_angularVelocity.z);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
void Tutorial::tutorialSolveContactConstraintUpdate(float deltaTime,LWContactPoint& contact)
|
||||||
|
{
|
||||||
|
ComputeClosestPointsSphereSphere(m_bodies[0]->m_collisionShape.m_sphere,
|
||||||
|
m_bodies[0]->m_worldPose,
|
||||||
|
m_bodies[1]->m_collisionShape.m_sphere,
|
||||||
|
m_bodies[1]->m_worldPose,
|
||||||
|
contact);
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void Tutorial::tutorialCollisionUpdate(float deltaTime,LWContactPoint& contact)
|
||||||
|
{
|
||||||
|
m_bodies[1]->m_worldPose.m_position.z = 3;
|
||||||
|
|
||||||
|
|
||||||
|
ComputeClosestPointsSphereSphere(m_bodies[0]->m_collisionShape.m_sphere,
|
||||||
|
m_bodies[0]->m_worldPose,
|
||||||
|
m_bodies[1]->m_collisionShape.m_sphere,
|
||||||
|
m_bodies[1]->m_worldPose,
|
||||||
|
contact);
|
||||||
|
|
||||||
|
switch (m_stage)
|
||||||
|
{
|
||||||
|
case 0:
|
||||||
|
{
|
||||||
|
m_bodies[0]->m_angularVelocity=b3MakeVector3(0,0,0);
|
||||||
|
m_bodies[0]->m_linearVelocity=b3MakeVector3(1,0,0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 1:
|
||||||
|
{
|
||||||
|
m_bodies[0]->m_linearVelocity=b3MakeVector3(-1,0,0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 2:
|
||||||
|
{
|
||||||
|
m_bodies[0]->m_linearVelocity=b3MakeVector3(0,1,0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 3:
|
||||||
|
{
|
||||||
|
m_bodies[0]->m_linearVelocity=b3MakeVector3(0,-1,0);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 4:
|
||||||
|
{
|
||||||
|
m_bodies[0]->m_linearVelocity=b3MakeVector3(0,0,1);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
case 5:
|
||||||
|
{
|
||||||
|
m_bodies[0]->m_linearVelocity=b3MakeVector3(0,0,-1);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
default:{}
|
||||||
|
};
|
||||||
|
m_counter++;
|
||||||
|
if (m_counter>120)
|
||||||
|
{
|
||||||
|
m_counter=0;
|
||||||
|
m_stage++;
|
||||||
|
if (m_stage>5)
|
||||||
|
m_stage=0;
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
class CommonExampleInterface* TutorialCreateFunc(struct CommonExampleOptions& options)
|
||||||
|
{
|
||||||
|
return new Tutorial(options.m_guiHelper, options.m_option);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|||||||
@@ -1,6 +1,14 @@
|
|||||||
#ifndef TUTORIAL_H
|
#ifndef TUTORIAL_H
|
||||||
#define TUTORIAL_H
|
#define TUTORIAL_H
|
||||||
|
|
||||||
|
enum EnumTutorialTypes
|
||||||
|
{
|
||||||
|
TUT_VELOCITY=0,
|
||||||
|
TUT_ACCELERATION,
|
||||||
|
TUT_COLLISION,
|
||||||
|
TUT_SOLVE_CONTACT_CONSTRAINT,
|
||||||
|
};
|
||||||
|
|
||||||
class CommonExampleInterface* TutorialCreateFunc(struct CommonExampleOptions& options);
|
class CommonExampleInterface* TutorialCreateFunc(struct CommonExampleOptions& options);
|
||||||
|
|
||||||
#endif //TUTORIAL_H
|
#endif //TUTORIAL_H
|
||||||
|
|||||||
Reference in New Issue
Block a user