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

@@ -338,6 +338,16 @@ int b3PhysicsParamSetSplitImpulsePenetrationThreshold(b3SharedMemoryCommandHandl
return 0;
}
int b3PhysicsParamSetContactBreakingThreshold(b3SharedMemoryCommandHandle commandHandle, double contactBreakingThreshold)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
command->m_physSimParamArgs.m_contactBreakingThreshold = contactBreakingThreshold;
command->m_updateFlags |= SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD;
return 0;
}
int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;

View File

@@ -191,7 +191,7 @@ int b3PhysicsParamSetCollisionFilterMode(b3SharedMemoryCommandHandle commandHand
int b3PhysicsParamSetUseSplitImpulse(b3SharedMemoryCommandHandle commandHandle, int useSplitImpulse);
int b3PhysicsParamSetSplitImpulsePenetrationThreshold(b3SharedMemoryCommandHandle commandHandle, double splitImpulsePenetrationThreshold);
int b3PhysicsParamSetContactBreakingThreshold(b3SharedMemoryCommandHandle commandHandle, double contactBreakingThreshold);
//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

View File

@@ -12,6 +12,7 @@
#include "BulletDynamics/Featherstone/btMultiBodyFixedConstraint.h"
#include "BulletDynamics/Featherstone/btMultiBodySliderConstraint.h"
#include "BulletDynamics/Featherstone/btMultiBodyPoint2Point.h"
#include "BulletCollision/NarrowPhaseCollision/btPersistentManifold.h"
#include "LinearMath/btHashMap.h"
#include "BulletInverseDynamics/MultiBodyTree.hpp"
#include "IKTrajectoryHelper.h"
@@ -798,7 +799,7 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = 0.08;
m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.00001;
m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = 50;
m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = 150;
m_data->m_dynamicsWorld->getSolverInfo().m_leastSquaresResidualThreshold = 1e-7;
// m_data->m_dynamicsWorld->getSolverInfo().m_minimumSolverBatchSize = 2;
//todo: islands/constraints are buggy in btMultiBodyDynamicsWorld! (performance + see slipping grasp)
@@ -2724,7 +2725,10 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
{
m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = clientCmd.m_physSimParamArgs.m_numSolverIterations;
}
if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD)
{
gContactBreakingThreshold = clientCmd.m_physSimParamArgs.m_contactBreakingThreshold;
}
if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_COLLISION_FILTER_MODE)
{
m_data->m_broadphaseCollisionFilterCallback->m_filterMode = clientCmd.m_physSimParamArgs.m_collisionFilterMode;

View File

@@ -553,7 +553,7 @@ public:
while (m_cs->getSharedParam(1)!=eGUIHelperIdle)
{
b3Clock::usleep(100);
b3Clock::usleep(0);
}
}
@@ -940,6 +940,8 @@ public:
virtual void stepSimulation(float deltaTime);
virtual void updateGraphics();
void enableCommandLogging()
{
m_physicsServer.enableCommandLogging(true,"BulletPhysicsCommandLog.bin");
@@ -1342,39 +1344,8 @@ bool PhysicsServerExample::wantsTermination()
return m_wantsShutdown;
}
void PhysicsServerExample::stepSimulation(float deltaTime)
void PhysicsServerExample::updateGraphics()
{
BT_PROFILE("PhysicsServerExample::stepSimulation");
//this->m_physicsServer.processClientCommands();
for (int i = m_multiThreadedHelper->m_userDebugLines.size()-1;i>=0;i--)
{
if (m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime)
{
m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime -= deltaTime;
if (m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime<=0)
{
m_multiThreadedHelper->m_userDebugLines.swap(i,m_multiThreadedHelper->m_userDebugLines.size()-1);
m_multiThreadedHelper->m_userDebugLines.pop_back();
}
}
}
for (int i = m_multiThreadedHelper->m_userDebugText.size()-1;i>=0;i--)
{
if (m_multiThreadedHelper->m_userDebugText[i].m_lifeTime)
{
m_multiThreadedHelper->m_userDebugText[i].m_lifeTime -= deltaTime;
if (m_multiThreadedHelper->m_userDebugText[i].m_lifeTime<=0)
{
m_multiThreadedHelper->m_userDebugText.swap(i,m_multiThreadedHelper->m_userDebugText.size()-1);
m_multiThreadedHelper->m_userDebugText.pop_back();
}
}
}
//check if any graphics related tasks are requested
switch (m_multiThreadedHelper->getCriticalSection()->getSharedParam(1))
@@ -1543,6 +1514,40 @@ void PhysicsServerExample::stepSimulation(float deltaTime)
}
}
void PhysicsServerExample::stepSimulation(float deltaTime)
{
BT_PROFILE("PhysicsServerExample::stepSimulation");
//this->m_physicsServer.processClientCommands();
for (int i = m_multiThreadedHelper->m_userDebugLines.size()-1;i>=0;i--)
{
if (m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime)
{
m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime -= deltaTime;
if (m_multiThreadedHelper->m_userDebugLines[i].m_lifeTime<=0)
{
m_multiThreadedHelper->m_userDebugLines.swap(i,m_multiThreadedHelper->m_userDebugLines.size()-1);
m_multiThreadedHelper->m_userDebugLines.pop_back();
}
}
}
for (int i = m_multiThreadedHelper->m_userDebugText.size()-1;i>=0;i--)
{
if (m_multiThreadedHelper->m_userDebugText[i].m_lifeTime)
{
m_multiThreadedHelper->m_userDebugText[i].m_lifeTime -= deltaTime;
if (m_multiThreadedHelper->m_userDebugText[i].m_lifeTime<=0)
{
m_multiThreadedHelper->m_userDebugText.swap(i,m_multiThreadedHelper->m_userDebugText.size()-1);
m_multiThreadedHelper->m_userDebugText.pop_back();
}
}
}
updateGraphics();

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;

View File

@@ -44,16 +44,13 @@ public:
PhysicsClientSharedMemory::disconnectSharedMemory();
}
unsigned long int ms = m_clock.getTimeMilliseconds();
if (ms>20)
{
m_clock.reset();
btUpdateInProcessExampleBrowserMainThread(m_data);
} else
{
//b3Clock::usleep(100);
}
return PhysicsClientSharedMemory::processServerStatus();
if (ms>20)
{
m_clock.reset();
btUpdateInProcessExampleBrowserMainThread(m_data);
}
b3Clock::usleep(0);
return PhysicsClientSharedMemory::processServerStatus();
}