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.sstatic.net/DNYTq.png)](https://i.sstatic.net/jmgnd.png)](https://i.sstatic.net/wU7WN.png)
Thanks in advance, Regards.
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:
MultibodyPlant
is configured to make use of that information by default.)<drake:compliant_hydroelastic/>
).<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.