#pragma once #include #include #include #include #include #include #include "drake/common/diagnostic_policy.h" #include "drake/geometry/geometry_instance.h" #include "drake/geometry/geometry_roles.h" #include "drake/geometry/shape_specification.h" #include "drake/math/rigid_transform.h" #include "drake/multibody/parsing/detail_sdf_diagnostic.h" #include "drake/multibody/parsing/package_map.h" #include "drake/multibody/plant/coulomb_friction.h" namespace drake { namespace multibody { namespace internal { /* Used for resolving URIs / filenames. */ using ResolveFilename = std::function; /* Given an sdf::Geometry object representing a element from an SDF file, this method makes a new drake::geometry::Shape object from this specification. If no recognizable geometry is specified, nullptr is returned. If the geometry is recognized, but malformed, emits an error. When the error policy is set to not throw it returns std::nullopt. */ std::optional> MakeShapeFromSdfGeometry( const SDFormatDiagnostic& diagnostic, const sdf::Geometry& sdf_geometry, ResolveFilename resolve_filename); /* Given an sdf::Visual object representing a element from an SDF file, this method makes a new drake::geometry::GeometryInstance object from this specification at a pose `X_LG` relatve to its parent link. This method returns nullptr when the given SDF specification corresponds to an uninterpreted geometry type: - `sdf::GeometryType::EMPTY` (`` SDF tag.) - `sdf::GeometryType::HEIGHTMAP` (`` SDF tag.) If the geometry is malformed, emits an error. When the error policy is not set to throw it returns an std::nullopt.

Targeting Renderers

In addition to the standard SDF hierarchy, Drake offers an additional tag ``: ``` renderer_name ... ``` The new tag serves as a list of renderers for which this visual is targeted. - The _value_ of the tag is the name of the renderer. - If the _value_ is empty, that is a parsing error. - If no instance of `` every renderer will be given the chance to reify this visual geometry. - Multiple instances of this tag are allowed. Each instance adds a renderer to the list of targeted renderers. This feature is one way to provide multiple visual representations of a body. */ std::optional> MakeGeometryInstanceFromSdfVisual( const SDFormatDiagnostic& diagnostic, const sdf::Visual& sdf_visual, ResolveFilename resolve_filename, const math::RigidTransformd& X_LG); /* Extracts the material properties from the given sdf::Visual object. The sdf::Visual object represents a corresponding tag from an SDF file. The material properties are placed into both a geometry::IllustrationProperties and geometry::PerceptionProperties as follows: | Group | Name | Type | Description | | :---: | :---------: | :-------------: | :---------- | | phong | diffuse | Vector4 | The normalized rgba values for the diffuse color | | phong | ambient | Vector4 | The normalized rgba values for the ambient color | | phong | specular | Vector4 | The normalized rgba values for the specular color | | phong | emissive | Vector4 | The normalized rgba values for the emissive color | | phong | diffuse_map | string | A resolvable URI to a png image that will be applied as a diffuse map. | These are properties to be used in the Phong lighting model and are taken from the similarly named property tags (see below). If any of `ambient`, `diffuse`, `specular`, or `emissive` tags are missing, that property will be omitted from the property set and the impact of those missing properties will depend on the downstream consumers documented handling of missing parameters. If any of the tags are malformed, sdformat will treat those properties as "missing" and they will not be included in the property set. The material properties come from the child tag. E.g., @code{xml} ... r_a g_a b_a a_a r_d g_d b_d a_d r_s g_s b_s a_s r_e g_e b_e a_e @endcode An instance of geometry::IllustrationProperties will be returned. If there is no material tag, no material property tags, or no successfully parsed material property tags, the property set will be empty. If the material is malformed an error will be emitted. If the error policy is not set to throw, an std::nullopt will be returned. */ std::optional MakeVisualPropertiesFromSdfVisual( const SDFormatDiagnostic& diagnostic, const sdf::Visual& sdf_visual, ResolveFilename resolve_filename); /* Computes the pose `X_LC` of frame C (the "canonical frame" of the geometry) relative to the link L containing the collision, given an `sdf_collision` stemming from the parsing of a `` element in an SDF file and its pose `X_LG`, where `G` represents the frame for the geometry of that collision element. */ math::RigidTransformd MakeGeometryPoseFromSdfCollision( const sdf::Collision& sdf_collision, const math::RigidTransformd& X_LG); /* @anchor sdf_contact_material 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 It returns a valid instance of ProximityProperties. There are not default values for these tags (except for friction -- see below); if the tag is missing, the corresponding property will be missing from the property set. If the collision element is malformed it emits an error. If the error policy is set to not throw an std::nullopt is returned instead. Mapping from SDF tag to geometry property. See @ref YET_TO_BE_WRITTEN_HYDROELASTIC_GEOMETRY_MODULE for details on the semantics of these properties. | Tag | Group | Property | Notes | | :------------------------------: | :----------: | :-----------------------: | :------------------------------------------------------------------------------------------------------------------------------: | | drake:mesh_resolution_hint | hydroelastic | resolution_hint | Required for shapes that require tessellation to support hydroelastic contact. | | drake:hydroelastic_modulus | hydroelastic | hydroelastic_modulus | Finite positive value. Required for compliant hydroelastic representations. | | drake:hunt_crossley_dissipation | material | hunt_crossley_dissipation | | | drake:relaxation_time | material | relaxation_time | Required when using a linear model of dissipation, for instance with the SAP solver. | | drake:mu_dynamic | material | coulomb_friction | See note below on friction. | | drake:mu_static | material | coulomb_friction | See note below on friction. | | drake:rigid_hydroelastic | hydroelastic | compliance_type | Requests a rigid hydroelastic representation. Cannot be combined *with* soft_hydroelastic. | | drake:compliant_hydroelastic | hydroelastic | compliance_type | Requests a compliant hydroelastic representation. Cannot be combined *with* rigid_hydroelastic. Requires a value for hydroelastic_modulus. |

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. */ std::optional MakeProximityPropertiesForCollision( const SDFormatDiagnostic& diagnostic, 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 `` as the static coefficient of friction and `` as the dynamic coefficient of friction. Consider the example below: ```xml 0.8 0.3 ``` If mu or mu2 are not found, an error is emitted. If the error policy is not set to throw an std::nullopt is returned. */ std::optional> MakeCoulombFrictionFromSdfCollisionOde( const SDFormatDiagnostic& diagnostic, const sdf::Collision& sdf_collision); } // namespace internal } // namespace multibody } // namespace drake