3

I would like to know how I can set the frictional properties of a body in MultibodyPlant.

More specifically, I have a model instance that has been read in from an SDF and I would like to add or change the friction properties of a particular body in that model instance.

samzapo
  • 33
  • 3

1 Answers1

2

There are several ways to set the frictional properties. In addition to your very specific question, I'm going to outline multiple workflows. (As a side note, while some of this is documented, it isn't necessarily discoverable -- or even rendered -- in the doxygen. That's an outstanding issue that needs to be addressed, for which an issue exists).

  • Define in the urdf/sdf.
    • Drake provides custom tags associated contact properties (including friction and more) with the <geometry> tag. The tags are the same across URDF/SDF but are exercised slightly differently (based on the style of SDF vs URDF). Details can be found here for sdf and here for urdf.
  • Add new geometry via the API and include friction in the definition.
    #include "drake/geometry/proximity_properties.h"
    #include "drake/multibody/plant/multibody_plant.h"
    
    // Omitting drake:: namespaces for clarity.
    MultibodyPlant<double> plant;
    // Populate plant with bodies.   
    ProximityProperties contact_props;
    AddContactMaterial({}, {}, CoulombFriction<double>(mu_s, mu_d), &contact_props);
    // Assume we've defined body, X_BG, shape, and name elsewhere.
    plant.RegisterCollisionGeometry(body, X_BG, shape, name, contact_props);
    
  • Add/Update to geometry defined in a urdf/sdf
    • In this case, we need to change the geometry definition in SceneGraph based on its association with a body. That means, starting with the Body, we need to get the GeometryId. We're going to assume that has been done and you have the GeometryId for this workflow.
    SceneGraph<double> sg;
    const GeometryId g_id = ...;
    CoulombFriction<double> friction(mu_s, mu_d);
    ProximityProperties new_props;
    const ProximityProperties* curr_props = 
        sg.model_inspector().GetProximityProperties(g_id);
    if (curr_props != nullptr) {
      new_props = *curr_props;
    }
    // Replaces old friction definition, or adds it if previously absent.
    new_props.UpdateProperty("material", "coulomb_friction", friction);
    sg.AssignRole(g_id, new_props, RoleAssign::kReplace);
    
Sean Curtis
  • 1,425
  • 7
  • 8
  • Note: the issue for making all of this more discoverable is: https://github.com/RobotLocomotion/drake/issues/13314 – Sean Curtis Jul 15 '20 at 16:07
  • Let me just add that this is thanks to the incredible effort from Joe Masterjohn in 13630 precisely per your reques @samzapo! working on body parameters now :-) – Alejandro Jul 15 '20 at 18:20