added b3PhysicsParamSetInternalSimFlags command, and pybullet setInternalSimFlags API.

//Use at own risk: magic things may or my not happen when calling this API.

This allows to enable/disable robot assets (samurai world, gripper, KUKA robot etc) in Physics Server (and App_PhysicsServerVR etc)
1 = create robot assets
2 = create experimental box-vr-gui

Add optional command-line parameter for App_PhysicsServerVR, --norobotassets, to start with an empty world, no assets in VR (no gripper, no kuka)
This commit is contained in:
erwincoumans
2016-10-23 07:14:50 -07:00
parent 2c6237abda
commit c2ca88bf44
8 changed files with 564 additions and 473 deletions

View File

@@ -179,6 +179,15 @@ int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandH
return 0;
}
int b3PhysicsParamSetInternalSimFlags(b3SharedMemoryCommandHandle commandHandle, int flags)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
command->m_physSimParamArgs.m_internalSimFlags = flags;
command->m_updateFlags |= SIM_PARAM_UPDATE_INTERNAL_SIMULATION_FLAGS;
return 0;
}
int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;

View File

@@ -108,6 +108,9 @@ int b3PhysicsParamSetNumSubSteps(b3SharedMemoryCommandHandle commandHandle, int
int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandHandle, int enableRealTimeSimulation);
int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations);
//b3PhysicsParamSetInternalSimFlags is for internal/temporary/easter-egg/experimental demo purposes
//Use at own risk: magic things may or my not happen when calling this API
int b3PhysicsParamSetInternalSimFlags(b3SharedMemoryCommandHandle commandHandle, int flags);
b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsClientHandle physClient);

View File

@@ -41,7 +41,8 @@
btVector3 gLastPickPos(0, 0, 0);
bool gCloseToKuka=false;
bool gEnableRealTimeSimVR=false;
bool gCreateSamuraiRobotAssets = true;
bool gCreateDefaultRobotAssets = false;
int gInternalSimFlags = 0;
int gCreateObjectSimVR = -1;
btScalar simTimeScalingFactor = 1;
@@ -2165,6 +2166,15 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
{
m_data->m_allowRealTimeSimulation = clientCmd.m_physSimParamArgs.m_allowRealTimeSimulation;
}
//see
if (clientCmd.m_updateFlags & SIM_PARAM_UPDATE_INTERNAL_SIMULATION_FLAGS)
{
//these flags are for internal/temporary/easter-egg/experimental demo purposes, use at own risk
gCreateDefaultRobotAssets = (clientCmd.m_physSimParamArgs.m_internalSimFlags & SIM_PARAM_INTERNAL_CREATE_ROBOT_ASSETS);
gInternalSimFlags = clientCmd.m_physSimParamArgs.m_internalSimFlags;
}
if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_GRAVITY)
{
btVector3 grav(clientCmd.m_physSimParamArgs.m_gravityAcceleration[0],
@@ -3223,12 +3233,60 @@ double gSubStep = 0.f;
void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
{
if ((gEnableRealTimeSimVR || m_data->m_allowRealTimeSimulation) && m_data->m_guiHelper)
{
///this hardcoded C++ scene creation is temporary for demo purposes. It will be done in Python later...
if (gCreateDefaultRobotAssets)
{
createDefaultRobotAssets();
}
int maxSteps = m_data->m_numSimulationSubSteps+3;
if (m_data->m_numSimulationSubSteps)
{
gSubStep = m_data->m_physicsDeltaTime / m_data->m_numSimulationSubSteps;
}
else
{
gSubStep = m_data->m_physicsDeltaTime;
}
int numSteps = m_data->m_dynamicsWorld->stepSimulation(dtInSec*simTimeScalingFactor,maxSteps, gSubStep);
gDroppedSimulationSteps += numSteps > maxSteps ? numSteps - maxSteps : 0;
if (numSteps)
{
gNumSteps = numSteps;
gDtInSec = dtInSec;
}
}
}
void PhysicsServerCommandProcessor::applyJointDamping(int bodyUniqueId)
{
InteralBodyData* body = m_data->getHandle(bodyUniqueId);
if (body) {
btMultiBody* mb = body->m_multiBody;
if (mb) {
for (int l=0;l<mb->getNumLinks();l++) {
for (int d=0;d<mb->getLink(l).m_dofCount;d++) {
double damping_coefficient = mb->getLink(l).m_jointDamping;
double damping = -damping_coefficient*mb->getJointVelMultiDof(l)[d];
mb->addJointTorqueMultiDof(l, d, damping);
}
}
}
}
}
//todo: move this to Python/scripting
void PhysicsServerCommandProcessor::createDefaultRobotAssets()
{
static btAlignedObjectArray<char> gBufferServerToClient;
gBufferServerToClient.resize(SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE);
int bodyId = 0;
if (gCreateObjectSimVR >= 0)
{
gCreateObjectSimVR = -1;
@@ -3247,9 +3305,6 @@ 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;
@@ -3693,42 +3748,3 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
}
}
int maxSteps = m_data->m_numSimulationSubSteps+3;
if (m_data->m_numSimulationSubSteps)
{
gSubStep = m_data->m_physicsDeltaTime / m_data->m_numSimulationSubSteps;
}
else
{
gSubStep = m_data->m_physicsDeltaTime;
}
int numSteps = m_data->m_dynamicsWorld->stepSimulation(dtInSec*simTimeScalingFactor,maxSteps, gSubStep);
gDroppedSimulationSteps += numSteps > maxSteps ? numSteps - maxSteps : 0;
if (numSteps)
{
gNumSteps = numSteps;
gDtInSec = dtInSec;
}
}
}
void PhysicsServerCommandProcessor::applyJointDamping(int bodyUniqueId)
{
InteralBodyData* body = m_data->getHandle(bodyUniqueId);
if (body) {
btMultiBody* mb = body->m_multiBody;
if (mb) {
for (int l=0;l<mb->getNumLinks();l++) {
for (int d=0;d<mb->getLink(l).m_dofCount;d++) {
double damping_coefficient = mb->getLink(l).m_jointDamping;
double damping = -damping_coefficient*mb->getJointVelMultiDof(l)[d];
mb->addJointTorqueMultiDof(l, d, damping);
}
}
}
}
}

View File

@@ -16,6 +16,9 @@ class PhysicsServerCommandProcessor
struct PhysicsServerCommandProcessorInternalData* m_data;
//todo: move this to physics client side / Python
void createDefaultRobotAssets();
protected:

View File

@@ -34,13 +34,15 @@ extern btScalar gVRGripperAnalog;
extern btScalar gVRGripper2Analog;
extern bool gCloseToKuka;
extern bool gEnableRealTimeSimVR;
extern bool gCreateSamuraiRobotAssets;
extern bool gCreateDefaultRobotAssets;
extern int gInternalSimFlags;
extern int gCreateObjectSimVR;
static int gGraspingController = -1;
extern btScalar simTimeScalingFactor;
extern bool gVRGripperClosed;
bool gDebugRenderToggle = false;
void MotionThreadFunc(void* userPtr,void* lsMemory);
void* MotionlsMemoryFunc();
@@ -600,6 +602,7 @@ public:
virtual void vrControllerButtonCallback(int controllerId, int button, int state, float pos[4], float orientation[4]);
virtual void vrControllerMoveCallback(int controllerId, float pos[4], float orientation[4], float analogAxis);
virtual bool mouseMoveCallback(float x,float y)
{
if (m_replay)
@@ -670,13 +673,18 @@ public:
virtual void processCommandLineArgs(int argc, char* argv[])
{
b3CommandLineArgs args(argc,argv);
if (args.CheckCmdLineFlag("emptyworld"))
if (args.CheckCmdLineFlag("robotassets"))
{
gCreateSamuraiRobotAssets = false;
gCreateDefaultRobotAssets = true;
}
if (args.CheckCmdLineFlag("norobotassets"))
{
gCreateDefaultRobotAssets = false;
}
}
};
@@ -995,7 +1003,7 @@ void PhysicsServerExample::renderScene()
}
#ifdef BT_ENABLE_VR
if (m_tinyVrGui==0)
if ((gInternalSimFlags&2 ) && m_tinyVrGui==0)
{
ComboBoxParams comboParams;
comboParams.m_comboboxId = 0;

View File

@@ -238,9 +238,16 @@ enum EnumSimParamUpdateFlags
SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS=4,
SIM_PARAM_UPDATE_NUM_SIMULATION_SUB_STEPS=8,
SIM_PARAM_UPDATE_REAL_TIME_SIMULATION = 16,
SIM_PARAM_UPDATE_DEFAULT_CONTACT_ERP=32
SIM_PARAM_UPDATE_DEFAULT_CONTACT_ERP=32,
SIM_PARAM_UPDATE_INTERNAL_SIMULATION_FLAGS=64
};
enum EnumSimParamInternalSimFlags
{
SIM_PARAM_INTERNAL_CREATE_ROBOT_ASSETS=1,
};
///Controlling a robot involves sending the desired state to its joint motor controllers.
///The control mode determines the state variables used for motor control.
struct SendPhysicsSimulationParameters
@@ -250,6 +257,7 @@ struct SendPhysicsSimulationParameters
int m_numSimulationSubSteps;
int m_numSolverIterations;
bool m_allowRealTimeSimulation;
int m_internalSimFlags;
double m_defaultContactERP;
};

View File

@@ -2199,7 +2199,15 @@ int main(int argc, char *argv[])
if (sExample)
{
//until we have a proper VR gui, always assume we want the hard-coded default robot assets
char* newargv[2];
char* t0 = (char*)"--robotassets";
newargv[0] = t0;
newargv[1] = t0;
sExample->processCommandLineArgs(2,newargv);
sExample->processCommandLineArgs(argc,argv);
}
//request disable VSYNC

View File

@@ -497,6 +497,39 @@ static PyObject* pybullet_setRealTimeSimulation(PyObject* self,
return Py_None;
}
static PyObject* pybullet_setInternalSimFlags(PyObject* self,
PyObject* args) {
if (0 == sm) {
PyErr_SetString(SpamError, "Not connected to physics server.");
return NULL;
}
{
int enableRealTimeSimulation = 0;
int ret;
b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(sm);
b3SharedMemoryStatusHandle statusHandle;
if (!PyArg_ParseTuple(args, "i", &enableRealTimeSimulation)) {
PyErr_SetString(
SpamError,
"setInternalSimFlags expected a single value (integer).");
return NULL;
}
ret =
b3PhysicsParamSetInternalSimFlags(command, enableRealTimeSimulation);
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, command);
// ASSERT_EQ(b3GetStatusType(statusHandle), CMD_CLIENT_COMMAND_COMPLETED);
}
Py_INCREF(Py_None);
return Py_None;
}
// Set the gravity of the world with (x, y, z) arguments
static PyObject* pybullet_setGravity(PyObject* self, PyObject* args) {
if (0 == sm) {
@@ -2218,6 +2251,9 @@ static PyMethodDef SpamMethods[] = {
"Enable or disable real time simulation (using the real time clock,"
" RTC) in the physics server. Expects one integer argument, 0 or 1" },
{ "setInternalSimFlags", pybullet_setInternalSimFlags, METH_VARARGS,
"This is for experimental purposes, use at own risk, magic may or not happen"},
{"loadURDF", pybullet_loadURDF, METH_VARARGS,
"Create a multibody by loading a URDF file."},