Undesired oscillatory, bouncing, low friction behavior of Robotiq 2F-140 gripper closing mechanism

  Kiến thức lập trình

When I simulate grasping of objects with the Robotiq 2F-140 gripper the gripper closing mechanism exhibits oscillatory low friction behavior as you can see in this video. The two finger pads bounce back heavily after impact with the rigid object hydroelastic compliant objects (same happens with a high hydroelastic modulus “rigid” and low to medium hydroelastic modulus).

While in reality the gripper closes quite slowly and does not normally oscillate (the finger pads do not bounce back).

The first method I tried to use was to increase the rotational inertia defined in the robotiq URDF file

    <actuator name="finger_joint_motor">
      <mechanicalReduction>1</mechanicalReduction>
      <drake:rotor_inertia value="0.045"/>
      <drake:gear_ratio value="20"/>
    </actuator>

The highest I could go was the above 0.045. It starts to take a unrealistic long time for the gripper to close and it still does oscillate quite a bit. The specific commit and URDF file used for this is here (steps to reproduce are listed later).

I also tried bigger forces in combination with raising the rotational inertia and it never erased the oscillatory behavior.

The next thing that I tried was to try to add friction to the joints:
I added <dynamics damping="1.0" friction="1.0"/> to

<joint name="finger_joint" type="revolute">
  <origin rpy="2.29579632679 0 0" xyz="0 -0.030601 0.054905"/>
  <parent link="robotiq_arg2f_base_link"/>
  <child link="left_outer_knuckle"/>
  <axis xyz="-1 0 0"/>
  <limit effort="1000" lower="0" upper="0.7" velocity="2.0"/>
  <dynamics damping="1.0" friction="1.0"/>
</joint>

for which I got

warning: A joint has specified a non-zero value for the 'friction' attribute of a joint/dynamics tag. MultibodyPlant does not currently support non-zero joint friction.

I guessed that this extra friction/ damping feature was only implementable with drake:joint after I read some documentation. But this fails also for my particular case , because I use mimic tags in the robotiq 140 URDF:

Changing

  <joint name="finger_joint" type="revolute">
    <origin rpy="2.29579632679 0 0" xyz="0 -0.030601 0.054905"/>
    <parent link="robotiq_arg2f_base_link"/>
    <child link="left_outer_knuckle"/>
    <axis xyz="-1 0 0"/>
    <limit effort="1000" lower="0" upper="0.7" velocity="2.0"/>
  </joint>

to

  <drake:joint name="finger_joint" type="planar">
    <origin rpy="2.29579632679 0 0" xyz="0 -0.030601 0.054905"/>
    <parent link="robotiq_arg2f_base_link"/>
    <child link="left_outer_knuckle"/>
    <axis xyz="-1 0 0"/>
    <limit effort="1000" lower="0" upper="0.7" velocity="2.0"/>
    <dynamics damping="100.0 100.0 100.0" friction="100.0"/>
  </drake:joint>

yields

error: Joint 'left_inner_knuckle_joint' which has 1 DOF cannot mimic joint 'finger_joint' which has 3 DOF.

since planar joint – the most fitting joint type – is defined with 3 DOF.

I also tried without success to add friction between the links in the gripper with Point contact, by setting drake:point_contact_stiffness and drake:mu_static and drake:mu_dynamic for every link (except finger pads)

      <drake:proximity_properties>
        <drake:point_contact_stiffness value="100"/>
        <drake:mu_dynamic value="10"/>
        <drake:mu_static value="10"/>
      </drake:proximity_properties>

and to do so analagously without success with hydroelastic friction properties for every link

      <drake:proximity_properties>
        <drake:rigid_hydroelastic/>
        <drake:hunt_crossley_dissipation value="100"/>
        <drake:relaxation_time value="100"/>
      </drake:proximity_properties>

Here is a good overview of the additional URDFs detailing the changes I tried.

I think maybe the last two methods don’t work, because we use the drake:collision_filter_group

    <drake:collision_filter_group name="finger_1">
      <drake:member link="left_outer_knuckle"/>
      <drake:member link="left_outer_finger"/>
      <drake:member link="left_inner_finger"/>
      <drake:member link="left_inner_knuckle"/>
      <drake:ignored_collision_filter_group name="finger_1"/>
    </drake:collision_filter_group>
    <drake:collision_filter_group name="finger_2">
      <drake:member link="right_outer_knuckle"/>
      <drake:member link="right_outer_finger"/>
      <drake:member link="right_inner_finger"/>
      <drake:member link="right_inner_knuckle"/>
      <drake:ignored_collision_filter_group name="finger_2"/>
    </drake:collision_filter_group>

I tried playing around with that and every change to that resulted in the gripper being just completely stuck with itself.

However, I have stumbled upon a somewhat remedying simulation scenario when I set the simulation to use kSap
plant.set_discrete_contact_approximation( drake::multibody::DiscreteContactApproximation::kSap);. The resulting behavior is that the gripper stops upon impact (like desired), but even a ridiculously high hydroelastic modulus does not prevent the finger pads to sink in quite deeply into the object as if the object were a sponge. A very high hydroelastic modulus results with kSimilar or kLagged for the object to be almost like rigid, but here with kSap it could not be achieved anymore however large the modulus value. The specific commit for this simulation setup is here.

Have I missed something in my approaches? What are some other approaches to try to solve this problem?

Thank you very much for your invaluable time and effort in advance.

Steps to reproduce
  • git clone [email protected]:hedaniel7/drake.git
  • cd drake
  • git checkout VanillaDrakeWithIssue19842Mods
  • git checkout e890ad5beca6be2f01954abd1bfd01212cba5287
  • copy the respective URDF (examples/simple_gripper/robotiq_140_gripper_drake_joints.urdf, robotiq_140_gripper_hydroelastic_joints.urdf , robotiq_140_gripper_point_contact_stiffness.urdf ) or respective parts of it into examples/simple_gripper/robotiq_140_gripper.urdf if wanted
  • bazel run //examples/simple_gripper:robotiq_140_shape_completion_integration -- --position="0.0237874, -0.0332736, 0.130206" --orientation="0.454149, 0.890181, -0.0290807, 0.0219256"
Update after Felix’s suggestion

Upon suggestion by Felix, I changed the links to be hydroelastic compliant and raise the drake:hunt_crossley_dissipation. That alone also did nothing. I thought because we using the drake:collision_filter_group the parts are not even touching.

Then I discovered that with the now hydroelastic compliant links, changing drake:collision_filter_group would not result in a complete stuck gripper. The gripper would at least move, albeit gripper parts were not resembling the real-world grasping behavior anymore and moved more chaotically and loose if you remove all collision filter groups in the URDF.
I experimented changing the collision filter groups again in a certain way, where I would only remove <drake:member link="left_inner_finger"/> and <drake:member link="right_inner_finger"/>, resulting in

  <drake:collision_filter_group name="finger_1">
    <drake:member link="left_outer_finger"/>
    <drake:member link="left_inner_finger"/>
    <drake:member link="left_inner_knuckle"/>
    <drake:ignored_collision_filter_group name="finger_1"/>
  </drake:collision_filter_group>
  <drake:collision_filter_group name="finger_2">
    <drake:member link="right_outer_finger"/>
    <drake:member link="right_inner_finger"/>
    <drake:member link="right_inner_knuckle"/>
    <drake:ignored_collision_filter_group name="finger_2"/>
  </drake:collision_filter_group>

The best I could manage is that there is now dissipation at the beginning of the closing mechanism. Afterwards, there is no contact and therefore no dissipation anymore and ultimately it still bounces back and oscillates. I tried this with kSimilar and kLagged. This is the relvant git commit.

Update after Alejandro’s answer

I did what Alejandro suggested in all his three steps, except for

Use margin = 1e-4 m, DefaultProximityProperties::margin

which I could not figure out how to do in the meantime (but that’s not the main point here, anyway). Because the second predicted “shape completed” (referring to the outcome of a mesh prediction neural network called shape completion which generates/predicts meshes from point cloud data) mesh I use and which you can see in the above videos falls over after fixing its inertia, I have recorded simulation results with both a stable mesh substitute (normal speed, 15% speed) and the falling over mesh (normal speed, 15% speed). The relevant git commits (for potential reproduction) are:

  1. Changes according to Alejandro’s steps + sim setting for stable mesh
  2. Sim setting for mesh, which falls over

The oscialltory, bouncing behavior appears to be reduced a lot with only these changes.

Are there additional steps/approaches to try to reduce it even more?

2nd update for Alejandro

I think there is no update needed to run exactly the two simulation conditions after your parameter suggestion described above in the update section. The following steps will do:

  • git clone [email protected]:hedaniel7/drake.git
  • cd drake
  • git checkout VanillaDrakeWithIssue19842Mods
  • git checkout 825917b45474e38fe5d95dc4d54afd3f4b98bca6 (stable standing mesh, but guessed size)
  • Optional: For Simulation of falling down mesh(git checkout 9bd599c17a29e4cd65e0670749b0ae36214afc8f (falling down, but real-sized mesh))
  • bazel run //examples/simple_gripper:robotiq_140_shape_completion_integration -- --position="0.0237874, -0.0332736, 0.130206" --orientation="0.454149, 0.890181, -0.0290807, 0.0219256" (This works for both meshes in the above commits)

Thank you very much again for looking into my code. This is a very kind gesture of yours and I do not take it for granted.

2

At a glance, from the video, I see several problems in this sim:

  1. The manipuland moves in a strange way, my guess is that inertia values and COM are off.
  2. The bouncing behavior as you identified it.
  3. The contact patch seems off compared to the visual. Maybe a lag in the visualization, but still strange.

This is what I suggest before moving forward:

  1. A great start to estimate inertia values is to use drake/bindings/pydrake/multibody/fix_inertia.py. See docs.
  2. For (first guess) contact parameters I suggest:
    1. Point contact stiffness 1e5 N/m. (if point contact is used)
    2. Hydroelastic modulus 1e5 to 1e6 Pa (somewhat soft, but I imagine you have rubber pads). For stiff objects, 1e7 Pa works best.
    3. Hunt&Crossley dissipation, 50 s/m.
    4. Use the “similar” approximation, DiscreteContactApproximation::kSimilar.
    5. Use margin = 1e-4 m, DefaultProximityProperties::margin.
  3. To verify the contact geomety matches the visual, use drake/bindings/pydrake/visualization/model_visualizer.py.

Many of these parameters will become defaults in future releases. The reason we haven’t done this yet is because some defaults don’t work for everyone. But we are very close to completion. You can see an experimental progress PR here.

4

The oscillation occurs because there is no energy drained from the system (i.e. there is barely any damping).

In an actual gripper, potential and kinetic energy is converted to heat mainly by friction in the joints and during the deformation of contact surfaces of the gripped object and the gripper pads.

As you statet, joint friction seems not to be supported which makes things a bit harder and leaves only the damping propertys of the contact and deformation process. Luckily, drake offers the Hunt-Crossley dissipation property for Hydroelastic contact. Try to increase the value for that dissipation while maintaining a non ridgid contact model.

Theme wordpress giá rẻ Theme wordpress giá rẻ Thiết kế website Kho Theme wordpress Kho Theme WP Theme WP

LEAVE A COMMENT