Modify the setup for grasping bunny example.

This commit is contained in:
yunfeibai 2016-11-02 12:49:51 -07:00
parent 3c37db0804
commit 295c1b7c88
2 changed files with 4 additions and 4 deletions

View File

@ -377,7 +377,7 @@ public:
{ {
b3RobotSimLoadFileArgs args(""); b3RobotSimLoadFileArgs args("");
args.m_fileName = "gripper/wsg50_one_motor_gripper_left_finger.urdf"; args.m_fileName = "gripper/wsg50_one_motor_gripper_left_finger.urdf";
args.m_startPosition.setValue(-0.05,0,0.27); args.m_startPosition.setValue(-0.1,0,0.5);
args.m_startOrientation.setEulerZYX(0,0,3.14); args.m_startOrientation.setEulerZYX(0,0,3.14);
args.m_forceOverrideFixedBase = false; args.m_forceOverrideFixedBase = false;
args.m_useMultiBody = false; args.m_useMultiBody = false;
@ -388,7 +388,7 @@ public:
{ {
b3RobotSimLoadFileArgs args(""); b3RobotSimLoadFileArgs args("");
args.m_fileName = "gripper/wsg50_one_motor_gripper_right_finger.urdf"; args.m_fileName = "gripper/wsg50_one_motor_gripper_right_finger.urdf";
args.m_startPosition.setValue(0.05,0,0.27); args.m_startPosition.setValue(0.1,0,0.5);
args.m_startOrientation.setEulerZYX(0,0,3.14); args.m_startOrientation.setEulerZYX(0,0,3.14);
args.m_forceOverrideFixedBase = false; args.m_forceOverrideFixedBase = false;
args.m_useMultiBody = false; args.m_useMultiBody = false;
@ -399,7 +399,7 @@ public:
{ {
b3RobotSimLoadFileArgs args(""); b3RobotSimLoadFileArgs args("");
args.m_fileName = "plane.urdf"; args.m_fileName = "plane.urdf";
args.m_startPosition.setValue(0,0,0); args.m_startPosition.setValue(0,0,-0.2);
args.m_startOrientation.setEulerZYX(0,0,0); args.m_startOrientation.setEulerZYX(0,0,0);
args.m_forceOverrideFixedBase = true; args.m_forceOverrideFixedBase = true;
args.m_useMultiBody = true; args.m_useMultiBody = true;

View File

@ -1658,7 +1658,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
pm->m_kLST = 1.0; 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 = 15; psb->m_cfg.piterations = 20;
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));