1

We are trying to simulate the contact of a two-link brachiating robot with unactuated(hook-shaped) grippers on the support bar of a horizontal ladder. The following image(img4.png) is the .obj file of one of the links, opened in MeshLab. More details may be found at: https://github.com/dfki-ric-underactuated-lab/acromonk

To simplify our task, we are first trying to simulate the hooking motion when the robot falls(due to gravity) over the support bar. The robot is given an initial configuration such that the gripper is exactly above the support bar. Theoretically, as the robot falls, the gripper clings onto the support bar and starts oscillating.

The problem is that gripper does not cling onto the support bar(as shown in the video, hi.gif, hell.gif, and images, img1.png, img2.png, & img3.png). We believe that the simulator applies a collision model such that gripper hook is completely enveloped, and the cavity of the hook is disregarded(img5.png). This is happening inspite of including the .obj file shown above as the geometry mesh in the collision tag of the robot URDF. How do we correct this, and make the simulator consider the mesh file of the link as the collison model?

P.S. The other parts of the horizontal ladder don't have their collision model yet. Only the collision models of the robot and the support bar are active.

img4.png [img1.png[img2.png[img3.pngimg5.png](https://i.stack.imgur.com/DNYTq.png)](https://i.stack.imgur.com/jmgnd.png)](https://i.stack.imgur.com/wU7WN.png)

hi.gif

Thanks in advance, Regards.

2 Answers2

1

That's a great robot. Let's see if we can't get you set up properly.

tl;dr: Use hydroelastic contact; make the gripper rigid and make the cylindrical bars compliant.

Details

I'm assuming that you're using the default configuration for simulation. This means that you're using point contact to model contact between objects. That means that you're using this query. This query has the property that arbitrary mesh objects are represented by their contact hulls. Exactly what you're seeing.

Drake has another, novel method for evaluating contact between bodies: hydroelastic contact. The linked guide should walk you through everything you need to do to tweak your simulation so that your hook is nicely interacting with the bars. The steps are along the lines of:

  1. Tweak your URDF to introduce the important Drake-specific hydroelastic properties. (MultibodyPlant is configured to make use of that information by default.)
  2. Add flags to the hook to make it have a rigid hydroelastic representation (i.e., <drake:compliant_hydroelastic/>).
  3. Replace the mesh cylinders with <cylinder> declarations that you can specifically declare to be <drake:compliant_hydroelastic/>.

The rigid hook will interact with the compliant rods without any recourse to the convex hull.

I'd also recommend configuring the MultibodyPlant in discrete mode and also consider setting the contact solver to SAP.


If hydroelastic contact proves problematic, you'll have to switch to a convex decomposition of your hook. Some Drake users have had success using v-hacd to do the offline decomposition and using the resultant family of geometries in the URDF as the set of collision geometries.

Sean Curtis
  • 1,425
  • 7
  • 8
  • Thanks a lot Sean! Now the links are support bars are interacting as they should. If I wanted to know the contact forces between the two interacting surfaces now, how I get that information? I looked at 'PointPairContactInfo', which, as I understand, requires us to provide the contact force as an input. Could you kindly clarify this and let me know how to access the contact forces? – Grama Shourie Mar 09 '23 at 08:28
  • `MultibodyPlant` has an output port that has `ContactResults`. That contains information about the per-body-pair contacts (broken down by point and hydroelastic contact surfaces). – Sean Curtis Mar 10 '23 at 14:43
1

This is a relevant example to use rigid-compliant hydroelastic contact. It uses a non-convex rigid mesh of a dinner plate in Obj file: https://github.com/RobotLocomotion/drake/tree/master/examples/hydroelastic/ball_plate

Your hook would have the collision section similar to this non-convex 8-inch dinner plate in the above ball_plate example:

  <collision name="collision">
    <pose>0 0 0 0 0 0</pose>
    <geometry>
      <mesh>
        <uri>plate_8in_col.obj</uri>
        <scale>1.0 1.0 1.0</scale>
      </mesh>
    </geometry>
    <drake:proximity_properties>
      <drake:rigid_hydroelastic/>
    </drake:proximity_properties>
  </collision>

It's from these lines of plate_8in.sdf in the above ball_plate example.

Your support bar would be similar to the following compliant ball (you would use a cylinder instead of a sphere):

  <collision name="collision">
    <pose>0 0 0 0 0 0</pose>
    <geometry>
      <sphere>
        <radius>0.02</radius>
      </sphere>
    </geometry>
    <drake:proximity_properties>
      <drake:compliant_hydroelastic/>
      <drake:hydroelastic_modulus>5.0e6</drake:hydroelastic_modulus>
      <drake:mesh_resolution_hint>0.005</drake:mesh_resolution_hint>
    </drake:proximity_properties>
  </collision>

It is from these lines in ball.sdf in this python_ball_paddle example.

As Sean said, Hydroelastic Contact User Guide has more details.