Skip to content

Commit

Permalink
added parsing of point_contact_stiffness (RobotLocomotion#13686)
Browse files Browse the repository at this point in the history
  • Loading branch information
joemasterjohn authored Jul 16, 2020
1 parent 0e2df7c commit bc71215
Show file tree
Hide file tree
Showing 5 changed files with 112 additions and 17 deletions.
19 changes: 19 additions & 0 deletions geometry/proximity_properties.cc
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,15 @@ void AddContactMaterial(
const std::optional<double>& dissipation,
const std::optional<multibody::CoulombFriction<double>>& friction,
ProximityProperties* properties) {
AddContactMaterial(elastic_modulus, dissipation, {}, friction, properties);
}

void AddContactMaterial(
const std::optional<double>& elastic_modulus,
const std::optional<double>& dissipation,
const std::optional<double>& point_stiffness,
const std::optional<multibody::CoulombFriction<double>>& friction,
ProximityProperties* properties) {
if (elastic_modulus.has_value()) {
if (*elastic_modulus <= 0) {
throw std::logic_error(fmt::format(
Expand All @@ -56,6 +65,16 @@ void AddContactMaterial(
*dissipation);
}

if (point_stiffness.has_value()) {
if (*point_stiffness <= 0) {
throw std::logic_error(fmt::format(
"The point_contact_stiffness must be strictly positive; given {}",
*point_stiffness));
}
properties->AddProperty(internal::kMaterialGroup, internal::kPointStiffness,
*point_stiffness);
}

if (friction.has_value()) {
properties->AddProperty(internal::kMaterialGroup, internal::kFriction,
*friction);
Expand Down
47 changes: 39 additions & 8 deletions geometry/proximity_properties.h
Original file line number Diff line number Diff line change
Expand Up @@ -88,20 +88,51 @@ std::ostream& operator<<(std::ostream& out, const HydroelasticType& type);

} // namespace internal

/**
* @anchor contact_material_utility_functions
* @name Contact Material Utility Functions
* AddContactMaterial() adds contact material properties to the given set of
* proximity `properties`. Only the parameters that carry values will be added
* to the given set of `properties`; no default values will be provided.
* Downstream consumers of the contact materials can optionally provide
* defaults for missing properties.
*
* For legacy and backwards compatibility purposes, two overloads for
* AddContactMaterial() are provided. One supports all contact material
* properties **except** `point_stiffness`, and the other includes it.
* Users are encouraged to use the overload that contains the argument for
* `point_stiffness`.
*
* These functions will throw an error if:
* - `elastic_modulus` is not positive
* - `dissipation` is negative
* - `point_stiffness` is not positive
* - Any of the contact material properties have already been defined in
* `properties`.
*/
///@{
/**
* @throws std::logic_error if any parameter doesn't satisfy the requirements
* listed in @ref contact_material_utility_functions
* "Contact Material Utility Functions".
*/
void AddContactMaterial(
const std::optional<double>& elastic_modulus,
const std::optional<double>& dissipation,
const std::optional<double>& point_stiffness,
const std::optional<multibody::CoulombFriction<double>>& friction,
ProximityProperties* properties);

/** Adds contact material properties to the given set of proximity `properties`.
Only the parameters that carry values will be added to the given set of
`properties`; no default values will be provided. Downstream consumers of the
contact materials can optionally provide defaults for missing properties.
@throws std::logic_error if `elastic_modulus` is not positive, `dissipation` is
negative, or any of the contact material properties
have already been defined in `properties`. */
/**
* @warning Please use the overload of AddContactMaterial() that includes the
* argument for `point_stiffness` rather than this one.
*/
void AddContactMaterial(
const std::optional<double>& elastic_modulus,
const std::optional<double>& dissipation,
const std::optional<multibody::CoulombFriction<double>>& friction,
ProximityProperties* properties);
///@}

/** Adds properties to the given set of proximity properties sufficient to cause
the associated geometry to generate a rigid hydroelastic representation.
Expand Down
42 changes: 35 additions & 7 deletions geometry/test/proximity_properties_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ using internal::kComplianceType;
using internal::kElastic;
using internal::kFriction;
using internal::kHcDissipation;
using internal::kPointStiffness;
using internal::kHydroGroup;
using internal::kMaterialGroup;
using internal::kRezHint;
Expand All @@ -23,14 +24,16 @@ using CoulombFrictiond = multibody::CoulombFriction<double>;
GTEST_TEST(ProximityPropertiesTest, AddContactMaterial) {
const double E = 1e8;
const double d = 0.1;
const double ps = 250.0;
CoulombFrictiond mu{0.9, 0.5};

// Case: Correct configuration.
{
ProximityProperties p;
EXPECT_NO_THROW(AddContactMaterial(E, d, mu, &p));
EXPECT_NO_THROW(AddContactMaterial(E, d, ps, mu, &p));
EXPECT_EQ(p.GetProperty<double>(kMaterialGroup, kElastic), E);
EXPECT_EQ(p.GetProperty<double>(kMaterialGroup, kHcDissipation), d);
EXPECT_EQ(p.GetProperty<double>(kMaterialGroup, kPointStiffness), ps);
const CoulombFrictiond& mu_stored =
p.GetProperty<CoulombFrictiond>(kMaterialGroup, kFriction);
EXPECT_EQ(mu_stored.static_friction(), mu.static_friction());
Expand All @@ -42,7 +45,7 @@ GTEST_TEST(ProximityPropertiesTest, AddContactMaterial) {
ProximityProperties p;
p.AddProperty(kMaterialGroup, kElastic, E);
DRAKE_EXPECT_THROWS_MESSAGE(
AddContactMaterial(E, d, mu, &p), std::logic_error,
AddContactMaterial(E, d, ps, mu, &p), std::logic_error,
".+ Trying to add property \\('.+', '.+'\\).+ name already exists");
}

Expand All @@ -51,7 +54,16 @@ GTEST_TEST(ProximityPropertiesTest, AddContactMaterial) {
ProximityProperties p;
p.AddProperty(kMaterialGroup, kHcDissipation, d);
DRAKE_EXPECT_THROWS_MESSAGE(
AddContactMaterial(E, d, mu, &p), std::logic_error,
AddContactMaterial(E, d, ps, mu, &p), std::logic_error,
".+ Trying to add property \\('.+', '.+'\\).+ name already exists");
}

// Error case: Already has stiffness.
{
ProximityProperties p;
p.AddProperty(kMaterialGroup, kPointStiffness, ps);
DRAKE_EXPECT_THROWS_MESSAGE(
AddContactMaterial(E, d, ps, mu, &p), std::logic_error,
".+ Trying to add property \\('.+', '.+'\\).+ name already exists");
}

Expand All @@ -60,33 +72,49 @@ GTEST_TEST(ProximityPropertiesTest, AddContactMaterial) {
ProximityProperties p;
p.AddProperty(kMaterialGroup, kFriction, mu);
DRAKE_EXPECT_THROWS_MESSAGE(
AddContactMaterial(E, d, mu, &p), std::logic_error,
AddContactMaterial(E, d, ps, mu, &p), std::logic_error,
".+ Trying to add property \\('.+', '.+'\\).+ name already exists");
}

// Error case: 0 elasticity.
{
ProximityProperties p;
DRAKE_EXPECT_THROWS_MESSAGE(AddContactMaterial(0, d, mu, &p),
DRAKE_EXPECT_THROWS_MESSAGE(AddContactMaterial(0, d, ps, mu, &p),
std::logic_error,
".+elastic modulus must be positive.+");
}

// Error case: negative elasticity.
{
ProximityProperties p;
DRAKE_EXPECT_THROWS_MESSAGE(AddContactMaterial(-1.3, d, mu, &p),
DRAKE_EXPECT_THROWS_MESSAGE(AddContactMaterial(-1.3, d, ps, mu, &p),
std::logic_error,
".+elastic modulus must be positive.+");
}

// Error case: negative dissipation.
{
ProximityProperties p;
DRAKE_EXPECT_THROWS_MESSAGE(AddContactMaterial(E, -1.2, mu, &p),
DRAKE_EXPECT_THROWS_MESSAGE(AddContactMaterial(E, -1.2, ps, mu, &p),
std::logic_error,
".+dissipation can't be negative.+");
}

// Error case: negative stiffness.
{
ProximityProperties p;
DRAKE_EXPECT_THROWS_MESSAGE(AddContactMaterial(E, d, -200, mu, &p),
std::logic_error,
".+stiffness must be strictly positive.+");
}

// Error case: zero-valued stiffness.
{
ProximityProperties p;
DRAKE_EXPECT_THROWS_MESSAGE(AddContactMaterial(E, d, 0, mu, &p),
std::logic_error,
".+stiffness must be strictly positive.+");
}
}

GTEST_TEST(ProximityPropertiesTest, AddRigidProperties) {
Expand Down
7 changes: 5 additions & 2 deletions multibody/parsing/detail_common.cc
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,9 @@ geometry::ProximityProperties ParseProximityProperties(
std::optional<double> dissipation =
read_double("drake:hunt_crossley_dissipation");

std::optional<double> stiffness =
read_double("drake:point_contact_stiffness");

std::optional<double> mu_dynamic = read_double("drake:mu_dynamic");
std::optional<double> mu_static = read_double("drake:mu_static");
std::optional<CoulombFriction<double>> friction;
Expand All @@ -46,8 +49,8 @@ geometry::ProximityProperties ParseProximityProperties(
friction = CoulombFriction<double>(*mu_static, *mu_static);
}

geometry::AddContactMaterial(elastic_modulus, dissipation, friction,
&properties);
geometry::AddContactMaterial(elastic_modulus, dissipation, stiffness,
friction, &properties);

return properties;
}
Expand Down
14 changes: 14 additions & 0 deletions multibody/parsing/test/detail_common_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,7 @@ using geometry::internal::kComplianceType;
using geometry::internal::kElastic;
using geometry::internal::kFriction;
using geometry::internal::kHcDissipation;
using geometry::internal::kPointStiffness;
using geometry::internal::kHydroGroup;
using geometry::internal::kMaterialGroup;
using geometry::internal::kRezHint;
Expand Down Expand Up @@ -171,6 +172,19 @@ GTEST_TEST(ParseProximityPropertiesTest, Dissipation) {
EXPECT_EQ(properties.num_groups(), 2); // Material and default groups.
}

// Confirms successful parsing of stiffness.
GTEST_TEST(ParseProximityPropertiesTest, Stiffness) {
const double kValue = 300.0;
ProximityProperties properties = ParseProximityProperties(
param_read_double("drake:point_contact_stiffness", kValue), !rigid,
!soft);
EXPECT_TRUE(
ExpectScalar(kMaterialGroup, kPointStiffness, kValue, properties));
// Stiffness is the only property.
EXPECT_EQ(properties.GetPropertiesInGroup(kMaterialGroup).size(), 1u);
EXPECT_EQ(properties.num_groups(), 2); // Material and default groups.
}

// Confirms successful parsing of friction.
GTEST_TEST(ParseProximityPropertiesTest, Friction) {
// We're not testing the case where *no* coefficients are provided; that's
Expand Down

0 comments on commit bc71215

Please sign in to comment.