diff --git a/data/gripper/wsg50_one_motor_gripper_left_finger.urdf b/data/gripper/wsg50_one_motor_gripper_left_finger.urdf new file mode 100644 index 000000000..a5e58f6c4 --- /dev/null +++ b/data/gripper/wsg50_one_motor_gripper_left_finger.urdf @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/data/gripper/wsg50_one_motor_gripper_no_finger.sdf b/data/gripper/wsg50_one_motor_gripper_no_finger.sdf new file mode 100644 index 000000000..878b1ee14 --- /dev/null +++ b/data/gripper/wsg50_one_motor_gripper_no_finger.sdf @@ -0,0 +1,307 @@ + + + + + 0 0 0.4 3.14 0 0 + + + + + + world + base_link + + 0 0 1 + + -10 + 10 + 1 + 1 + + + 0 + 0 + 0 + 0 + + + + + + 0 0 0 0 0 0 + + 0 0 0 0 0 0 + 1.2 + + 1 + 0 + 0 + 1 + 0 + 1 + + + + + 0 0 0 0 -0 0 + + + 1 1 1 + meshes/WSG50_110.stl + + + + + + + + + + + 0 0 0.03 0 0 0 + + 0 0 0 0 0 0 + 0.1 + + 0.1 + 0 + 0 + 0.1 + 0 + 0.1 + + + + 0 0 0.01 0 0 0 + + + 0.02 0.02 0.02 + + + + + + + motor + base_link + + 0 0 1 + + -0.055 + 0.001 + 10.0 + 10.0 + + + 0 + 0 + 0 + 0 + + + + + + 0 0 0.04 0 0 0 + + 0 0 0.035 0 0 0 + 0.1 + + 0.1 + 0 + 0 + 0.1 + 0 + 0.1 + + + + -0.03 0 0.01 0 -1.2 0 + + + 0.02 0.02 0.07 + + + + + + + left_hinge + motor + + 0 1 0 + + -20.0 + 20.0 + 10 + 10 + + + 0 + 0 + 0 + 0 + + 0 + + + + + 0 0 0.04 0 0 0 + + 0 0 0.035 0 0 0 + 0.1 + + 0.1 + 0 + 0 + 0.1 + 0 + 0.1 + + + + 0.03 0 0.01 0 1.2 0 + + + 0.02 0.02 0.07 + + + + + + + right_hinge + motor + + 0 1 0 + + -20.0 + 20.0 + 10 + 10 + + + 0 + 0 + 0 + 0 + + 0 + + + + + -0.055 0 0.06 0 -0 0 + + 0 0 0.0115 0 -0 0 + 0.2 + + 0.1 + 0 + 0 + 0.1 + 0 + 0.1 + + + + + 0 0 -0.06 0 0 0 + + + 0.001 0.001 0.001 + meshes/GUIDE_WSG50_110.stl + + + + + 0 0 -0.037 0 0 0 + + + 0.001 0.001 0.001 + meshes/WSG-FMF.stl + + + + + + + + gripper_left + base_link + + 1 0 0 + + -0.01 + 0.04 + 1 + 1 + + + 0 + 0 + 0 + 0 + + + + + + 0.055 0 0.06 0 0 0 + + 0 0 0.0115 0 -0 0 + 0.2 + + 0.1 + 0 + 0 + 0.1 + 0 + 0.1 + + + + + 0 0 -0.06 0 0 3.14159 + + + 0.001 0.001 0.001 + meshes/GUIDE_WSG50_110.stl + + + + + 0 0 -0.037 0 0 3.14159 + + + 0.001 0.001 0.001 + meshes/WSG-FMF.stl + + + + + + + gripper_right + base_link + + 1 0 0 + + -0.04 + 0.01 + 1 + 1 + + + 0 + 0 + 0 + 0 + + + + + + + \ No newline at end of file diff --git a/data/gripper/wsg50_one_motor_gripper_right_finger.urdf b/data/gripper/wsg50_one_motor_gripper_right_finger.urdf new file mode 100644 index 000000000..c6257e399 --- /dev/null +++ b/data/gripper/wsg50_one_motor_gripper_right_finger.urdf @@ -0,0 +1,27 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/examples/RoboticsLearning/GripperGraspExample.cpp b/examples/RoboticsLearning/GripperGraspExample.cpp index 37e6c06a0..831255ef2 100644 --- a/examples/RoboticsLearning/GripperGraspExample.cpp +++ b/examples/RoboticsLearning/GripperGraspExample.cpp @@ -346,7 +346,7 @@ public: if (1) { b3RobotSimLoadFileArgs args(""); - args.m_fileName = "gripper/wsg50_one_motor_gripper_new.sdf"; + args.m_fileName = "gripper/wsg50_one_motor_gripper_no_finger.sdf"; args.m_fileType = B3_SDF_FILE; args.m_useMultiBody = true; b3RobotSimLoadFileResults results; @@ -365,7 +365,7 @@ public: b3Printf("joint[%d].m_jointName=%s",i,jointInfo.m_jointName); } - for (int i=0;i<8;i++) + for (int i=0;i<6;i++) { b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY); controlArgs.m_maxTorqueValue = 0.0; @@ -374,7 +374,27 @@ 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_startOrientation.setEulerZYX(0,0,3.14); + args.m_forceOverrideFixedBase = false; + args.m_useMultiBody = false; + b3RobotSimLoadFileResults results; + m_robotSim.loadFile(args,results); + + } + { + b3RobotSimLoadFileArgs args(""); + args.m_fileName = "gripper/wsg50_one_motor_gripper_right_finger.urdf"; + args.m_startPosition.setValue(0.05,0,0.27); + args.m_startOrientation.setEulerZYX(0,0,3.14); + args.m_forceOverrideFixedBase = false; + args.m_useMultiBody = false; + b3RobotSimLoadFileResults results; + m_robotSim.loadFile(args,results); + } if (1) { b3RobotSimLoadFileArgs args(""); @@ -391,16 +411,16 @@ public: m_robotSim.loadBunny(); b3JointInfo revoluteJoint1; - revoluteJoint1.m_parentFrame[0] = -0.055; + revoluteJoint1.m_parentFrame[0] = -0.007; revoluteJoint1.m_parentFrame[1] = 0; - revoluteJoint1.m_parentFrame[2] = 0.02; + revoluteJoint1.m_parentFrame[2] = 0.0735; revoluteJoint1.m_parentFrame[3] = 0; revoluteJoint1.m_parentFrame[4] = 0; revoluteJoint1.m_parentFrame[5] = 0; revoluteJoint1.m_parentFrame[6] = 1.0; revoluteJoint1.m_childFrame[0] = 0; revoluteJoint1.m_childFrame[1] = 0; - revoluteJoint1.m_childFrame[2] = 0; + revoluteJoint1.m_childFrame[2] = -0.05; revoluteJoint1.m_childFrame[3] = 0; revoluteJoint1.m_childFrame[4] = 0; revoluteJoint1.m_childFrame[5] = 0; @@ -410,16 +430,16 @@ public: revoluteJoint1.m_jointAxis[2] = 0.0; revoluteJoint1.m_jointType = ePoint2PointType; b3JointInfo revoluteJoint2; - revoluteJoint2.m_parentFrame[0] = 0.055; + revoluteJoint2.m_parentFrame[0] = 0.007; revoluteJoint2.m_parentFrame[1] = 0; - revoluteJoint2.m_parentFrame[2] = 0.02; + revoluteJoint2.m_parentFrame[2] = 0.0735; revoluteJoint2.m_parentFrame[3] = 0; revoluteJoint2.m_parentFrame[4] = 0; revoluteJoint2.m_parentFrame[5] = 0; revoluteJoint2.m_parentFrame[6] = 1.0; revoluteJoint2.m_childFrame[0] = 0; revoluteJoint2.m_childFrame[1] = 0; - revoluteJoint2.m_childFrame[2] = 0; + revoluteJoint2.m_childFrame[2] = -0.05; revoluteJoint2.m_childFrame[3] = 0; revoluteJoint2.m_childFrame[4] = 0; revoluteJoint2.m_childFrame[5] = 0; @@ -428,8 +448,128 @@ public: revoluteJoint2.m_jointAxis[1] = 0.0; revoluteJoint2.m_jointAxis[2] = 0.0; revoluteJoint2.m_jointType = ePoint2PointType; - m_robotSim.createJoint(0, 2, 0, 4, &revoluteJoint1); - m_robotSim.createJoint(0, 3, 0, 6, &revoluteJoint2); + b3JointInfo revoluteJoint3; + revoluteJoint3.m_parentFrame[0] = -0.207; + revoluteJoint3.m_parentFrame[1] = 0; + revoluteJoint3.m_parentFrame[2] = 0.0735; + revoluteJoint3.m_parentFrame[3] = 0; + revoluteJoint3.m_parentFrame[4] = 0; + revoluteJoint3.m_parentFrame[5] = 0; + revoluteJoint3.m_parentFrame[6] = 1.0; + revoluteJoint3.m_childFrame[0] = -0.2; + revoluteJoint3.m_childFrame[1] = 0; + revoluteJoint3.m_childFrame[2] = -0.05; + revoluteJoint3.m_childFrame[3] = 0; + revoluteJoint3.m_childFrame[4] = 0; + revoluteJoint3.m_childFrame[5] = 0; + revoluteJoint3.m_childFrame[6] = 1.0; + revoluteJoint3.m_jointAxis[0] = 1.0; + revoluteJoint3.m_jointAxis[1] = 0.0; + revoluteJoint3.m_jointAxis[2] = 0.0; + revoluteJoint3.m_jointType = ePoint2PointType; + b3JointInfo revoluteJoint4; + revoluteJoint4.m_parentFrame[0] = 0.207; + revoluteJoint4.m_parentFrame[1] = 0; + revoluteJoint4.m_parentFrame[2] = 0.0735; + revoluteJoint4.m_parentFrame[3] = 0; + revoluteJoint4.m_parentFrame[4] = 0; + revoluteJoint4.m_parentFrame[5] = 0; + revoluteJoint4.m_parentFrame[6] = 1.0; + revoluteJoint4.m_childFrame[0] = 0.2; + revoluteJoint4.m_childFrame[1] = 0; + revoluteJoint4.m_childFrame[2] = -0.05; + revoluteJoint4.m_childFrame[3] = 0; + revoluteJoint4.m_childFrame[4] = 0; + revoluteJoint4.m_childFrame[5] = 0; + revoluteJoint4.m_childFrame[6] = 1.0; + revoluteJoint4.m_jointAxis[0] = 1.0; + revoluteJoint4.m_jointAxis[1] = 0.0; + revoluteJoint4.m_jointAxis[2] = 0.0; + revoluteJoint4.m_jointType = ePoint2PointType; + b3JointInfo revoluteJoint5; + revoluteJoint5.m_parentFrame[0] = -0.007; + revoluteJoint5.m_parentFrame[1] = 0; + revoluteJoint5.m_parentFrame[2] = 0.2735; + revoluteJoint5.m_parentFrame[3] = 0; + revoluteJoint5.m_parentFrame[4] = 0; + revoluteJoint5.m_parentFrame[5] = 0; + revoluteJoint5.m_parentFrame[6] = 1.0; + revoluteJoint5.m_childFrame[0] = 0; + revoluteJoint5.m_childFrame[1] = 0; + revoluteJoint5.m_childFrame[2] = 0.15; + revoluteJoint5.m_childFrame[3] = 0; + revoluteJoint5.m_childFrame[4] = 0; + revoluteJoint5.m_childFrame[5] = 0; + revoluteJoint5.m_childFrame[6] = 1.0; + revoluteJoint5.m_jointAxis[0] = 1.0; + revoluteJoint5.m_jointAxis[1] = 0.0; + revoluteJoint5.m_jointAxis[2] = 0.0; + revoluteJoint5.m_jointType = ePoint2PointType; + b3JointInfo revoluteJoint6; + revoluteJoint6.m_parentFrame[0] = 0.007; + revoluteJoint6.m_parentFrame[1] = 0; + revoluteJoint6.m_parentFrame[2] = 0.2735; + revoluteJoint6.m_parentFrame[3] = 0; + revoluteJoint6.m_parentFrame[4] = 0; + revoluteJoint6.m_parentFrame[5] = 0; + revoluteJoint6.m_parentFrame[6] = 1.0; + revoluteJoint6.m_childFrame[0] = 0; + revoluteJoint6.m_childFrame[1] = 0; + revoluteJoint6.m_childFrame[2] = 0.15; + revoluteJoint6.m_childFrame[3] = 0; + revoluteJoint6.m_childFrame[4] = 0; + revoluteJoint6.m_childFrame[5] = 0; + revoluteJoint6.m_childFrame[6] = 1.0; + revoluteJoint6.m_jointAxis[0] = 1.0; + revoluteJoint6.m_jointAxis[1] = 0.0; + revoluteJoint6.m_jointAxis[2] = 0.0; + revoluteJoint6.m_jointType = ePoint2PointType; + b3JointInfo revoluteJoint7; + revoluteJoint7.m_parentFrame[0] = -0.055; + revoluteJoint7.m_parentFrame[1] = 0; + revoluteJoint7.m_parentFrame[2] = 0.02; + revoluteJoint7.m_parentFrame[3] = 0; + revoluteJoint7.m_parentFrame[4] = 0; + revoluteJoint7.m_parentFrame[5] = 0; + revoluteJoint7.m_parentFrame[6] = 1.0; + revoluteJoint7.m_childFrame[0] = 0; + revoluteJoint7.m_childFrame[1] = 0; + revoluteJoint7.m_childFrame[2] = 0; + revoluteJoint7.m_childFrame[3] = 0; + revoluteJoint7.m_childFrame[4] = 0; + revoluteJoint7.m_childFrame[5] = 0; + revoluteJoint7.m_childFrame[6] = 1.0; + revoluteJoint7.m_jointAxis[0] = 1.0; + revoluteJoint7.m_jointAxis[1] = 0.0; + revoluteJoint7.m_jointAxis[2] = 0.0; + revoluteJoint7.m_jointType = ePoint2PointType; + b3JointInfo revoluteJoint8; + revoluteJoint8.m_parentFrame[0] = 0.055; + revoluteJoint8.m_parentFrame[1] = 0; + revoluteJoint8.m_parentFrame[2] = 0.02; + revoluteJoint8.m_parentFrame[3] = 0; + revoluteJoint8.m_parentFrame[4] = 0; + revoluteJoint8.m_parentFrame[5] = 0; + revoluteJoint8.m_parentFrame[6] = 1.0; + revoluteJoint8.m_childFrame[0] = 0; + revoluteJoint8.m_childFrame[1] = 0; + revoluteJoint8.m_childFrame[2] = 0; + revoluteJoint8.m_childFrame[3] = 0; + revoluteJoint8.m_childFrame[4] = 0; + revoluteJoint8.m_childFrame[5] = 0; + revoluteJoint8.m_childFrame[6] = 1.0; + revoluteJoint8.m_jointAxis[0] = 1.0; + revoluteJoint8.m_jointAxis[1] = 0.0; + revoluteJoint8.m_jointAxis[2] = 0.0; + revoluteJoint8.m_jointType = ePoint2PointType; + m_robotSim.createJoint(0, 4, 1, 0, &revoluteJoint1); + m_robotSim.createJoint(0, 5, 2, 0, &revoluteJoint2); + m_robotSim.createJoint(0, 4, 1, 0, &revoluteJoint3); + m_robotSim.createJoint(0, 5, 2, 0, &revoluteJoint4); + m_robotSim.createJoint(0, 4, 1, 0, &revoluteJoint5); + m_robotSim.createJoint(0, 5, 2, 0, &revoluteJoint6); + m_robotSim.createJoint(0, 2, 0, 4, &revoluteJoint7); + m_robotSim.createJoint(0, 3, 0, 5, &revoluteJoint8); } } virtual void exitPhysics() @@ -479,7 +619,7 @@ public: int fingerJointIndices[2]={0,1}; double fingerTargetVelocities[2]={sGripperVerticalVelocity,sGripperClosingTargetVelocity }; - double maxTorqueValues[2]={50.0,50.0}; + double maxTorqueValues[2]={50.0,10.0}; for (int i=0;i<2;i++) { b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY); diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 86d3e2ac5..b8962bb62 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -1643,14 +1643,14 @@ 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 = 2; + psb->m_cfg.piterations = 15; psb->m_cfg.kDF = 0.5; psb->randomizeConstraints(); psb->rotate(btQuaternion(0.70711,0,0,0.70711)); - psb->translate(btVector3(0,0,3.0)); + psb->translate(btVector3(0,0,1.0)); psb->scale(btVector3(0.1,0.1,0.1)); - psb->setTotalMass(1,true); - psb->getCollisionShape()->setMargin(0.01); + psb->setTotalMass(0.1,true); + psb->getCollisionShape()->setMargin(0.02); m_data->m_dynamicsWorld->addSoftBody(psb); #endif @@ -3772,4 +3772,4 @@ void PhysicsServerCommandProcessor::createDefaultRobotAssets() } } -} \ No newline at end of file +}