VR video recording, use command-line --mp4=videoname.mp4

tune gripper grasp example with tefal pan, 800Newton force.
URDF importer: if using single transform 1 child shape, don't use compound shape.
if renderGUI is false, don't intercept mouse clicks
add manyspheres.py example (performance is pretty bad, will look into it)
[pybullet] expose contactBreakingThreshold
This commit is contained in:
Erwin Coumans
2017-02-16 14:19:09 -08:00
parent 08b83c3cd8
commit 63486a712c
18 changed files with 140 additions and 82 deletions

View File

@@ -313,7 +313,8 @@ enum EnumSimParamUpdateFlags
SIM_PARAM_UPDATE_INTERNAL_SIMULATION_FLAGS=64,
SIM_PARAM_UPDATE_USE_SPLIT_IMPULSE=128,
SIM_PARAM_UPDATE_SPLIT_IMPULSE_PENETRATION_THRESHOLD = 256,
SIM_PARAM_UPDATE_COLLISION_FILTER_MODE=512
SIM_PARAM_UPDATE_COLLISION_FILTER_MODE=512,
SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD = 1024,
};
enum EnumLoadBunnyUpdateFlags
@@ -340,6 +341,7 @@ struct SendPhysicsSimulationParameters
bool m_allowRealTimeSimulation;
int m_useSplitImpulse;
double m_splitImpulsePenetrationThreshold;
double m_contactBreakingThreshold;
int m_internalSimFlags;
double m_defaultContactERP;
int m_collisionFilterMode;