Step 7: Grasping simulation

You can download the file associated with this step at:
http://sofamacbuilder.lille.inria.fr/defrost/scenes/Tutorial/step7-SoftGripperGraspingSimulation/SoftGripper.py (Here, it is strongly recommended to test it on the virtual machine !!)

The simulation in SOFA reproduces grasping using a combination of constraints for frictional contact (using Coulomb's friction) and for actuators. To do this, we need to modify several elements of the simulation.

 

The simulation in SOFA allows to reproduce grasping using a combination of constraints for frictional contact (using Coulomb's friction) and for actuators. To do this, we need to modify several elements of the simulation (see SoftGripper.py)

a. Activate collision and direct simulation

In this example, we will simulate the collision response of the gripper with its environment and particularly an object that will be grasped. The first step is to activate the modules for collision detection and response in SOFA. These modules are described in more details in the documentation of SOFA. The user can modify the coefficient of friction in RuleBasedContactManager (mu=0.8). GenericConstraintSolver is able to solve, in a unified system, the constraints for collision response and the constraints (direct, non inverse) of the actuators. This is what this example illustrates:

          ##################################
          # Direct simulation
          ##################################
           rootNode.createObject('FreeMotionAnimationLoop')
           rootNode.createObject('GenericConstraintSolver', printLog='0', tolerance="1e-6", maxIterations="1000")
           rootNode.createObject('CollisionPipeline', verbose="0")
           rootNode.createObject('BruteForceDetection', name="N2")
           rootNode.createObject('RuleBasedContactManager', name="Response", response="FrictionContact", rules="0 * FrictionContact?mu=0.8" )
           rootNode.createObject('LocalMinDistance', name="Proximity", alarmDistance="4", contactDistance="3", angleCone="0.01")
      

b. Add an object that will be grasped

We add a rigid object and simulate its dynamics with a 6DoFs mechanical object. It computes the physics at the center of gravity. The mass and inertia of the object are computed by UniformMass. The component UncoupledConstraintCorrection provides the physics-based response after collision (in practice, it will use the parameters of the component UniformMass):

          ############# Grasped Object ##########
          # mechanics
           cube =directSimuNode.createChild('cube')
           cube.createObject('EulerImplicit', name='odesolver')
           cube.createObject('CGLinearSolver', name='linearSolver')
           cube.createObject('MechanicalObject', template="Rigid", scale="6", dx="60.0", dy="10", dz="8", rx="10")
           cube.createObject('UniformMass', mass='0.03 10 1000 0 0 0 1000 0 0 0 1000')
           cube.createObject('UncoupledConstraintCorrection')
      

Then, we will need to add a collision model to detect the contacts between this cube and the soft gripper. First, we load the mesh that is used for collision and create a mechanical object with it. Then, we add the collision primitives (Triangle, Line and Point) that will be tested. Finally, the collision model is linked to the behavior of the center of gravity by a RigidMapping:

          #collision
           cubeCollis = cube.createChild('cubeCollis')
           cubeCollis.createObject('MeshObjLoader', name="loader", filename="mesh/smCube27.obj", triangulate="true",  scale="6")
           cubeCollis.createObject('Mesh', src="@loader")
           cubeCollis.createObject('MechanicalObject')
           cubeCollis.createObject('Triangle')
           cubeCollis.createObject('Line')
           cubeCollis.createObject('Point')
           cubeCollis.createObject('RigidMapping')
      

In the same way, we can load an other mesh and use a mapping for the visualization:

          #visualization
           cubeVisu = cube.createChild('cubeVisu')
           cubeVisu.createObject('OglModel', name="Visual", fileMesh="mesh/smCube27.obj", color="0.0 0.5 0.5 1.0", scale="6.2")
           cubeVisu.createObject('RigidMapping')

      

c. Add a fixed floor

Now, we add a collision surface and a collision plane so that we can place the object before and after grasping:

          ################### Fix Floor #############
           planeNode = directSimuNode.createChild('Plane')
           planeNode.createObject('MeshObjLoader', name='loader', filename="mesh/floorFlat.obj", triangulate="true", rotation="0 0 270", scale =10, translation="38 0 0")
           planeNode.createObject('Mesh', src="@loader")
           planeNode.createObject('MechanicalObject', src="@loader")
           planeNode.createObject('Triangle',simulated="0", moving="0")
           planeNode.createObject('Line',simulated="0", moving="0")
        planeNode.createObject('Point',simulated="0", moving="0")
           planeNode.createObject('OglModel',name="Visual", fileMesh="mesh/floorFlat.obj", color="1 0 0 1",rotation="0 0 270", scale =10, translation="38.1 0 0")
      

d. Add collision models to the gripper

We need to put a collision surface to each finger of the soft gripper. In the graph, the collision model is a child of the node that contains the mechanical object (here, the FEM model of each finger). This surface is defined by a mesh (here finger.stl). The primitives of collision are also defined (Triangle, Line, Point). The surface motion is linked to the motion of the FEM model using a BarycentricMapping:

      
           #finger1/finger1Collis
           finger1Collis = finger1.createChild('collis')
           finger1Collis.createObject('MeshSTLLoader', name='loader', filename=path+'finger.stl', rotation="0 0 25", translation="150 0 0")
           finger1Collis.createObject('TriangleSetTopologyContainer', src='@loader', name='container')
           finger1Collis.createObject('MechanicalObject', name='collisMO', template='Vec3d')
           finger1Collis.createObject('Triangle')
           finger1Collis.createObject('Line')
           finger1Collis.createObject('Point')
           finger1Collis.createObject('BarycentricMapping')
      

e. Control the gripper

The user can interactively control the gripper using keyboard events. The definition of the controls is done using a python script.

      ####################################
       # Control of the robot with the keyboard
       rootNode.createObject('PythonScriptController', filename="controllerGripper.py", classname="controller")
       ####################################
      

To close/open the gripper, press the following keys:

  • CTRL +
  • CTRL -

Note that with MacOS, you may have to use CMD instead of CTRL . The actuator is controlled in force. The key CTRL + increases the force applied on the cable. To move the gripper, press the following keys:

  • CTRL ↑ to move it up
  • CTRL ↓ to move it down
  • CTRL ← to move it left
  • CTRL → to move it right