@@ -44,20 +44,23 @@ DeformableBodyId DeformableModel<T>::RegisterDeformableBody(
44
44
ModelInstanceIndex model_instance,
45
45
const fem::DeformableBodyConfig<T>& config, double resolution_hint) {
46
46
this ->ThrowIfSystemResourcesDeclared (__func__);
47
+ ThrowIfNotDiscrete (__func__);
47
48
ThrowIfNotDouble (__func__);
48
49
if (!(model_instance < this ->plant ().num_model_instances ())) {
49
50
throw std::logic_error (
50
- " Invalid model instance specified. A valid model instance can be "
51
- " obtained by calling MultibodyPlant::AddModelInstance()." );
51
+ " RegisterDeformableBody(): Invalid model instance specified. A valid "
52
+ " model instance can be obtained by calling "
53
+ " MultibodyPlant::AddModelInstance()." );
52
54
}
53
55
if constexpr (std::is_same_v<T, double >) {
54
56
const std::string name = geometry_instance->name ();
55
57
if (HasBodyNamed (name, model_instance)) {
56
58
const std::string& model_instance_name =
57
59
this ->plant ().GetModelInstanceName (model_instance);
58
60
throw std::logic_error (fmt::format (
59
- " Model instance '{}' already contains a deformable body "
60
- " named '{}'. Body names must be unique within a given model." ,
61
+ " RegisterDeformableBody(): Model instance '{}' already contains a "
62
+ " deformable body named '{}'. Body names must be unique within a "
63
+ " given model." ,
61
64
model_instance_name, name));
62
65
}
63
66
/* Register the geometry with SceneGraph. */
@@ -162,6 +165,7 @@ void DeformableModel<T>::AddExternalForce(
162
165
std::unique_ptr<ForceDensityFieldBase<T>> force_density) {
163
166
this ->ThrowIfSystemResourcesDeclared (__func__);
164
167
ThrowIfNotDouble (__func__);
168
+ ThrowIfNotDiscrete (__func__);
165
169
force_densities_.push_back (std::move (force_density));
166
170
}
167
171
@@ -221,17 +225,18 @@ bool DeformableModel<T>::HasBodyNamed(const std::string& name) const {
221
225
template <typename T>
222
226
bool DeformableModel<T>::HasBodyNamed(const std::string& name,
223
227
ModelInstanceIndex model_instance) const {
224
- return ! GetBodyIndicesByName (name, model_instance).empty ();
228
+ return GetBodyIndexByName (name, model_instance).has_value ();
225
229
}
226
230
227
231
template <typename T>
228
232
const DeformableBody<T>& DeformableModel<T>::GetBodyByName(
229
233
const std::string& name) const {
230
234
const std::vector<DeformableBodyIndex> indices = GetBodyIndicesByName (name);
231
235
if (indices.empty ()) {
232
- throw std::runtime_error (fmt::format (
233
- " No deformable body with the given name {} has been registered." ,
234
- name));
236
+ throw std::runtime_error (
237
+ fmt::format (" GetBodyByName(): No deformable body with the given name "
238
+ " {} has been registered." ,
239
+ name));
235
240
}
236
241
if (indices.size () > 1 ) {
237
242
throw std::runtime_error (
@@ -245,15 +250,15 @@ const DeformableBody<T>& DeformableModel<T>::GetBodyByName(
245
250
template <typename T>
246
251
const DeformableBody<T>& DeformableModel<T>::GetBodyByName(
247
252
const std::string& name, ModelInstanceIndex model_instance) const {
248
- const std::vector <DeformableBodyIndex> indices =
249
- GetBodyIndicesByName (name, model_instance);
250
- if (indices. empty ()) {
253
+ const std::optional <DeformableBodyIndex> index =
254
+ GetBodyIndexByName (name, model_instance);
255
+ if (!index. has_value ()) {
251
256
throw std::runtime_error (
252
- fmt::format (" No deformable body with the given name {} in instance {}." ,
257
+ fmt::format (" GetBodyByName(): No deformable body with the given name "
258
+ " {} in instance {}." ,
253
259
name, model_instance));
254
260
}
255
- DRAKE_DEMAND (ssize (indices) == 1 );
256
- return deformable_bodies_.get_element (indices[0 ]);
261
+ return deformable_bodies_.get_element (index.value ());
257
262
}
258
263
259
264
template <typename T>
@@ -364,7 +369,7 @@ DeformableModel<T>::CloneToSymbolic(
364
369
template <typename T>
365
370
void DeformableModel<T>::DoDeclareSystemResources() {
366
371
if constexpr (!std::is_same_v<T, double >) {
367
- /* A none double DeformableModel is always empty. */
372
+ /* A non- double DeformableModel is always empty. */
368
373
DRAKE_DEMAND (is_empty ());
369
374
return ;
370
375
} else {
@@ -467,6 +472,15 @@ void DeformableModel<T>::ThrowIfNotDouble(const char* function_name) const {
467
472
function_name));
468
473
}
469
474
}
475
+ template <typename T>
476
+ void DeformableModel<T>::ThrowIfNotDiscrete(const char * function_name) const {
477
+ if (!this ->plant ().is_discrete ()) {
478
+ throw std::logic_error (
479
+ fmt::format (" Calls to {}() with a DeformableModel belonging to a "
480
+ " continuous MultibodyPlant are not allowed." ,
481
+ function_name));
482
+ }
483
+ }
470
484
471
485
template <typename T>
472
486
std::vector<DeformableBodyIndex> DeformableModel<T>::GetBodyIndicesByName(
@@ -481,18 +495,17 @@ std::vector<DeformableBodyIndex> DeformableModel<T>::GetBodyIndicesByName(
481
495
}
482
496
483
497
template <typename T>
484
- std::vector <DeformableBodyIndex> DeformableModel<T>::GetBodyIndicesByName (
498
+ std::optional <DeformableBodyIndex> DeformableModel<T>::GetBodyIndexByName (
485
499
const std::string& name, ModelInstanceIndex model_instance) const {
486
500
/* Use the name lookup for its side-effect of throwing on an invalid index. */
487
501
unused (this ->plant ().GetModelInstanceName (model_instance));
488
502
auto [lower, upper] = deformable_bodies_.names_map ().equal_range (name);
489
- std::vector<DeformableBodyIndex> indices;
490
503
for (auto it = lower; it != upper; ++it) {
491
504
if (GetBody (it->second ).model_instance () == model_instance) {
492
- indices. push_back ( it->second ) ;
505
+ return it->second ;
493
506
}
494
507
}
495
- return indices ;
508
+ return std::nullopt ;
496
509
}
497
510
498
511
} // namespace multibody
0 commit comments