Create project file for BussIK inverse kinematics library (premake, cmake)

URDF/SDF: add a flag to force concave mesh collisiofor static objects. <collision concave="yes" name="pod_collision">
VR: support teleporting using buttong, allow multiple controllers to be used, fast wireframe rendering,
Turn off warnings about deprecated C routine in btScalar.h/b3Scalar.h
Add a dummy return to stop a warning
Expose defaultContactERP in shared memory api/pybullet.
First start to expose IK in shared memory api/pybullet (not working yet)
This commit is contained in:
erwin coumans
2016-09-08 15:15:58 -07:00
parent 630fcda38b
commit 32eccdff61
43 changed files with 791 additions and 144 deletions

View File

@@ -13,7 +13,9 @@
#include "BulletCollision/CollisionShapes/btCollisionShape.h"
#include "BulletDynamics/Dynamics/btDiscreteDynamicsWorld.h"
#include "LinearMath/btIDebugDraw.h"
int gSharedMemoryKey = -1;
int gDebugDrawFlags = 0;
//how can you try typing on a keyboard, without seeing it?
//it is pretty funny, to see the desktop in VR!
@@ -32,7 +34,7 @@ int gSharedMemoryKey = -1;
CommonExampleInterface* sExample;
int sPrevPacketNum=0;
GUIHelperInterface* sGuiPtr = 0;
OpenGLGuiHelper* sGuiPtr = 0;
static vr::VRControllerState_t sPrevStates[vr::k_unMaxTrackedDeviceCount] = { 0 };
@@ -384,6 +386,8 @@ bool CMainApplication::BInit()
sGuiPtr = new OpenGLGuiHelper(m_app,false);
sGuiPtr->setVRMode(true);
//sGuiPtr = new DummyGUIHelper;
@@ -467,7 +471,7 @@ bool CMainApplication::BInit()
m_fScaleSpacing = 4.0f;
m_fNearClip = 0.1f;
m_fFarClip = 30.0f;
m_fFarClip = 3000.0f;
m_iTexture = 0;
m_uiVertcount = 0;
@@ -668,6 +672,7 @@ bool CMainApplication::HandleInput()
{
//we need to have the 'move' events, so no early out here
//if (sPrevStates[unDevice].unPacketNum != state.unPacketNum)
if( m_pHMD->GetTrackedDeviceClass( unDevice) == vr::TrackedDeviceClass_Controller )
{
sPrevStates[unDevice].unPacketNum = state.unPacketNum;
@@ -689,6 +694,14 @@ bool CMainApplication::HandleInput()
if ((sPrevStates[unDevice].ulButtonPressed&trigger)==0)
{
// printf("Device PRESSED: %d, button %d\n", unDevice, button);
if (button==2)
{
glPolygonMode( GL_FRONT_AND_BACK, GL_LINE );
gDebugDrawFlags = btIDebugDraw::DBG_DrawContactPoints
//btIDebugDraw::DBG_DrawConstraintLimits+
//btIDebugDraw::DBG_DrawConstraints
;
}
sExample->vrControllerButtonCallback(unDevice, button, 1, pos, orn);
}
else
@@ -699,16 +712,30 @@ bool CMainApplication::HandleInput()
}
else
{
//not pressed now, but pressed before -> raise a button up event
if ((sPrevStates[unDevice].ulButtonPressed&trigger) != 0)
if( m_pHMD->GetTrackedDeviceClass( unDevice) == vr::TrackedDeviceClass_Controller )
{
b3Transform tr;
getControllerTransform(unDevice, tr);
float pos[3] = { tr.getOrigin()[0], tr.getOrigin()[1], tr.getOrigin()[2] };
b3Quaternion born = tr.getRotation();
float orn[4] = { born[0], born[1], born[2], born[3] };
// printf("Device RELEASED: %d, button %d\n", unDevice,button);
sExample->vrControllerButtonCallback(unDevice, button, 0, pos, orn);
// printf("Device RELEASED: %d, button %d\n", unDevice,button);
//not pressed now, but pressed before -> raise a button up event
if ((sPrevStates[unDevice].ulButtonPressed&trigger) != 0)
{
if (button==2)
{
gDebugDrawFlags = 0;
glPolygonMode( GL_FRONT_AND_BACK, GL_FILL);
}
sExample->vrControllerButtonCallback(unDevice, button, 0, pos, orn);
} else
{
sExample->vrControllerMoveCallback(unDevice, pos, orn);
}
}
}
}
@@ -1603,11 +1630,19 @@ void CMainApplication::RenderStereoTargets()
m_app->m_instancingRenderer->setRenderFrameBuffer((unsigned int)leftEyeDesc.m_nRenderFramebufferId);
sExample->renderScene();
if (gDebugDrawFlags)
{
sExample->physicsDebugDraw(gDebugDrawFlags);
}
{
sExample->renderScene();
}
//m_app->m_instancingRenderer->renderScene();
DrawGridData gridUp;
gridUp.upAxis = m_app->getUpAxis();
m_app->drawGrid(gridUp);
// m_app->drawGrid(gridUp);
glBindFramebuffer( GL_FRAMEBUFFER, 0 );
@@ -1645,8 +1680,17 @@ void CMainApplication::RenderStereoTargets()
m_app->m_instancingRenderer->setRenderFrameBuffer((unsigned int)rightEyeDesc.m_nRenderFramebufferId);
//m_app->m_renderer->renderScene();
sExample->renderScene();
m_app->drawGrid(gridUp);
if (gDebugDrawFlags)
{
sExample->physicsDebugDraw(gDebugDrawFlags);
}
{
sExample->renderScene();
}
//m_app->drawGrid(gridUp);
glBindFramebuffer( GL_FRAMEBUFFER, 0 );