fix pybullet.c compilation for Windows
add lego.urdf, duck.urdf (optimized using VHACD convex decomposition) optimize Kiva shelf collision model (by hand, using boxes/Blender) physics timescale toggle between 1 -> 0,25 -> 0
This commit is contained in:
@@ -1,6 +1,5 @@
|
||||
#include "PhysicsServerCommandProcessor.h"
|
||||
|
||||
|
||||
#include "../Importers/ImportURDFDemo/BulletUrdfImporter.h"
|
||||
#include "../Importers/ImportURDFDemo/MyMultiBodyCreator.h"
|
||||
#include "../Importers/ImportURDFDemo/URDF2Bullet.h"
|
||||
@@ -563,7 +562,7 @@ PhysicsServerCommandProcessor::PhysicsServerCommandProcessor()
|
||||
m_data = new PhysicsServerCommandProcessorInternalData();
|
||||
|
||||
createEmptyDynamicsWorld();
|
||||
m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.0001;
|
||||
m_data->m_dynamicsWorld->getSolverInfo().m_linearSlop = 0.00001;
|
||||
m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = 100;
|
||||
|
||||
}
|
||||
@@ -604,7 +603,7 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
|
||||
|
||||
|
||||
m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, 0));
|
||||
m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = 0.05;
|
||||
m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = 0.08;
|
||||
|
||||
}
|
||||
|
||||
@@ -1887,6 +1886,9 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
|
||||
applyJointDamping(i);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
btScalar deltaTimeScaled = m_data->m_physicsDeltaTime*simTimeScalingFactor;
|
||||
|
||||
if (m_data->m_numSimulationSubSteps > 0)
|
||||
@@ -2820,6 +2822,7 @@ void PhysicsServerCommandProcessor::removePickingConstraint()
|
||||
m_data->m_dynamicsWorld->removeConstraint(m_data->m_pickedConstraint);
|
||||
delete m_data->m_pickedConstraint;
|
||||
m_data->m_pickedConstraint = 0;
|
||||
m_data->m_pickedBody->forceActivationState(ACTIVE_TAG);
|
||||
m_data->m_pickedBody = 0;
|
||||
}
|
||||
if (m_data->m_pickingMultiBodyPoint2Point)
|
||||
@@ -2889,11 +2892,12 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
|
||||
btVector3 shiftPos = spawnDir*spawnDistance;
|
||||
btVector3 spawnPos = gVRGripperPos + shiftPos;
|
||||
loadUrdf("sphere_small.urdf", spawnPos, gVRGripperOrn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
//loadUrdf("lego/lego.urdf", spawnPos, gVRGripperOrn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
m_data->m_sphereId = bodyId;
|
||||
InteralBodyData* parentBody = m_data->getHandle(bodyId);
|
||||
if (parentBody->m_multiBody)
|
||||
{
|
||||
parentBody->m_multiBody->setBaseVel(spawnDir * 3);
|
||||
parentBody->m_multiBody->setBaseVel(spawnDir * 5);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -2942,9 +2946,9 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
|
||||
loadUrdf("cube.urdf", btVector3(3, -2, 0.5+i), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
}
|
||||
|
||||
loadUrdf("sphere2.urdf", btVector3(-5, 0, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
loadUrdf("sphere2.urdf", btVector3(-5, 0, 2), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
loadUrdf("sphere2.urdf", btVector3(-5, 0, 3), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
loadUrdf("lego/lego.urdf", btVector3(-3, 0, .1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
loadUrdf("lego/lego.urdf", btVector3(-3, 0, .2), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
loadUrdf("lego/lego.urdf", btVector3(-3, 0, .3), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
loadUrdf("r2d2.urdf", btVector3(2, -2, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
|
||||
|
||||
@@ -2973,15 +2977,27 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
//loadUrdf("nao/nao.urdf", btVector3(2,5, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
|
||||
|
||||
|
||||
for (int i = 0; i < 6; i++)
|
||||
{
|
||||
loadUrdf("jenga/jenga.urdf", btVector3(-1-0.1*i,-0.5, .07), btQuaternion(btVector3(0,1,0),SIMD_HALF_PI), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
}
|
||||
|
||||
//loadUrdf("nao/nao.urdf", btVector3(2,5, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
loadUrdf("husky/husky.urdf", btVector3(5, 2, 1), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
m_data->m_huskyId = bodyId;
|
||||
|
||||
}
|
||||
loadSdf("kiva_shelf/model.sdf", &gBufferServerToClient[0], gBufferServerToClient.size(), true);
|
||||
loadUrdf("teddy_vhacd.urdf", btVector3(-0.1, 0.6, 0.85), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
loadUrdf("sphere_small.urdf", btVector3(-0.1, 0.6, 1.25), gVRGripperOrn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
loadUrdf("duck_vhacd.urdf", btVector3(-0.3, 0.6, 0.6), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
//loadUrdf("cup/cup_small.urdf", btVector3(-0.3, 0.6, 0.85), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
//loadUrdf("cup/pitcher_small.urdf", btVector3(-0.3, 0.6, 1.15), btQuaternion(0, 0, 0, 1), true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
|
||||
//loadUrdf("sphere_small.urdf", btVector3(-0.1, 0.6, 1.25), gVRGripperOrn, true, false, &bodyId, &gBufferServerToClient[0], gBufferServerToClient.size());
|
||||
|
||||
|
||||
m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, -10));
|
||||
|
||||
|
||||
@@ -1181,14 +1181,20 @@ void PhysicsServerExample::vrControllerButtonCallback(int controllerId, int butt
|
||||
} else
|
||||
{
|
||||
gDebugRenderToggle = 0;
|
||||
simTimeScalingFactor *= 0.5;
|
||||
|
||||
if (simTimeScalingFactor==0)
|
||||
{
|
||||
simTimeScalingFactor = 1;
|
||||
}
|
||||
if (simTimeScalingFactor<0.01)
|
||||
} else
|
||||
{
|
||||
simTimeScalingFactor = 0;
|
||||
if (simTimeScalingFactor==1)
|
||||
{
|
||||
simTimeScalingFactor = 0.25;
|
||||
}
|
||||
else
|
||||
{
|
||||
simTimeScalingFactor = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
} else
|
||||
|
||||
Reference in New Issue
Block a user