Simulate bunny in grasp demo and set collision margin.

This commit is contained in:
yunfeibai 2016-10-12 15:34:45 -07:00
parent 379f2ac933
commit 880ee097fa
3 changed files with 25 additions and 16 deletions

View File

@ -2,7 +2,7 @@
<sdf version='1.6'> <sdf version='1.6'>
<world name='default'> <world name='default'>
<model name='wsg50_with_gripper'> <model name='wsg50_with_gripper'>
<pose frame=''>0 0 0.6 3.14 0 0</pose> <pose frame=''>0 0 0.7 3.14 0 0</pose>
<link name='world'> <link name='world'>
</link> </link>

View File

@ -401,7 +401,6 @@ public:
} }
} }
/*
if ((m_options & eONE_MOTOR_GRASP)!=0) if ((m_options & eONE_MOTOR_GRASP)!=0)
{ {
int fingerJointIndices[2]={0,1}; int fingerJointIndices[2]={0,1};
@ -417,9 +416,8 @@ public:
m_robotSim.setJointMotorControl(m_gripperIndex,fingerJointIndices[i],controlArgs); m_robotSim.setJointMotorControl(m_gripperIndex,fingerJointIndices[i],controlArgs);
} }
} }
*/
//m_robotSim.stepSimulation(); m_robotSim.stepSimulation();
} }
virtual void renderScene() virtual void renderScene()
{ {

View File

@ -429,6 +429,7 @@ struct PhysicsServerCommandProcessorInternalData
btDefaultCollisionConfiguration* m_collisionConfiguration; btDefaultCollisionConfiguration* m_collisionConfiguration;
btSoftMultiBodyDynamicsWorld* m_dynamicsWorld; btSoftMultiBodyDynamicsWorld* m_dynamicsWorld;
SharedMemoryDebugDrawer* m_remoteDebugDrawer; SharedMemoryDebugDrawer* m_remoteDebugDrawer;
btSoftBodyWorldInfo m_softBodyWorldInfo;
btAlignedObjectArray<b3ContactPointData> m_cachedContactPoints; btAlignedObjectArray<b3ContactPointData> m_cachedContactPoints;
@ -607,8 +608,14 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded) ///use the default collision dispatcher. For parallel processing you can use a diffent dispatcher (see Extras/BulletMultiThreaded)
m_data->m_dispatcher = new btCollisionDispatcher(m_data->m_collisionConfiguration); m_data->m_dispatcher = new btCollisionDispatcher(m_data->m_collisionConfiguration);
m_data->m_softBodyWorldInfo.m_dispatcher = m_data->m_dispatcher;
m_data->m_broadphase = new btDbvtBroadphase(); //m_data->m_broadphase = new btDbvtBroadphase();
btVector3 worldAabbMin(-1000,-1000,-1000);
btVector3 worldAabbMax(1000,1000,1000);
int maxProxies = 32766;
m_data->m_broadphase = new btAxisSweep3(worldAabbMin,worldAabbMax,maxProxies);
m_data->m_solver = new btMultiBodyConstraintSolver; m_data->m_solver = new btMultiBodyConstraintSolver;
@ -622,30 +629,34 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
m_data->m_remoteDebugDrawer = new SharedMemoryDebugDrawer(); m_data->m_remoteDebugDrawer = new SharedMemoryDebugDrawer();
m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, 0)); m_data->m_dynamicsWorld->setGravity(btVector3(0, 0, -10));
m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = 0.08; m_data->m_dynamicsWorld->getSolverInfo().m_erp2 = 0.08;
btSoftBodyWorldInfo softBodyWorldInfo; m_data->m_softBodyWorldInfo.air_density = (btScalar)1.2;
softBodyWorldInfo.air_density = (btScalar)1.2; m_data->m_softBodyWorldInfo.water_density = 0;
softBodyWorldInfo.water_density = 0; m_data->m_softBodyWorldInfo.water_offset = 0;
softBodyWorldInfo.water_offset = 0; m_data->m_softBodyWorldInfo.water_normal = btVector3(0,0,0);
softBodyWorldInfo.water_normal = btVector3(0,0,0); m_data->m_softBodyWorldInfo.m_gravity.setValue(0,0,-10);
softBodyWorldInfo.m_gravity.setValue(0,0,0);
m_data->m_softBodyWorldInfo.m_broadphase = m_data->m_broadphase;
m_data->m_softBodyWorldInfo.m_sparsesdf.Initialize();
btSoftBody* psb=btSoftBodyHelpers::CreateFromTriMesh(softBodyWorldInfo,gVerticesBunny, btSoftBody* psb=btSoftBodyHelpers::CreateFromTriMesh(m_data->m_softBodyWorldInfo,gVerticesBunny,
&gIndicesBunny[0][0], &gIndicesBunny[0][0],
BUNNY_NUM_TRIANGLES); BUNNY_NUM_TRIANGLES);
btSoftBody::Material* pm=psb->appendMaterial(); btSoftBody::Material* pm=psb->appendMaterial();
pm->m_kLST = 0.5; pm->m_kLST = 1.0
;
pm->m_flags -= btSoftBody::fMaterial::DebugDraw; pm->m_flags -= btSoftBody::fMaterial::DebugDraw;
psb->generateBendingConstraints(2,pm); psb->generateBendingConstraints(2,pm);
psb->m_cfg.piterations = 2; psb->m_cfg.piterations = 2;
psb->m_cfg.kDF = 0.5; psb->m_cfg.kDF = 0.5;
psb->randomizeConstraints(); psb->randomizeConstraints();
psb->rotate(btQuaternion(0.70711,0,0,0.70711)); psb->rotate(btQuaternion(0.70711,0,0,0.70711));
psb->translate(btVector3(0,0,1.0)); psb->translate(btVector3(0,0,3.0));
psb->scale(btVector3(0.1,0.1,0.1)); psb->scale(btVector3(0.1,0.1,0.1));
psb->setTotalMass(1,true); psb->setTotalMass(1,true);
psb->getCollisionShape()->setMargin(0.01);
m_data->m_dynamicsWorld->addSoftBody(psb); m_data->m_dynamicsWorld->addSoftBody(psb);
} }