diff --git a/examples/RoboticsLearning/GripperGraspExample.cpp b/examples/RoboticsLearning/GripperGraspExample.cpp index 08cc463ca..33b24eda7 100644 --- a/examples/RoboticsLearning/GripperGraspExample.cpp +++ b/examples/RoboticsLearning/GripperGraspExample.cpp @@ -377,7 +377,7 @@ public: { b3RobotSimLoadFileArgs args(""); 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_forceOverrideFixedBase = false; args.m_useMultiBody = false; @@ -388,7 +388,7 @@ public: { b3RobotSimLoadFileArgs args(""); 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_forceOverrideFixedBase = false; args.m_useMultiBody = false; @@ -399,7 +399,7 @@ public: { b3RobotSimLoadFileArgs args(""); 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_forceOverrideFixedBase = true; args.m_useMultiBody = true; diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index bd497b494..0191b5f69 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -1658,7 +1658,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm pm->m_kLST = 1.0; pm->m_flags -= btSoftBody::fMaterial::DebugDraw; psb->generateBendingConstraints(2,pm); - psb->m_cfg.piterations = 15; + psb->m_cfg.piterations = 20; psb->m_cfg.kDF = 0.5; psb->randomizeConstraints(); psb->rotate(btQuaternion(0.70711,0,0,0.70711));