diff --git a/bindings/pydrake/multibody/plant_py.cc b/bindings/pydrake/multibody/plant_py.cc index 566f8d452a8c..14966d5f27e4 100644 --- a/bindings/pydrake/multibody/plant_py.cc +++ b/bindings/pydrake/multibody/plant_py.cc @@ -129,6 +129,8 @@ void DoScalarDependentDefinitions(py::module m, T) { .def("dynamic_friction", &Class::dynamic_friction, cls_doc.dynamic_friction.doc); + AddValueInstantiation>(m); + m.def("CalcContactFrictionFromSurfaceProperties", [](const multibody::CoulombFriction& surface_properties1, const multibody::CoulombFriction& surface_properties2) { @@ -597,13 +599,24 @@ void DoScalarDependentDefinitions(py::module m, T) { py::arg("body"), py::arg("X_BG"), py::arg("shape"), py::arg("name"), py::arg("diffuse_color"), py::arg("scene_graph") = nullptr, doc_iso3_deprecation) + .def("RegisterCollisionGeometry", + py::overload_cast&, const RigidTransform&, + const geometry::Shape&, const std::string&, + geometry::ProximityProperties>( + &Class::RegisterCollisionGeometry), + py::arg("body"), py::arg("X_BG"), py::arg("shape"), py::arg("name"), + py::arg("properties"), + cls_doc.RegisterCollisionGeometry + .doc_5args_body_X_BG_shape_name_properties) .def("RegisterCollisionGeometry", py::overload_cast&, const RigidTransform&, const geometry::Shape&, const std::string&, const CoulombFriction&>( &Class::RegisterCollisionGeometry), py::arg("body"), py::arg("X_BG"), py::arg("shape"), py::arg("name"), - py::arg("coulomb_friction"), cls_doc.RegisterCollisionGeometry.doc) + py::arg("coulomb_friction"), + cls_doc.RegisterCollisionGeometry + .doc_5args_body_X_BG_shape_name_coulomb_friction) .def("get_source_id", &Class::get_source_id, cls_doc.get_source_id.doc) .def("get_geometry_query_input_port", &Class::get_geometry_query_input_port, py_reference_internal, diff --git a/bindings/pydrake/multibody/test/plant_test.py b/bindings/pydrake/multibody/test/plant_test.py index aca2b2975de5..e26271ce4ced 100644 --- a/bindings/pydrake/multibody/test/plant_test.py +++ b/bindings/pydrake/multibody/test/plant_test.py @@ -63,6 +63,7 @@ GeometryId, Role, PenetrationAsPointPair_, + ProximityProperties, SceneGraph_, SignedDistancePair_, SignedDistanceToPoint_, @@ -182,6 +183,19 @@ def test_multibody_plant_construction_api(self, T): self.assertEqual(plant.default_coulomb_friction( plant.GetCollisionGeometriesForBody(body)[0] ).dynamic_friction(), 0.5) + explicit_props = ProximityProperties() + explicit_props.AddProperty("material", "coulomb_friction", + CoulombFriction(1.1, 0.8)) + plant.RegisterCollisionGeometry( + body=body, X_BG=body_X_BG, shape=box, + name="new_body_collision2", properties=explicit_props) + self.assertGreater(plant.num_collision_geometries(), 1) + self.assertEqual(plant.default_coulomb_friction( + plant.GetCollisionGeometriesForBody(body)[1] + ).static_friction(), 1.1) + self.assertEqual(plant.default_coulomb_friction( + plant.GetCollisionGeometriesForBody(body)[1] + ).dynamic_friction(), 0.8) @numpy_compare.check_all_types def test_multibody_plant_api_via_parsing(self, T): diff --git a/examples/scene_graph/simple_contact_surface_vis.cc b/examples/scene_graph/simple_contact_surface_vis.cc index 4b82c5dee27b..b210edf95947 100644 --- a/examples/scene_graph/simple_contact_surface_vis.cc +++ b/examples/scene_graph/simple_contact_surface_vis.cc @@ -99,7 +99,8 @@ class MovingBall final : public LeafSystem { make_unique(1.0), "ball")); ProximityProperties prox_props; - prox_props.AddProperty(geometry::kMaterialGroup, geometry::kElastic, 1e8); + prox_props.AddProperty(geometry::internal::kMaterialGroup, + geometry::internal::kElastic, 1e8); AddSoftHydroelasticProperties(FLAGS_length, &prox_props); scene_graph->AssignRole(source_id_, geometry_id_, prox_props); @@ -250,7 +251,8 @@ int do_main() { X_WB, make_unique(edge_len, edge_len, edge_len), "box")); ProximityProperties rigid_props; // A rigid hydroelastic geometry must have an infinite elastic modulus. - rigid_props.AddProperty(geometry::kMaterialGroup, geometry::kElastic, + rigid_props.AddProperty(geometry::internal::kMaterialGroup, + geometry::internal::kElastic, std::numeric_limits::infinity()); AddRigidHydroelasticProperties(edge_len, &rigid_props); scene_graph.AssignRole(source_id, ground_id, rigid_props); diff --git a/geometry/geometry_roles.h b/geometry/geometry_roles.h index 7d2561e7d6a2..cc1525aef8cc 100644 --- a/geometry/geometry_roles.h +++ b/geometry/geometry_roles.h @@ -144,6 +144,8 @@ namespace geometry { /** The set of properties for geometry used in a _proximity_ role. + Examples of functionality that depends on the proximity role: - n/a */ diff --git a/geometry/proximity_properties.cc b/geometry/proximity_properties.cc index 015b77d30c4a..68dcf190ed4e 100644 --- a/geometry/proximity_properties.cc +++ b/geometry/proximity_properties.cc @@ -2,26 +2,33 @@ namespace drake { namespace geometry { +namespace internal { const char* const kMaterialGroup = "material"; const char* const kElastic = "elastic_modulus"; +const char* const kFriction = "coulomb_friction"; +const char* const kHcDissipation = "hunt_crossley_dissipation"; const char* const kHydroGroup = "hydroelastic"; const char* const kRezHint = "resolution_hint"; +} // namespace internal + // NOTE: Although these functions currently do the same thing, we're leaving // the two functions in place to facilitate future differences. void AddRigidHydroelasticProperties(double resolution_hint, ProximityProperties* properties) { DRAKE_DEMAND(properties); - properties->AddProperty(kHydroGroup, kRezHint, resolution_hint); + properties->AddProperty(internal::kHydroGroup, internal::kRezHint, + resolution_hint); } void AddSoftHydroelasticProperties(double resolution_hint, ProximityProperties* properties) { DRAKE_DEMAND(properties); - properties->AddProperty(kHydroGroup, kRezHint, resolution_hint); + properties->AddProperty(internal::kHydroGroup, internal::kRezHint, + resolution_hint); } } // namespace geometry diff --git a/geometry/proximity_properties.h b/geometry/proximity_properties.h index c0f67d13514c..042225587f7f 100644 --- a/geometry/proximity_properties.h +++ b/geometry/proximity_properties.h @@ -11,6 +11,7 @@ namespace drake { namespace geometry { +namespace internal { /** @name Declaring general contact material properties @@ -18,12 +19,22 @@ namespace geometry { SceneGraph depends on. These are not the exhaustive set of contact material properties that downstream consumers (e.g., MultibodyPlant) may require. + As the namespace indicates, these are for internal use only, so Drake entities + can implicitly coordinate the values they use to define proximity properties. + These strings don't suggest what constitutes a valid property *value*. For + those definitions, one should refer to the consumer of the properties (as + called out in the documentation of the ProximityProperties class). + The material properties come from the child tag. E.g., - ```xml + @code{xml} ... @@ -70,7 +71,7 @@ std::unique_ptr MakeGeometryInstanceFromSdfVisual( r_e g_e b_e a_e - ``` + @endcode An instance of geometry::IllustrationProperties will always be returned. If there is no material tag, no material property tags, or no successfully @@ -84,6 +85,54 @@ geometry::IllustrationProperties MakeVisualPropertiesFromSdfVisual( math::RigidTransformd MakeGeometryPoseFromSdfCollision( const sdf::Collision& sdf_collision); +/** Parses the drake-relevant collision properties from a element. + + Specifically, looks for tag to find drake-specific + geometry collision (or "proximity") properties. The set of tags are enumerated + in the table below. Each tag should be of the form: + + @code{xml} + real_value + @endcode + + As long as no exceptions are thrown, the function is guaranteed to return + a valid instance of ProximityProperties. + + Mapping from SDF tag to geometry property. See + @ref YET_TO_BE_WRITTEN_HYDROELATIC_GEOMETRY_MODULE for details on the semantics + of these properties. + | Tag | Group | Property | Notes | + | :------------------------------: | :----------: | :-----------------------: | :---------------------------------------------: | + | drake:mesh_resolution_hint | hydroelastic | resolution_hint | Required for hydroelastic contact. | + | drake:elastic_modulus | material | elastic_modulus | ∞ for rigid hydrolelastic models; < ∞ for soft. | + | drake:hunt_crossley_dissipation | material | hunt_crossley_dissipation | | + | drake:mu_dynamic | material | coulomb_friction | See note below on friction. | + | drake:mu_static | material | coulomb_friction | See note below on friction. | + +

Coefficients of friction

+ + Parsing coefficients of friction has a relatively complicated protocol: + + 1. If one of `` *or* `` is present, the + property of type CoulombFriction will be instantiated with both + values initialized to the single value. An exception will be thrown + - if the value is negative. + 2. If both `` and `` tags are present, the + CoulombFriction will contain both values. An exception will be + thrown if: + - either value is negative, or + - `mu_dynamic` is greater than `mu_static`. + 3. If *both* tags are missing, the parser will look for two coefficients + in the SDF tag path: `` and + ``. + a. See MakeCoulombFrictionFromSdfCollisionOde() for failure modes. + 4. If no meaningful friction coefficients are found, a default value will be + created (see default_friction()). + As long as no exception is thrown, the resulting ProximityProperties will have + the ('material', 'coulomb_friction') property. */ +geometry::ProximityProperties MakeProximityPropertiesForCollision( + const sdf::Collision& sdf_collision); + /** Parses friction coefficients from `sdf_collision`. This method looks for the definitions specific to ODE, as given by the SDF specification in ``. Drake understands @@ -101,8 +150,8 @@ math::RigidTransformd MakeGeometryPoseFromSdfCollision( ``` - If a `` is not found, it returns the coefficients for a - frictionless surface. If `` is found, all other nested elements + If a `` is not found, it returns arbitrary default coefficients + (typically mu = mu2 = 1). If `` is found, all other nested elements are required and an exception is thrown if not present. */ CoulombFriction MakeCoulombFrictionFromSdfCollisionOde( const sdf::Collision& sdf_collision); diff --git a/multibody/parsing/detail_sdf_parser.cc b/multibody/parsing/detail_sdf_parser.cc index 216eee333bc0..d33e7e77d8fa 100644 --- a/multibody/parsing/detail_sdf_parser.cc +++ b/multibody/parsing/detail_sdf_parser.cc @@ -473,11 +473,10 @@ std::vector AddLinksFromSpecification( MakeGeometryPoseFromSdfCollision(sdf_collision)); std::unique_ptr shape = MakeShapeFromSdfGeometry(sdf_geometry); - const CoulombFriction coulomb_friction = - MakeCoulombFrictionFromSdfCollisionOde(sdf_collision); - plant->RegisterCollisionGeometry(body, X_LG, *shape, - sdf_collision.Name(), - coulomb_friction); + geometry::ProximityProperties props = + MakeProximityPropertiesForCollision(sdf_collision); + plant->RegisterCollisionGeometry( + body, X_LG, *shape, sdf_collision.Name(), std::move(props)); } } } diff --git a/multibody/parsing/detail_urdf_geometry.cc b/multibody/parsing/detail_urdf_geometry.cc index 0b1fb5200f19..f6fdab5c9e2b 100644 --- a/multibody/parsing/detail_urdf_geometry.cc +++ b/multibody/parsing/detail_urdf_geometry.cc @@ -6,9 +6,12 @@ #include #include +#include + #include "drake/common/drake_assert.h" #include "drake/common/text_logging.h" #include "drake/geometry/geometry_roles.h" +#include "drake/geometry/proximity_properties.h" #include "drake/multibody/parsing/detail_common.h" #include "drake/multibody/parsing/detail_path_utils.h" #include "drake/multibody/parsing/detail_tinyxml.h" @@ -78,8 +81,8 @@ void AddMaterialToMaterialMap(const std::string& material_name, void ParseMaterial(const XMLElement* node, MaterialMap* materials) { if (std::string(node->Name()) != "material") { - throw std::runtime_error( - std::string("Expected material element, got ") + node->Name()); + throw std::runtime_error(std::string("Expected material element, got ") + + node->Name()); } std::string name; @@ -112,8 +115,8 @@ void ParseMaterial(const XMLElement* node, MaterialMap* materials) { if (texture_node) { std::stringstream error_buff; - error_buff << "WARNING: Material \"" - << name << "\" is a texture. Textures are currently " + error_buff << "WARNING: Material \"" << name + << "\" is a texture. Textures are currently " << "not supported. For more information, see: " << "https://github.com/RobotLocomotion/drake/issues/2588. " << "Defaulting to use the black color for this material."; @@ -122,9 +125,9 @@ void ParseMaterial(const XMLElement* node, MaterialMap* materials) { AddMaterialToMaterialMap(name, rgba, true /* abort_if_name_clash */, materials); } else { - throw std::runtime_error( - "Material\"" + name + "\" not previously defined. Therefore " - "a color must be specified."); + throw std::runtime_error("Material\"" + name + + "\" not previously defined. Therefore " + "a color must be specified."); } } } @@ -178,9 +181,9 @@ std::unique_ptr ParseCapsule(const XMLElement* shape_node) { return std::make_unique(r, l); } -std::unique_ptr ParseMesh( - const XMLElement* shape_node, const PackageMap& package_map, - const std::string& root_dir) { +std::unique_ptr ParseMesh(const XMLElement* shape_node, + const PackageMap& package_map, + const std::string& root_dir) { std::string filename; if (!ParseStringAttribute(shape_node, "filename", &filename)) { throw std::runtime_error("Mesh element has no filename tag"); @@ -204,8 +207,8 @@ std::unique_ptr ParseMesh( if (!(scale_vector(0) == scale_vector(1) && scale_vector(0) == scale_vector(2))) { throw std::runtime_error( - "Drake meshes only support isotropic scaling. Therefore all " - "three scaling factors must be exactly equal."); + "Drake meshes only support isotropic scaling. Therefore all " + "three scaling factors must be exactly equal."); } scale = scale_vector(0); } @@ -217,9 +220,9 @@ std::unique_ptr ParseMesh( } } -std::unique_ptr ParseGeometry( - const XMLElement* node, const PackageMap& package_map, - const std::string& root_dir) { +std::unique_ptr ParseGeometry(const XMLElement* node, + const PackageMap& package_map, + const std::string& root_dir) { if (node->FirstChildElement("box")) { return ParseBox(node->FirstChildElement("box")); } @@ -233,19 +236,19 @@ std::unique_ptr ParseGeometry( return ParseCapsule(node->FirstChildElement("capsule")); } if (node->FirstChildElement("mesh")) { - return ParseMesh(node->FirstChildElement("mesh"), package_map, - root_dir); + return ParseMesh(node->FirstChildElement("mesh"), package_map, root_dir); } - throw std::runtime_error("Warning: geometry element " - "has an unknown type and will be ignored."); + throw std::runtime_error( + "Warning: geometry element " + "has an unknown type and will be ignored."); } std::string MakeGeometryName(const std::string& basename, const XMLElement* node) { + using std::hex; using std::setfill; using std::setw; - using std::hex; // Append the address spelled like "@0123456789abcdef". intptr_t address = reinterpret_cast(node); @@ -257,15 +260,14 @@ std::string MakeGeometryName(const std::string& basename, } // namespace // Parses a "visual" element in @p node. -geometry::GeometryInstance ParseVisual( - const std::string& parent_element_name, - const PackageMap& package_map, - const std::string& root_dir, const XMLElement* node, - MaterialMap* materials) { +geometry::GeometryInstance ParseVisual(const std::string& parent_element_name, + const PackageMap& package_map, + const std::string& root_dir, + const XMLElement* node, + MaterialMap* materials) { if (std::string(node->Name()) != "visual") { - throw std::runtime_error( - "In link " + parent_element_name + - " expected visual element, got " + node->Name()); + throw std::runtime_error("In link " + parent_element_name + + " expected visual element, got " + node->Name()); } // Ensures there is a geometry child element. Since this is a required @@ -310,9 +312,8 @@ geometry::GeometryInstance ParseVisual( const XMLElement* color_node = material_node->FirstChildElement("color"); if (color_node) { if (!ParseVectorAttribute(color_node, "rgba", &rgba)) { - throw std::runtime_error( - "Failed to parse color of material for link " + - parent_element_name); + throw std::runtime_error("Failed to parse color of material for link " + + parent_element_name); } color_specified = true; } @@ -344,7 +345,7 @@ geometry::GeometryInstance ParseVisual( // distributed across multiple `` elements and are not at the // `` level. AddMaterialToMaterialMap(material_name, rgba, - false /* abort_if_name_clash */, materials); + false /* abort_if_name_clash */, materials); } // If the color is specified as a child element of the current material @@ -371,32 +372,94 @@ geometry::GeometryInstance ParseVisual( geometry_name = MakeGeometryName(parent_element_name + "_Visual", node); } - auto instance = geometry::GeometryInstance( - T_element_to_link, std::move(shape), geometry_name); + auto instance = geometry::GeometryInstance(T_element_to_link, + std::move(shape), geometry_name); instance.set_illustration_properties(properties); return instance; } +// This is the backwards-compatible fallback for defining friction; it reads +// the soon-to-be-deprecated tag for data. It throws errors +// for malformed values or returns a friction (either the valid friction +// defined in the tag or the default). +// +// It incidentally propagates some warnings about unused tags from the rigid +// body tree days. +CoulombFriction ParseCoulombFrictionFromDrakeCompliance( + const std::string& parent_element_name, const XMLElement* node) { + const XMLElement* compliant_node = + node->FirstChildElement("drake_compliance"); + if (compliant_node) { + // TODO(SeanCurtis-TRI): Ultimately, we want to kill + // and these will go along with it. These values are only used in rigid + // body tree; with no real expectation we'll re-use them in MBP. + if (compliant_node->FirstChildElement("youngs_modulus")) { + drake::log()->warn("Ignoring youngs_modulus for link " + + parent_element_name); + } + + if (compliant_node->FirstChildElement("dissipation")) { + drake::log()->warn("Ignoring dissipation for link " + + parent_element_name); + } + + double static_friction{-1}; + double dynamic_friction{-1}; + bool static_friction_present{false}; + bool dynamic_friction_present{false}; + + const XMLElement* friction_node = + compliant_node->FirstChildElement("static_friction"); + if (friction_node) { + static_friction_present = true; + if (friction_node->QueryDoubleText(&static_friction)) { + throw std::runtime_error("Unable to parse static_friction for link " + + parent_element_name); + } + } + + friction_node = compliant_node->FirstChildElement("dynamic_friction"); + if (friction_node) { + dynamic_friction_present = true; + if (friction_node->QueryDoubleText(&dynamic_friction)) { + throw std::runtime_error("Unable to parse dynamic_friction for link " + + parent_element_name); + } + } + + if (static_friction_present != dynamic_friction_present) { + throw std::runtime_error( + fmt::format("Link '{}': When specifying coefficient of friction, " + "both static and dynamic coefficients must be defined", + parent_element_name)); + } + + if (static_friction_present) { + return CoulombFriction(static_friction, dynamic_friction); + } + } + return default_friction(); +} + // Parses a "collision" element in @p node. // // @param[out] friction Coulomb friction for the associated geometry. geometry::GeometryInstance ParseCollision( - const std::string& parent_element_name, - const PackageMap& package_map, - const std::string& root_dir, const XMLElement* node, - CoulombFriction* friction) { + const std::string& parent_element_name, const PackageMap& package_map, + const std::string& root_dir, const XMLElement* node) { if (std::string(node->Name()) != "collision") { throw std::runtime_error( - "In link " + parent_element_name + - " expected collision element, got " + node->Name()); + fmt::format("In link '{}' expected collision element, got {}", + parent_element_name, node->Name())); } // Ensures there is a geometry child element. Since this is a required // element, throws an exception if a geometry element does not exist. const XMLElement* geometry_node = node->FirstChildElement("geometry"); if (!geometry_node) { - throw std::runtime_error("Link " + parent_element_name + - " has a collision element without geometry."); + throw std::runtime_error( + fmt::format("Link '{}' has a collision element without geometry", + parent_element_name)); } // Obtains the reference frame of the visualization relative to the @@ -417,53 +480,81 @@ geometry::GeometryInstance ParseCollision( std::unique_ptr shape = ParseGeometry(geometry_node, package_map, root_dir); - *friction = default_friction(); - const XMLElement* compliant_node = - node->FirstChildElement("drake_compliance"); - if (compliant_node) { - double static_friction{-1}; - double dynamic_friction{-1}; - bool static_friction_present = false; - bool dynamic_friction_present = false; - - const XMLElement* friction_node = - compliant_node->FirstChildElement("static_friction"); - if (friction_node) { - static_friction_present = true; - if (friction_node->QueryDoubleText(&static_friction)) { - throw std::runtime_error( - "Unable to parse static_friction for link " + parent_element_name); + // Parse the properties from . + geometry::ProximityProperties props; + const XMLElement* drake_element = + node->FirstChildElement("drake:proximity_properties"); + if (drake_element) { + auto read_double = + [drake_element](const char* element_name) -> std::optional { + const XMLElement* value_node = + drake_element->FirstChildElement(element_name); + if (value_node != nullptr) { + double value{}; + if (ParseScalarAttribute(value_node, "value", &value)) { + return value; + } else { + throw std::runtime_error( + fmt::format("Unable to read the 'value' attribute for the <{}> " + "tag on line {}", + element_name, value_node->GetLineNum())); + } } - } + return {}; + }; - friction_node = compliant_node->FirstChildElement("dynamic_friction"); - if (friction_node) { - dynamic_friction_present = true; - if (friction_node->QueryDoubleText(&dynamic_friction)) { - throw std::runtime_error( - "Unable to parse dynamic_friction for link " + parent_element_name); - } + std::optional rez_hint = read_double("drake:mesh_resolution_hint"); + if (rez_hint) { + props.AddProperty(geometry::internal::kHydroGroup, + geometry::internal::kRezHint, *rez_hint); } - - if (static_friction_present != dynamic_friction_present) { - throw std::runtime_error( - "Link " + parent_element_name + - ": When specifying coefficient of friction, " - "both static and dynamic coefficients must be defined"); + std::optional elastic_modulus = + read_double("drake:elastic_modulus"); + if (elastic_modulus) { + props.AddProperty(geometry::internal::kMaterialGroup, + geometry::internal::kElastic, *elastic_modulus); } - - if (static_friction_present) { - *friction = CoulombFriction(static_friction, dynamic_friction); + std::optional dissipation = + read_double("drake:hunt_crossley_dissipation"); + if (dissipation) { + props.AddProperty(geometry::internal::kMaterialGroup, + geometry::internal::kHcDissipation, *dissipation); } - - if (compliant_node->FirstChildElement("youngs_modulus")) { - drake::log()->warn("Ignoring youngs_modulus for link " + - parent_element_name); + std::optional mu_dynamic = read_double("drake:mu_dynamic"); + std::optional mu_static = read_double("drake:mu_static"); + if (mu_dynamic && mu_static) { + props.AddProperty(geometry::internal::kMaterialGroup, + geometry::internal::kFriction, + CoulombFriction(*mu_static, *mu_dynamic)); + } else if (mu_dynamic) { + props.AddProperty(geometry::internal::kMaterialGroup, + geometry::internal::kFriction, + CoulombFriction(*mu_dynamic, *mu_dynamic)); + } else if (mu_static) { + props.AddProperty(geometry::internal::kMaterialGroup, + geometry::internal::kFriction, + CoulombFriction(*mu_static, *mu_static)); } + } - if (compliant_node->FirstChildElement("dissipation")) { - drake::log()->warn("Ignoring dissipation for link " + - parent_element_name); + // Now test to see how we should handle a potential tag. + if (!props.HasProperty(geometry::internal::kMaterialGroup, + geometry::internal::kFriction)) { + // We have no friction from so we need the old + // tag. + CoulombFriction friction = + ParseCoulombFrictionFromDrakeCompliance(parent_element_name, node); + props.AddProperty(geometry::internal::kMaterialGroup, + geometry::internal::kFriction, friction); + } else { + // We parsed friction from ; test for the + // existence of and warn that it won't be used. + if (node->FirstChildElement("drake_compliance")) { + drake::log()->warn(fmt::format( + "Drake contact parameters are fully specified by the " + " tag for the '{}' link. The " + " tag is ignored. Consider removing it.", + parent_element_name)); } } @@ -472,8 +563,10 @@ geometry::GeometryInstance ParseCollision( geometry_name = MakeGeometryName(parent_element_name + "_Collision", node); } - return geometry::GeometryInstance(T_element_to_link, std::move(shape), - geometry_name); + geometry::GeometryInstance instance(T_element_to_link, std::move(shape), + geometry_name); + instance.set_proximity_properties(std::move(props)); + return instance; } } // namespace internal diff --git a/multibody/parsing/detail_urdf_geometry.h b/multibody/parsing/detail_urdf_geometry.h index 8a64394b5bc3..e64ff7d3bbd7 100644 --- a/multibody/parsing/detail_urdf_geometry.h +++ b/multibody/parsing/detail_urdf_geometry.h @@ -16,43 +16,90 @@ namespace drake { namespace multibody { namespace internal { -/// A map from the name of a material to its color. The color is specified in -/// RGBA (Red, Green, Blue, Alpha) format. // TODO(sammy-tri) Add support for texture-based materials, see #2588. +/** A map from the name of a material to its color. The color is specified in + RGBA (Red, Green, Blue, Alpha) format. */ typedef std::map MaterialMap; -/// Parses a "material" element in @p node and adds the result to @p -/// materials. -/// -/// @throws std::runtime_error if the material is missing required attributes -/// or if it was already defined with different properties. +/** Parses a "material" element in @p node and adds the result to @p materials. + + @throws std::runtime_error if the material is missing required attributes + or if it was already defined with different properties. */ void ParseMaterial(const tinyxml2::XMLElement* node, MaterialMap* materials); -/// Parses a "visual" element in @p node. -/// -/// @param[in] parent_element_name The name of the parent link element, used -/// to construct default geometry names and for error reporting. -/// @param[in,out] materials The MaterialMap is used to look up materials -/// which are referenced by name only in the visual element. New materials -/// which are specified by both color and name will be added to the map and -/// can be used by later visual elements. Material definitions may be -/// repeated if the material properties are identical. +/** Parses a "visual" element in @p node. + + @param[in] parent_element_name The name of the parent link element, used + to construct default geometry names and for error reporting. + @param[in,out] materials The MaterialMap is used to look up materials + which are referenced by name only in the visual element. New materials + which are specified by both color and name will be added to the map and + can be used by later visual elements. Material definitions may be + repeated if the material properties are identical. */ geometry::GeometryInstance ParseVisual( const std::string& parent_element_name, const PackageMap& package_map, const std::string& root_dir, const tinyxml2::XMLElement* node, MaterialMap* materials); -/// Parses a "collision" element in @p node. -/// -/// @param[in] parent_element_name The name of the parent link element, used -/// to construct default geometry names and for error reporting. -/// @param[out] friction Coulomb friction for the associated geometry. +/** Parses a element in @p node. + + Reads the definition of a collision geometry (shape, pose, properties, etc.) + + For properties, this function specifically looks for the + `` child tag to find drake-specific geometry + collision (or "proximity") properties. It looks for the following tags with the + mapping to properties as show below. + + All of the tags should be of the form: + + @code{xml} + + @endcode + + Mapping from URDF tag to geometry property. See + @ref YET_TO_BE_WRITTEN_HYDROELATIC_GEOMETRY_MODULE for details on the semantics + of these properties. + | Tag | Group | Property | Notes | + | :------------------------------: | :----------: | :-----------------------: | :---------------------------------------------: | + | drake:mesh_resolution_hint | hydroelastic | resolution_hint | Required for hydroelastic contact. | + | drake:elastic_modulus | material | elastic_modulus | ∞ for rigid hydrolelastic models; < ∞ for soft. | + | drake:hunt_crossley_dissipation | material | hunt_crossley_dissipation | | + | drake:mu_dynamic | material | coulomb_friction | See note below on friction. | + | drake:mu_static | material | coulomb_friction | See note below on friction. | + +

Coefficients of friction

+ + Parsing coefficients of friction has a relatively complicated protocol: + + 1. If one of `` *or* `` is present, the + property of type CoulombFriction will be instantiated with both + values initialized to the single value. An exception will be thrown + - if the value is negative. + 2. If both `` and `` tags are present, the + CoulombFriction will contain both values. An exception will be + thrown if: + - either value is negative, or + - `mu_dynamic` is greater than `mu_static`. + 3. If *both* tags are missing, the parser will look for two tags: + `` and + `` with the same error conditions on + values. + 4. If no meaningful friction coefficients are found, a default value will be + created (see default_friction()). + As long as no exception is thrown, the returned geometry::GeometryInstance + will contain a valid instance of geometry::ProximityProperties with (at least) + the ('material', 'coulomb_friction') property. + + @param[in] parent_element_name The name of the parent link element, used + to construct default geometry names and for error reporting. + @param[in] package_map The map used to resolve paths. + @param[in] root_dir The root directory of the containing URDF file. + @param[in] node The node corresponding to the tag. */ geometry::GeometryInstance ParseCollision( const std::string& parent_element_name, const PackageMap& package_map, - const std::string& root_dir, const tinyxml2::XMLElement* node, - CoulombFriction* friction); + const std::string& root_dir, const tinyxml2::XMLElement* node); } /// namespace internal } /// namespace multibody diff --git a/multibody/parsing/detail_urdf_parser.cc b/multibody/parsing/detail_urdf_parser.cc index 153e528abf5d..979b1b14582d 100644 --- a/multibody/parsing/detail_urdf_parser.cc +++ b/multibody/parsing/detail_urdf_parser.cc @@ -134,13 +134,12 @@ void ParseBody(const multibody::PackageMap& package_map, for (XMLElement* collision_node = node->FirstChildElement("collision"); collision_node; collision_node = collision_node->NextSiblingElement("collision")) { - CoulombFriction friction; geometry::GeometryInstance geometry_instance = - ParseCollision(body_name, package_map, root_dir, collision_node, - &friction); - plant->RegisterCollisionGeometry(body, geometry_instance.pose(), - geometry_instance.shape(), - geometry_instance.name(), friction); + ParseCollision(body_name, package_map, root_dir, collision_node); + DRAKE_DEMAND(geometry_instance.proximity_properties()); + plant->RegisterCollisionGeometry( + body, geometry_instance.pose(), geometry_instance.shape(), + geometry_instance.name(), *geometry_instance.proximity_properties()); } } } diff --git a/multibody/parsing/test/detail_scene_graph_test.cc b/multibody/parsing/test/detail_scene_graph_test.cc index b43d2ad94623..be9f3825e63f 100644 --- a/multibody/parsing/test/detail_scene_graph_test.cc +++ b/multibody/parsing/test/detail_scene_graph_test.cc @@ -11,9 +11,11 @@ #include "drake/common/test_utilities/eigen_matrix_compare.h" #include "drake/common/test_utilities/expect_throws_message.h" #include "drake/geometry/geometry_instance.h" +#include "drake/geometry/proximity_properties.h" #include "drake/geometry/scene_graph.h" #include "drake/math/roll_pitch_yaw.h" #include "drake/math/rotation_matrix.h" +#include "drake/multibody/parsing/detail_common.h" namespace drake { namespace multibody { @@ -31,6 +33,7 @@ using geometry::GeometryInstance; using geometry::HalfSpace; using geometry::IllustrationProperties; using geometry::Mesh; +using geometry::ProximityProperties; using geometry::SceneGraph; using geometry::Shape; using geometry::Sphere; @@ -824,6 +827,163 @@ GTEST_TEST(SceneGraphParserDetail, kTolerance, MatrixCompareType::relative)); } +// Verify we can parse drake collision properties from a element. +GTEST_TEST(SceneGraphParserDetail, MakeProximityPropertiesForCollision) { + // This string represents the generic XML spelling of a element. + // It contains a `{}` place holder such that child tags of can be + // injected to test various expressions of collision properties -- + // substitution via fmt::format. + const std::string collision_xml = R"_( + + 0.0 0.0 0.0 0.0 0.0 0.0 + + + 1.0 2.0 3.0 + + {} + +)_"; + + auto make_sdf_collision = [&collision_xml](const char* material_string) { + return MakeSdfCollisionFromString( + fmt::format(collision_xml, material_string)); + }; + + auto assert_friction = [](const ProximityProperties& properties, + const CoulombFriction& expected_friction) { + ASSERT_TRUE(properties.HasProperty(geometry::internal::kMaterialGroup, + geometry::internal::kFriction)); + const auto& friction = properties.GetProperty>( + geometry::internal::kMaterialGroup, geometry::internal::kFriction); + EXPECT_EQ(friction.static_friction(), expected_friction.static_friction()); + EXPECT_EQ(friction.dynamic_friction(), + expected_friction.dynamic_friction()); + }; + + auto assert_single_property = [](const ProximityProperties& properties, + const char* group, const char* property, + double value) { + ASSERT_TRUE(properties.HasProperty(group, property)); + EXPECT_EQ(properties.GetProperty(group, property), value); + }; + + // Case: has resolution hint; contains hint and default friction coefficients. + { + unique_ptr sdf_collision = make_sdf_collision(R"_( + + 2.5 + )_"); + ProximityProperties properties = + MakeProximityPropertiesForCollision(*sdf_collision); + assert_single_property(properties, geometry::internal::kHydroGroup, + geometry::internal::kRezHint, 2.5); + assert_friction(properties, default_friction()); + } + + // Case: has elastic_modulus; contains modulus and default friction + // coefficients. + { + unique_ptr sdf_collision = make_sdf_collision(R"_( + + 3.5 + )_"); + ProximityProperties properties = + MakeProximityPropertiesForCollision(*sdf_collision); + assert_single_property(properties, geometry::internal::kMaterialGroup, + geometry::internal::kElastic, 3.5); + assert_friction(properties, default_friction()); + } + + // Case: has dissipation; contains dissipation and default friction + // coefficients. + { + unique_ptr sdf_collision = make_sdf_collision(R"_( + + 4.5 + )_"); + ProximityProperties properties = + MakeProximityPropertiesForCollision(*sdf_collision); + assert_single_property(properties, geometry::internal::kMaterialGroup, + geometry::internal::kHcDissipation, 4.5); + assert_friction(properties, default_friction()); + } + + // Case: has dynamic friction. + { + unique_ptr sdf_collision = make_sdf_collision(R"_( + + 4.5 + )_"); + ProximityProperties properties = + MakeProximityPropertiesForCollision(*sdf_collision); + assert_friction(properties, {4.5, 4.5}); + } + + // Case: has static friction. + { + unique_ptr sdf_collision = make_sdf_collision(R"_( + + 4.75 + )_"); + ProximityProperties properties = + MakeProximityPropertiesForCollision(*sdf_collision); + assert_friction(properties, {4.75, 4.75}); + } + + // Case: has static and dynamic friction. + { + unique_ptr sdf_collision = make_sdf_collision(R"_( + + 4.5 + 4.75 + )_"); + ProximityProperties properties = + MakeProximityPropertiesForCollision(*sdf_collision); + assert_friction(properties, {4.75, 4.5}); + } + + // Case: has no drake coefficients, only mu & m2 in ode: contains mu, mu2 + // friction. + { + unique_ptr sdf_collision = make_sdf_collision(R"_( + + + + 0.8 + 0.3 + + + )_"); + ProximityProperties properties = + MakeProximityPropertiesForCollision(*sdf_collision); + assert_friction(properties, {0.8, 0.3}); + } + + // Case: has both ode (mu, mu2) and drake (dynamic): contains + // drake::mu_dynamic wins. + { + unique_ptr sdf_collision = make_sdf_collision(R"_( + + 0.3 + + + + + 1.8 + 1.3 + + + )_"); + ProximityProperties properties = + MakeProximityPropertiesForCollision(*sdf_collision); + assert_friction(properties, {0.3, 0.3}); + } + + // Note: we're not explicitly testing negative friction coefficients or + // dynamic > static because we rely on the CoulombFriction constructor to + // handle that. +} + // Verify we can parse friction coefficients from an element in // . Drake understands to be the static // coefficient and the dynamic coefficient of friction. @@ -851,6 +1011,26 @@ GTEST_TEST(SceneGraphParserDetail, MakeCoulombFrictionFromSdfCollisionOde) { EXPECT_EQ(friction.dynamic_friction(), 0.3); } +// Verify that if no tag is present, we return default friction +// coefficients. +GTEST_TEST(SceneGraphParserDetail, + MakeCoulombFrictionFromSdfCollisionOde_NoSurface) { + unique_ptr sdf_collision = MakeSdfCollisionFromString( + "" + " 0.0 0.0 0.0 0.0 0.0 0.0" + " " + " " + " 1.0 2.0 3.0" + " " + " " + ""); + const CoulombFriction friction = + MakeCoulombFrictionFromSdfCollisionOde(*sdf_collision); + const CoulombFriction expected_friction = default_friction(); + EXPECT_EQ(friction.static_friction(), expected_friction.static_friction()); + EXPECT_EQ(friction.dynamic_friction(), expected_friction.dynamic_friction()); +} + // Verify MakeCoulombFrictionFromSdfCollisionOde() throws an exception if // provided a dynamic friction coefficient larger than the static friction // coefficient. diff --git a/multibody/parsing/test/detail_urdf_geometry_test.cc b/multibody/parsing/test/detail_urdf_geometry_test.cc index 94724d6a87c7..0ea9ede38826 100644 --- a/multibody/parsing/test/detail_urdf_geometry_test.cc +++ b/multibody/parsing/test/detail_urdf_geometry_test.cc @@ -1,5 +1,6 @@ #include "drake/multibody/parsing/detail_urdf_geometry.h" +#include #include #include @@ -9,7 +10,9 @@ #include "drake/common/test_utilities/expect_no_throw.h" #include "drake/common/test_utilities/expect_throws_message.h" #include "drake/geometry/geometry_roles.h" +#include "drake/geometry/proximity_properties.h" #include "drake/math/rigid_transform.h" +#include "drake/multibody/parsing/detail_common.h" #include "drake/multibody/parsing/detail_path_utils.h" #include "drake/multibody/parsing/package_map.h" @@ -18,11 +21,33 @@ namespace multibody { namespace internal { namespace { +using std::make_unique; +using std::unique_ptr; + using tinyxml2::XMLDocument; using tinyxml2::XMLElement; using math::RigidTransformd; using geometry::GeometryInstance; +using geometry::ProximityProperties; + +// Creates a special XML DOM consisting of *only* a collision object. XML text +// can be provided as an input and it will be injected as a child of the +// tag. +unique_ptr MakeCollisionDocFromString( + const std::string& collision_spec) { + const std::string urdf_harness = R"_( + + + + + {} + )_"; + const std::string urdf = fmt::format(urdf_harness, collision_spec); + auto doc = make_unique(); + doc->Parse(urdf.c_str()); + return doc; +} class UrdfGeometryTests : public testing::Test { public: @@ -73,10 +98,9 @@ class UrdfGeometryTests : public testing::Test { link_node->FirstChildElement("collision"); collision_node; collision_node = collision_node->NextSiblingElement("collision")) { - CoulombFriction friction; geometry::GeometryInstance geometry_instance = internal::ParseCollision(body_name, package_map_, root_dir_, - collision_node, &friction); + collision_node); collision_instances_.push_back(geometry_instance); } } @@ -254,11 +278,10 @@ TEST_F(UrdfGeometryTests, TestWrongElementType) { &materials_), std::runtime_error, "In link fake_name expected visual element, got material"); - CoulombFriction friction; DRAKE_EXPECT_THROWS_MESSAGE( internal::ParseCollision("fake_name", package_map_, root_dir_, - material_node, &friction), std::runtime_error, - "In link fake_name expected collision element, got material"); + material_node), std::runtime_error, + "In link 'fake_name' expected collision element, got material"); } TEST_F(UrdfGeometryTests, TestParseConvexMesh) { @@ -286,6 +309,166 @@ TEST_F(UrdfGeometryTests, TestParseConvexMesh) { } } +// Verify we can parse drake collision properties from a element. +TEST_F(UrdfGeometryTests, CollisionProperties) { + // Verifies that the property exists with the given double-typed value. + auto verify_single_property = [](const ProximityProperties& properties, + const char* group, const char* property, + double value) { + ASSERT_TRUE(properties.HasProperty(group, property)) + << fmt::format(" for property: ('{}', '{}')", group, property); + EXPECT_EQ(properties.GetProperty(group, property), value); + }; + + // Verifies that the properties has friction and it matches the given values. + auto verify_friction = [](const ProximityProperties& properties, + const CoulombFriction& expected_friction) { + ASSERT_TRUE(properties.HasProperty("material", "coulomb_friction")); + const auto& friction = properties.GetProperty>( + "material", "coulomb_friction"); + EXPECT_EQ(friction.static_friction(), expected_friction.static_friction()); + EXPECT_EQ(friction.dynamic_friction(), + expected_friction.dynamic_friction()); + }; + + const PackageMap package_map; // An empty package map. + const std::string root_dir("."); // Arbitrary, un-used root directory. + + // Case: has resolution hint; contains hint and default friction coefficients. + { + unique_ptr doc = MakeCollisionDocFromString(R"_( + + + )_"); + const XMLElement* collision_node = doc->FirstChildElement("collision"); + ASSERT_NE(collision_node, nullptr); + GeometryInstance instance = + ParseCollision("link_name", package_map, root_dir, collision_node); + ASSERT_NE(instance.proximity_properties(), nullptr); + const ProximityProperties& properties = *instance.proximity_properties(); + verify_single_property(properties, geometry::internal::kHydroGroup, + geometry::internal::kRezHint, 2.5); + verify_friction(properties, default_friction()); + } + + // Case: has elastic_modulus; contains modulus and default friction + // coefficients. + { + unique_ptr doc = MakeCollisionDocFromString(R"_( + + + )_"); + const XMLElement* collision_node = doc->FirstChildElement("collision"); + ASSERT_NE(collision_node, nullptr); + GeometryInstance instance = + ParseCollision("link_name", package_map, root_dir, collision_node); + ASSERT_NE(instance.proximity_properties(), nullptr); + const ProximityProperties& properties = *instance.proximity_properties(); + verify_single_property(properties, geometry::internal::kMaterialGroup, + geometry::internal::kElastic, 3.5); + verify_friction(properties, default_friction()); + } + + // Case: has dissipation; contains dissipation and default friction + // coefficients. + { + unique_ptr doc = MakeCollisionDocFromString(R"_( + + + )_"); + const XMLElement* collision_node = doc->FirstChildElement("collision"); + ASSERT_NE(collision_node, nullptr); + GeometryInstance instance = + ParseCollision("link_name", package_map, root_dir, collision_node); + ASSERT_NE(instance.proximity_properties(), nullptr); + const ProximityProperties& properties = *instance.proximity_properties(); + verify_single_property(properties, geometry::internal::kMaterialGroup, + geometry::internal::kHcDissipation, 3.5); + verify_friction(properties, default_friction()); + } + + // Case: has dynamic friction. + { + unique_ptr doc = MakeCollisionDocFromString(R"_( + + + )_"); + const XMLElement* collision_node = doc->FirstChildElement("collision"); + ASSERT_NE(collision_node, nullptr); + GeometryInstance instance = + ParseCollision("link_name", package_map, root_dir, collision_node); + ASSERT_NE(instance.proximity_properties(), nullptr); + const ProximityProperties& properties = *instance.proximity_properties(); + verify_friction(properties, {3.5, 3.5}); + } + + // Case: has static friction. + { + unique_ptr doc = MakeCollisionDocFromString(R"_( + + + )_"); + const XMLElement* collision_node = doc->FirstChildElement("collision"); + ASSERT_NE(collision_node, nullptr); + GeometryInstance instance = + ParseCollision("link_name", package_map, root_dir, collision_node); + ASSERT_NE(instance.proximity_properties(), nullptr); + const ProximityProperties& properties = *instance.proximity_properties(); + verify_friction(properties, {3.25, 3.25}); + } + + // Case: has static and dynamic friction. + { + unique_ptr doc = MakeCollisionDocFromString(R"_( + + + + )_"); + const XMLElement* collision_node = doc->FirstChildElement("collision"); + ASSERT_NE(collision_node, nullptr); + GeometryInstance instance = + ParseCollision("link_name", package_map, root_dir, collision_node); + ASSERT_NE(instance.proximity_properties(), nullptr); + const ProximityProperties& properties = *instance.proximity_properties(); + verify_friction(properties, {3.5, 3.25}); + } + + // Case: has no drake:proximity_properties coefficients, only drake_compliance + // coeffs. + { + unique_ptr doc = MakeCollisionDocFromString(R"_( + + 3.5 + 2.5 + )_"); + const XMLElement* collision_node = doc->FirstChildElement("collision"); + ASSERT_NE(collision_node, nullptr); + GeometryInstance instance = + ParseCollision("link_name", package_map, root_dir, collision_node); + ASSERT_NE(instance.proximity_properties(), nullptr); + const ProximityProperties& properties = *instance.proximity_properties(); + verify_friction(properties, {3.5, 2.5}); + } + + // Case: has both drake_compliance and drake:proximity_properties; + // drake:proximity_properties wins. + unique_ptr doc = MakeCollisionDocFromString(R"_( + + 3.5 + 2.5 + + + + )_"); + const XMLElement* collision_node = doc->FirstChildElement("collision"); + ASSERT_NE(collision_node, nullptr); + GeometryInstance instance = + ParseCollision("link_name", package_map, root_dir, collision_node); + ASSERT_NE(instance.proximity_properties(), nullptr); + const ProximityProperties& properties = *instance.proximity_properties(); + verify_friction(properties, {4.5, 4.5}); +} + } // namespace } // namespace internal } // namespace multibody diff --git a/multibody/plant/multibody_plant.cc b/multibody/plant/multibody_plant.cc index 69aba76d84a2..4129ea0a5e76 100644 --- a/multibody/plant/multibody_plant.cc +++ b/multibody/plant/multibody_plant.cc @@ -384,31 +384,44 @@ template geometry::GeometryId MultibodyPlant::RegisterCollisionGeometry( const Body& body, const math::RigidTransform& X_BG, const geometry::Shape& shape, const std::string& name, - const CoulombFriction& coulomb_friction) { + geometry::ProximityProperties properties) { DRAKE_MBP_THROW_IF_FINALIZED(); DRAKE_THROW_UNLESS(geometry_source_is_registered()); + DRAKE_THROW_UNLESS(properties.HasProperty("material", "coulomb_friction")); + + const CoulombFriction& coulomb_friction = + properties.GetProperty>("material", + "coulomb_friction"); // TODO(amcastro-tri): Consider doing this after finalize so that we can // register geometry that has a fixed path to world to the world body (i.e., // as anchored geometry). - GeometryId id = - RegisterGeometry(body, X_BG, shape, - GetScopedName(*this, body.model_instance(), name)); + GeometryId id = RegisterGeometry( + body, X_BG, shape, GetScopedName(*this, body.model_instance(), name)); - // TODO(SeanCurtis-TRI): Push the contact parameters into the - // ProximityProperties. - member_scene_graph().AssignRole( - *source_id_, id, geometry::ProximityProperties()); + member_scene_graph().AssignRole(*source_id_, id, std::move(properties)); const int collision_index = geometry_id_to_collision_index_.size(); geometry_id_to_collision_index_[id] = collision_index; DRAKE_ASSERT( static_cast(default_coulomb_friction_.size()) == collision_index); + // TODO(SeanCurtis-TRI): Stop storing coulomb friction in MBP and simply + // acquire it from SceneGraph. default_coulomb_friction_.push_back(coulomb_friction); DRAKE_ASSERT(num_bodies() == static_cast(collision_geometries_.size())); collision_geometries_[body.index()].push_back(id); return id; } +template +geometry::GeometryId MultibodyPlant::RegisterCollisionGeometry( + const Body& body, const math::RigidTransform& X_BG, + const geometry::Shape& shape, const std::string& name, + const CoulombFriction& coulomb_friction) { + geometry::ProximityProperties props; + props.AddProperty("material", "coulomb_friction", coulomb_friction); + return RegisterCollisionGeometry(body, X_BG, shape, name, std::move(props)); +} + template const std::vector& MultibodyPlant::GetCollisionGeometriesForBody(const Body& body) const { diff --git a/multibody/plant/multibody_plant.h b/multibody/plant/multibody_plant.h index 267b7afda235..59e0c3aac7d5 100644 --- a/multibody/plant/multibody_plant.h +++ b/multibody/plant/multibody_plant.h @@ -956,10 +956,19 @@ class MultibodyPlant : public internal::MultibodyTreeSystem { /// @param[in] shape /// The geometry::Shape used for visualization. E.g.: geometry::Sphere, /// geometry::Cylinder, etc. - /// @param[in] coulomb_friction - /// Coulomb's law of friction coefficients to model friction on the - /// surface of `shape` for the given `body`. - /// @throws std::exception if called post-finalize. + /// @param[in] properties + /// The proximity properties associated with the collision geometry. They + /// *must* include the (`material`, `coulomb_friction`) property of type + /// CoulombFriction. + /// @throws std::exception if called post-finalize or if the properties are + /// missing the coulomb friction property (or if it is of the wrong type). + geometry::GeometryId RegisterCollisionGeometry( + const Body& body, const math::RigidTransform& X_BG, + const geometry::Shape& shape, const std::string& name, + geometry::ProximityProperties properties); + + // TODO(SeanCurtis-TRI): Deprecate this in favor of simply passing properties. + /// Overload which specifies a single property: coulomb_friction. geometry::GeometryId RegisterCollisionGeometry( const Body& body, const math::RigidTransform& X_BG, const geometry::Shape& shape, const std::string& name,