Merge pull request #825 from erwincoumans/master
App_SharedMemoryPhysics_VR: Add a command-line flag (--emptyworld) to start with an empty VR world and use pybullet to populate it over shared memory.
This commit is contained in:
@@ -48,6 +48,8 @@ public:
|
||||
|
||||
virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4], float analogAxis) {}
|
||||
virtual void vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orientation[4]){}
|
||||
|
||||
virtual void processCommandLineArgs(int argc, char* argv[]){};
|
||||
};
|
||||
|
||||
class ExampleEntries
|
||||
|
||||
@@ -31,6 +31,8 @@
|
||||
btVector3 gLastPickPos(0, 0, 0);
|
||||
bool gCloseToKuka=false;
|
||||
bool gEnableRealTimeSimVR=false;
|
||||
bool gCreateSamuraiRobotAssets = true;
|
||||
|
||||
int gCreateObjectSimVR = -1;
|
||||
btScalar simTimeScalingFactor = 1;
|
||||
btScalar gRhsClamp = 1.f;
|
||||
@@ -2972,6 +2974,9 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
|
||||
}
|
||||
}
|
||||
|
||||
///this hardcoded C++ scene creation is temporary for demo purposes. It will be done in Python later...
|
||||
if (gCreateSamuraiRobotAssets)
|
||||
{
|
||||
if (!m_data->m_hasGround)
|
||||
{
|
||||
m_data->m_hasGround = true;
|
||||
@@ -3011,7 +3016,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
|
||||
}
|
||||
}
|
||||
|
||||
loadUrdf("kuka_iiwa/model.urdf", btVector3(1.4, -0.2, 0.6), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
loadUrdf("kuka_iiwa/model_vr_limits.urdf", btVector3(1.4, -0.2, 0.6), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
m_data->m_KukaId = bodyId;
|
||||
loadUrdf("lego/lego.urdf", btVector3(1.0, -0.2, .7), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
loadUrdf("lego/lego.urdf", btVector3(1.0, -0.2, .8), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
@@ -3291,7 +3296,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
|
||||
}
|
||||
}
|
||||
|
||||
int ikMethod= IK2_VEL_DLS_WITH_ORIENTATION; //IK2_VEL_DLS_WITH_ORIENTATION_NULLSPACE; //IK2_VEL_DLS;
|
||||
int ikMethod= IK2_VEL_DLS_WITH_ORIENTATION_NULLSPACE;//IK2_VEL_DLS_WITH_ORIENTATION; //IK2_VEL_DLS;
|
||||
|
||||
btVector3DoubleData endEffectorWorldPosition;
|
||||
btVector3DoubleData endEffectorWorldOrientation;
|
||||
@@ -3332,20 +3337,20 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
|
||||
upper_limit.resize(numDofs);
|
||||
joint_range.resize(numDofs);
|
||||
rest_pose.resize(numDofs);
|
||||
lower_limit[0] = -2.32;
|
||||
lower_limit[1] = -1.6;
|
||||
lower_limit[2] = -2.32;
|
||||
lower_limit[3] = -1.6;
|
||||
lower_limit[4] = -2.32;
|
||||
lower_limit[5] = -1.6;
|
||||
lower_limit[6] = -2.4;
|
||||
upper_limit[0] = 2.32;
|
||||
upper_limit[1] = 1.6;
|
||||
upper_limit[2] = 2.32;
|
||||
upper_limit[3] = 1.6;
|
||||
upper_limit[4] = 2.32;
|
||||
upper_limit[5] = 1.6;
|
||||
upper_limit[6] = 2.4;
|
||||
lower_limit[0] = -.967;
|
||||
lower_limit[1] = -2.0;
|
||||
lower_limit[2] = -2.96;
|
||||
lower_limit[3] = 0.19;
|
||||
lower_limit[4] = -2.96;
|
||||
lower_limit[5] = -2.09;
|
||||
lower_limit[6] = -3.05;
|
||||
upper_limit[0] = .96;
|
||||
upper_limit[1] = 2.0;
|
||||
upper_limit[2] = 2.96;
|
||||
upper_limit[3] = 2.29;
|
||||
upper_limit[4] = 2.96;
|
||||
upper_limit[5] = 2.09;
|
||||
upper_limit[6] = 3.05;
|
||||
joint_range[0] = 5.8;
|
||||
joint_range[1] = 4;
|
||||
joint_range[2] = 5.8;
|
||||
@@ -3414,7 +3419,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
int maxSteps = m_data->m_numSimulationSubSteps+3;
|
||||
if (m_data->m_numSimulationSubSteps)
|
||||
|
||||
@@ -7,7 +7,7 @@
|
||||
|
||||
|
||||
#include "PhysicsServerSharedMemory.h"
|
||||
|
||||
#include "Bullet3Common/b3CommandLineArgs.h"
|
||||
#include "SharedMemoryCommon.h"
|
||||
#include "Bullet3Common/b3Matrix3x3.h"
|
||||
#include "../Utils/b3Clock.h"
|
||||
@@ -28,6 +28,7 @@ extern btScalar gVRGripperAnalog;
|
||||
extern btScalar gVRGripper2Analog;
|
||||
extern bool gCloseToKuka;
|
||||
extern bool gEnableRealTimeSimVR;
|
||||
extern bool gCreateSamuraiRobotAssets;
|
||||
extern int gCreateObjectSimVR;
|
||||
static int gGraspingController = -1;
|
||||
extern btScalar simTimeScalingFactor;
|
||||
@@ -656,6 +657,16 @@ public:
|
||||
m_physicsServer.setSharedMemoryKey(key);
|
||||
}
|
||||
|
||||
virtual void processCommandLineArgs(int argc, char* argv[])
|
||||
{
|
||||
b3CommandLineArgs args(argc,argv);
|
||||
if (args.CheckCmdLineFlag("emptyworld"))
|
||||
{
|
||||
gCreateSamuraiRobotAssets = false;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
};
|
||||
|
||||
|
||||
@@ -7,6 +7,7 @@
|
||||
#include "Bullet3Common/b3Quaternion.h"
|
||||
#include "Bullet3Common/b3Transform.h"
|
||||
|
||||
|
||||
#include "../ExampleBrowser/OpenGLGuiHelper.h"
|
||||
#include "../CommonInterfaces/CommonExampleInterface.h"
|
||||
#include "../CommonInterfaces/CommonGUIHelperInterface.h"
|
||||
@@ -708,6 +709,10 @@ bool CMainApplication::HandleInput()
|
||||
//btIDebugDraw::DBG_DrawConstraintLimits+
|
||||
//btIDebugDraw::DBG_DrawConstraints
|
||||
//;
|
||||
gDebugDrawFlags = btIDebugDraw::DBG_DrawConstraintLimits+ btIDebugDraw::DBG_DrawConstraints+btIDebugDraw::DBG_DrawContactPoints+btIDebugDraw::DBG_DrawFrames;
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
sExample->vrControllerButtonCallback(unDevice, button, 1, pos, orn);
|
||||
@@ -1663,7 +1668,7 @@ void CMainApplication::RenderStereoTargets()
|
||||
{
|
||||
sExample->physicsDebugDraw(gDebugDrawFlags);
|
||||
}
|
||||
else
|
||||
//else
|
||||
{
|
||||
sExample->renderScene();
|
||||
}
|
||||
@@ -1714,7 +1719,7 @@ void CMainApplication::RenderStereoTargets()
|
||||
{
|
||||
sExample->physicsDebugDraw(gDebugDrawFlags);
|
||||
}
|
||||
else
|
||||
//else
|
||||
{
|
||||
sExample->renderScene();
|
||||
}
|
||||
@@ -2183,6 +2188,7 @@ int main(int argc, char *argv[])
|
||||
//b3SetCustomLeaveProfileZoneFunc(...);
|
||||
#endif
|
||||
|
||||
|
||||
CMainApplication *pMainApplication = new CMainApplication( argc, argv );
|
||||
|
||||
if (!pMainApplication->BInit())
|
||||
@@ -2191,6 +2197,11 @@ int main(int argc, char *argv[])
|
||||
return 1;
|
||||
}
|
||||
|
||||
if (sExample)
|
||||
{
|
||||
sExample->processCommandLineArgs(argc,argv);
|
||||
}
|
||||
|
||||
//request disable VSYNC
|
||||
typedef bool (APIENTRY *PFNWGLSWAPINTERVALFARPROC)(int);
|
||||
PFNWGLSWAPINTERVALFARPROC wglSwapIntervalEXT = 0;
|
||||
|
||||
Reference in New Issue
Block a user