/
proximity_properties.cc
173 lines (150 loc) · 5.98 KB
/
proximity_properties.cc
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
#include "drake/geometry/proximity_properties.h"
#include <array>
#include <string>
namespace drake {
namespace geometry {
namespace internal {
const char* const kMaterialGroup = "material";
const char* const kFriction = "coulomb_friction";
const char* const kHcDissipation = "hunt_crossley_dissipation";
const char* const kRelaxationTime = "relaxation_time";
const char* const kPointStiffness = "point_contact_stiffness";
const char* const kHydroGroup = "hydroelastic";
const char* const kElastic = "hydroelastic_modulus";
const char* const kRezHint = "resolution_hint";
const char* const kComplianceType = "compliance_type";
const char* const kSlabThickness = "slab_thickness";
namespace {
// Use a switch() statement here, to ensure the compiler sends us a reminder
// when somebody adds a new value to the enum. New values must be listed here
// as well as in the list of kHydroelasticTypes below.
constexpr const char* EnumToChars(HydroelasticType enum_value) {
switch (enum_value) {
case HydroelasticType::kUndefined:
return "undefined";
case HydroelasticType::kRigid:
return "rigid";
case HydroelasticType::kCompliant:
return "compliant";
}
DRAKE_UNREACHABLE();
}
template <typename Enum>
struct NamedEnum {
// An implicit conversion here enables the convenient initializer_list syntax
// that's used below, so we'll say NOLINTNEXTLINE(runtime/explicit).
constexpr NamedEnum(Enum value_in)
: value(value_in), name(EnumToChars(value_in)) {}
const Enum value;
const char* const name;
};
constexpr std::array<NamedEnum<HydroelasticType>, 3> kHydroelasticTypes{{
{HydroelasticType::kUndefined},
{HydroelasticType::kRigid},
{HydroelasticType::kCompliant},
}};
} // namespace
HydroelasticType GetHydroelasticTypeFromString(
std::string_view hydroelastic_type) {
for (const auto& [value, name] : kHydroelasticTypes) {
if (name == hydroelastic_type) {
return value;
}
}
throw std::logic_error(
fmt::format("Unknown hydroelastic_type: '{}'", hydroelastic_type));
}
std::string GetStringFromHydroelasticType(HydroelasticType hydroelastic_type) {
for (const auto& [value, name] : kHydroelasticTypes) {
if (value == hydroelastic_type) {
return name;
}
}
DRAKE_UNREACHABLE();
}
std::ostream& operator<<(std::ostream& out, const HydroelasticType& type) {
out << EnumToChars(type);
return out;
}
} // namespace internal
void AddContactMaterial(
std::optional<double> dissipation,
std::optional<double> point_stiffness,
const std::optional<multibody::CoulombFriction<double>>& friction,
ProximityProperties* properties) {
DRAKE_DEMAND(properties != nullptr);
if (dissipation.has_value()) {
if (*dissipation < 0) {
throw std::logic_error(fmt::format(
"The dissipation can't be negative; given {}", *dissipation));
}
properties->AddProperty(internal::kMaterialGroup, internal::kHcDissipation,
*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);
}
}
// 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 != nullptr);
properties->AddProperty(internal::kHydroGroup, internal::kRezHint,
resolution_hint);
AddRigidHydroelasticProperties(properties);
}
void AddRigidHydroelasticProperties(ProximityProperties* properties) {
DRAKE_DEMAND(properties != nullptr);
// The bare minimum of defining a rigid geometry is to declare its compliance
// type. Downstream consumers (ProximityEngine) will determine if this is
// sufficient.
properties->AddProperty(internal::kHydroGroup, internal::kComplianceType,
internal::HydroelasticType::kRigid);
}
namespace {
void AddCompliantHydroelasticProperties(double hydroelastic_modulus,
ProximityProperties* properties) {
DRAKE_DEMAND(properties != nullptr);
// The bare minimum of defining a compliant geometry is to declare its
// compliance type. Downstream consumers (ProximityEngine) will determine
// if this is sufficient.
if (hydroelastic_modulus <= 0) {
throw std::logic_error(
fmt::format("The hydroelastic modulus must be positive; given {}",
hydroelastic_modulus));
}
properties->AddProperty(internal::kHydroGroup, internal::kElastic,
hydroelastic_modulus);
properties->AddProperty(internal::kHydroGroup, internal::kComplianceType,
internal::HydroelasticType::kCompliant);
}
} // namespace
void AddCompliantHydroelasticProperties(double resolution_hint,
double hydroelastic_modulus,
ProximityProperties* properties) {
DRAKE_DEMAND(properties != nullptr);
properties->AddProperty(internal::kHydroGroup, internal::kRezHint,
resolution_hint);
AddCompliantHydroelasticProperties(hydroelastic_modulus, properties);
}
void AddCompliantHydroelasticPropertiesForHalfSpace(
double slab_thickness, double hydroelastic_modulus,
ProximityProperties* properties) {
DRAKE_DEMAND(properties != nullptr);
properties->AddProperty(internal::kHydroGroup, internal::kSlabThickness,
slab_thickness);
AddCompliantHydroelasticProperties(hydroelastic_modulus, properties);
}
} // namespace geometry
} // namespace drake