I declared the ground place as follows,
plant.RegisterCollisionGeometry(
plant.world_body(),
X_BG,
HalfSpace(),
"ground_collision",
surface_friction)
plant.RegisterVisualGeometry(
plant.world_body(),
X_BG,
HalfSpace(),
"ground_visual",
np.array([0.5,0.5,0.5,0.0]))
and then with no explicit value for plant.set_penetration_allowance
, I managed to derive expected behavior from the robot feet (manageable amounts of penetration). Image below for reference:
The declared time step being time_step = 2e-3
Now, when I modify feet collisions to restrict the assumption of point contact, by adding a foot plane (Box(thickness=1e-3)
), the feet start penetrating a lot.
I understand that the contact model always result in penetration with the ground (Pydrake: About Penetration in discrete time simulation). I tried following the suggestion of keeping the time step to what is needed (2e-3) and started reducing the penetration allowance. However, reducing the penetration allowance does not seem to have any effect on the penetration (except that the robot flies off at the end, possible due to very high contact forces).
Modifying the box thickness does not seem to have any effect either. The only quantity that has an effect and improves (if not eliminate) unwanted penetration is reducing the time_step=5e-4
.
Is this the only way? Or is there a better way to handle this issue without having to reduce the time step?
EDIT:
Using hydroelastic contacts for the feet is what I needed. Now the behavior is as intended:
Box on box collision is a bad case for (single) point contact. Adding spheres to the corners is very reasonable if you're using the point contact model.
But it sounds like what you want is to use Drake's hydroelastic contact model. Then you'll get a beautiful pressure field over the foot. I'd recommend checking out the hydroelastic tutorial in Drake.
Typically we'd enable hydroelastic for your assets by using the hydro tags in urdf/sdf (described in the tutorial and hydro user guide). If you do want to use the
RegisterCollisionGeometry
entry point for the ground, it will look something like this:Note that you'll need to mark both the feet and the ground to be hydroelastic.