mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-13 21:30:09 +00:00
debug pybullet setup
This commit is contained in:
parent
96605f7a8c
commit
a018d63fb3
@ -18,7 +18,8 @@ int main(int argc, char* argv[])
|
|||||||
}
|
}
|
||||||
|
|
||||||
//remove all existing objects (if any)
|
//remove all existing objects (if any)
|
||||||
sim->resetSimulation();
|
// sim->resetSimulation();
|
||||||
|
sim->resetSimulation(RESET_USE_REDUCED_DEFORMABLE_WORLD);
|
||||||
sim->setGravity(btVector3(0, 0, -9.8));
|
sim->setGravity(btVector3(0, 0, -9.8));
|
||||||
sim->setNumSolverIterations(100);
|
sim->setNumSolverIterations(100);
|
||||||
b3RobotSimulatorSetPhysicsEngineParameters args;
|
b3RobotSimulatorSetPhysicsEngineParameters args;
|
||||||
@ -27,10 +28,11 @@ int main(int argc, char* argv[])
|
|||||||
int planeUid = sim->loadURDF("plane.urdf");
|
int planeUid = sim->loadURDF("plane.urdf");
|
||||||
printf("planeUid = %d\n", planeUid);
|
printf("planeUid = %d\n", planeUid);
|
||||||
|
|
||||||
int r2d2Uid = sim->loadURDF("r2d2.urdf");
|
int r2d2Uid = sim->loadURDF("reduced_bottle_coarse/reduced_bottle_coarse.urdf");
|
||||||
printf("r2d2 #joints = %d\n", sim->getNumJoints(r2d2Uid));
|
// int r2d2Uid = sim->loadURDF("r2d2.urdf");
|
||||||
|
// printf("r2d2 #joints = %d\n", sim->getNumJoints(r2d2Uid));
|
||||||
|
|
||||||
btVector3 basePosition = btVector3(0, 0, 0.5);
|
btVector3 basePosition = btVector3(0, 0.5, 0.2);
|
||||||
btQuaternion baseOrientation = btQuaternion(0, 0, 0, 1);
|
btQuaternion baseOrientation = btQuaternion(0, 0, 0, 1);
|
||||||
|
|
||||||
sim->resetBasePositionAndOrientation(r2d2Uid, basePosition, baseOrientation);
|
sim->resetBasePositionAndOrientation(r2d2Uid, basePosition, baseOrientation);
|
||||||
@ -40,7 +42,7 @@ int main(int argc, char* argv[])
|
|||||||
btVector3 basePos;
|
btVector3 basePos;
|
||||||
btQuaternion baseOrn;
|
btQuaternion baseOrn;
|
||||||
sim->getBasePositionAndOrientation(r2d2Uid, basePos, baseOrn);
|
sim->getBasePositionAndOrientation(r2d2Uid, basePos, baseOrn);
|
||||||
printf("r2d2 basePosition = [%f,%f,%f]\n", basePos[0], basePos[1], basePos[2]);
|
// printf("r2d2 basePosition = [%f,%f,%f]\n", basePos[0], basePos[1], basePos[2]);
|
||||||
|
|
||||||
sim->stepSimulation();
|
sim->stepSimulation();
|
||||||
}
|
}
|
||||||
|
@ -55,12 +55,24 @@ int main(int argc, char* argv[])
|
|||||||
sim->loadURDF("plane.urdf");
|
sim->loadURDF("plane.urdf");
|
||||||
|
|
||||||
{
|
{
|
||||||
int deformableUID = sim->loadURDF("reduced_cube/reduced_cube.urdf");
|
int cubeID = sim->loadURDF("cube.urdf");
|
||||||
// int deformableUID = sim->loadURDF("reduced_cube/deform_cube.urdf");
|
|
||||||
// int deformableUID = sim->loadURDF("reduced_torus/reduced_torus.urdf");
|
|
||||||
// int deformableUID = sim->loadURDF("torus_deform.urdf");
|
|
||||||
btVector3 basePosition = btVector3(0, 0, 2);
|
btVector3 basePosition = btVector3(0, 0, 2);
|
||||||
btQuaternion baseOrientation = btQuaternion(0, 0, 0, 1);
|
btQuaternion baseOrientation = btQuaternion(0, 0, 0, 1);
|
||||||
|
sim->resetBasePositionAndOrientation(cubeID, basePosition, baseOrientation);
|
||||||
|
}
|
||||||
|
|
||||||
|
{
|
||||||
|
// int deformableUID = sim->loadURDF("reduced_torus/reduced_torus.urdf");
|
||||||
|
int deformableUID = sim->loadURDF("reduced_cube/reduced_cube.urdf");
|
||||||
|
// int deformableUID = sim->loadURDF("reduced_bottle/reduced_bottle.urdf");
|
||||||
|
// int deformableUID = sim->loadURDF("reduced_bottle_coarse/reduced_bottle_coarse.urdf");
|
||||||
|
// int deformableUID = sim->loadURDF("reduced_bottle/deform_bottle.urdf");
|
||||||
|
// int deformableUID = sim->loadURDF("torus_deform.urdf");
|
||||||
|
btVector3 basePosition = btVector3(0, 3, 3);
|
||||||
|
// btVector3 basePosition = btVector3(0, 0, 0.2);
|
||||||
|
// btVector3 basePosition = btVector3(0, 0.5, 0.2);
|
||||||
|
// btQuaternion baseOrientation = btQuaternion(0, 0, 0, 1);
|
||||||
|
btQuaternion baseOrientation = btQuaternion(btVector3(1, 0, 0), SIMD_PI / 2.0);
|
||||||
sim->resetBasePositionAndOrientation(deformableUID, basePosition, baseOrientation);
|
sim->resetBasePositionAndOrientation(deformableUID, basePosition, baseOrientation);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -9216,6 +9216,10 @@ bool PhysicsServerCommandProcessor::processDeformable(const UrdfDeformable& defo
|
|||||||
psb->setGravityFactor(deformable.m_gravFactor);
|
psb->setGravityFactor(deformable.m_gravFactor);
|
||||||
psb->setCacheBarycenter(deformable.m_cache_barycenter);
|
psb->setCacheBarycenter(deformable.m_cache_barycenter);
|
||||||
psb->initializeFaceTree();
|
psb->initializeFaceTree();
|
||||||
|
|
||||||
|
deformWorld->setImplicit(true);
|
||||||
|
deformWorld->setLineSearch(false);
|
||||||
|
deformWorld->setUseProjection(true);
|
||||||
}
|
}
|
||||||
#endif //SKIP_DEFORMABLE_BODY
|
#endif //SKIP_DEFORMABLE_BODY
|
||||||
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
|
#ifndef SKIP_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
|
||||||
@ -9646,7 +9650,6 @@ bool PhysicsServerCommandProcessor::processReducedDeformable(const UrdfReducedDe
|
|||||||
// collion between deformable and deformable and self-collision
|
// collion between deformable and deformable and self-collision
|
||||||
// rsb->m_cfg.collisions |= btSoftBody::fCollision::VF_DD;
|
// rsb->m_cfg.collisions |= btSoftBody::fCollision::VF_DD;
|
||||||
rsb->setCollisionFlags(0);
|
rsb->setCollisionFlags(0);
|
||||||
rsb->setTotalMass(reduced_deformable.m_mass);
|
|
||||||
rsb->setSelfCollision(useSelfCollision);
|
rsb->setSelfCollision(useSelfCollision);
|
||||||
rsb->initializeFaceTree();
|
rsb->initializeFaceTree();
|
||||||
}
|
}
|
||||||
@ -9681,6 +9684,11 @@ bool PhysicsServerCommandProcessor::processReducedDeformable(const UrdfReducedDe
|
|||||||
deformWorld->addSoftBody(rsb);
|
deformWorld->addSoftBody(rsb);
|
||||||
deformWorld->getSolverInfo().m_deformable_erp = reduced_deformable.m_erp;
|
deformWorld->getSolverInfo().m_deformable_erp = reduced_deformable.m_erp;
|
||||||
deformWorld->getSolverInfo().m_deformable_cfm = reduced_deformable.m_cfm;
|
deformWorld->getSolverInfo().m_deformable_cfm = reduced_deformable.m_cfm;
|
||||||
|
deformWorld->getSolverInfo().m_friction = reduced_deformable.m_friction;
|
||||||
|
deformWorld->getSolverInfo().m_splitImpulse = false;
|
||||||
|
deformWorld->setImplicit(false);
|
||||||
|
deformWorld->setLineSearch(false);
|
||||||
|
deformWorld->setUseProjection(false);
|
||||||
}
|
}
|
||||||
else
|
else
|
||||||
#endif //SKIP_DEFORMABLE_BODY
|
#endif //SKIP_DEFORMABLE_BODY
|
||||||
|
Loading…
Reference in New Issue
Block a user