Skip to content

Commit 25965fc

Browse files
committed
Address feature review comments
1 parent 085db92 commit 25965fc

File tree

6 files changed

+69
-43
lines changed

6 files changed

+69
-43
lines changed

multibody/plant/deformable_ids.h

Lines changed: 0 additions & 11 deletions
This file was deleted.

multibody/plant/deformable_model.cc

Lines changed: 32 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -44,20 +44,23 @@ DeformableBodyId DeformableModel<T>::RegisterDeformableBody(
4444
ModelInstanceIndex model_instance,
4545
const fem::DeformableBodyConfig<T>& config, double resolution_hint) {
4646
this->ThrowIfSystemResourcesDeclared(__func__);
47+
ThrowIfNotDiscrete(__func__);
4748
ThrowIfNotDouble(__func__);
4849
if (!(model_instance < this->plant().num_model_instances())) {
4950
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().");
5254
}
5355
if constexpr (std::is_same_v<T, double>) {
5456
const std::string name = geometry_instance->name();
5557
if (HasBodyNamed(name, model_instance)) {
5658
const std::string& model_instance_name =
5759
this->plant().GetModelInstanceName(model_instance);
5860
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.",
6164
model_instance_name, name));
6265
}
6366
/* Register the geometry with SceneGraph. */
@@ -162,6 +165,7 @@ void DeformableModel<T>::AddExternalForce(
162165
std::unique_ptr<ForceDensityFieldBase<T>> force_density) {
163166
this->ThrowIfSystemResourcesDeclared(__func__);
164167
ThrowIfNotDouble(__func__);
168+
ThrowIfNotDiscrete(__func__);
165169
force_densities_.push_back(std::move(force_density));
166170
}
167171

@@ -221,17 +225,18 @@ bool DeformableModel<T>::HasBodyNamed(const std::string& name) const {
221225
template <typename T>
222226
bool DeformableModel<T>::HasBodyNamed(const std::string& name,
223227
ModelInstanceIndex model_instance) const {
224-
return !GetBodyIndicesByName(name, model_instance).empty();
228+
return GetBodyIndexByName(name, model_instance).has_value();
225229
}
226230

227231
template <typename T>
228232
const DeformableBody<T>& DeformableModel<T>::GetBodyByName(
229233
const std::string& name) const {
230234
const std::vector<DeformableBodyIndex> indices = GetBodyIndicesByName(name);
231235
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));
235240
}
236241
if (indices.size() > 1) {
237242
throw std::runtime_error(
@@ -245,15 +250,15 @@ const DeformableBody<T>& DeformableModel<T>::GetBodyByName(
245250
template <typename T>
246251
const DeformableBody<T>& DeformableModel<T>::GetBodyByName(
247252
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()) {
251256
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 {}.",
253259
name, model_instance));
254260
}
255-
DRAKE_DEMAND(ssize(indices) == 1);
256-
return deformable_bodies_.get_element(indices[0]);
261+
return deformable_bodies_.get_element(index.value());
257262
}
258263

259264
template <typename T>
@@ -364,7 +369,7 @@ DeformableModel<T>::CloneToSymbolic(
364369
template <typename T>
365370
void DeformableModel<T>::DoDeclareSystemResources() {
366371
if constexpr (!std::is_same_v<T, double>) {
367-
/* A none double DeformableModel is always empty. */
372+
/* A non-double DeformableModel is always empty. */
368373
DRAKE_DEMAND(is_empty());
369374
return;
370375
} else {
@@ -467,6 +472,15 @@ void DeformableModel<T>::ThrowIfNotDouble(const char* function_name) const {
467472
function_name));
468473
}
469474
}
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+
}
470484

471485
template <typename T>
472486
std::vector<DeformableBodyIndex> DeformableModel<T>::GetBodyIndicesByName(
@@ -481,18 +495,17 @@ std::vector<DeformableBodyIndex> DeformableModel<T>::GetBodyIndicesByName(
481495
}
482496

483497
template <typename T>
484-
std::vector<DeformableBodyIndex> DeformableModel<T>::GetBodyIndicesByName(
498+
std::optional<DeformableBodyIndex> DeformableModel<T>::GetBodyIndexByName(
485499
const std::string& name, ModelInstanceIndex model_instance) const {
486500
/* Use the name lookup for its side-effect of throwing on an invalid index. */
487501
unused(this->plant().GetModelInstanceName(model_instance));
488502
auto [lower, upper] = deformable_bodies_.names_map().equal_range(name);
489-
std::vector<DeformableBodyIndex> indices;
490503
for (auto it = lower; it != upper; ++it) {
491504
if (GetBody(it->second).model_instance() == model_instance) {
492-
indices.push_back(it->second);
505+
return it->second;
493506
}
494507
}
495-
return indices;
508+
return std::nullopt;
496509
}
497510

498511
} // namespace multibody

multibody/plant/deformable_model.h

Lines changed: 19 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22

33
#include <map>
44
#include <memory>
5+
#include <optional>
56
#include <string>
67
#include <unordered_map>
78
#include <vector>
@@ -82,6 +83,8 @@ class DeformableModel final : public multibody::PhysicalModel<T> {
8283
@pre resolution_hint > 0.
8384
@throws std::exception if `this` %DeformableModel is not of scalar type
8485
double.
86+
@throws std::exception if `this` %DeformableModel belongs to a continuous
87+
MultibodyPlant.
8588
@throws std::exception if the model instance does not exist.
8689
@throws std::exception if a deformable body with the same name has already
8790
been registered to the model instance.
@@ -302,7 +305,7 @@ class DeformableModel final : public multibody::PhysicalModel<T> {
302305
DeformableBodyIndex index = GetBodyIndex(id);
303306
return deformable_bodies_.get_element(index);
304307
} else {
305-
/* A none double DeformableModel is always empty. */
308+
/* A non-double DeformableModel is always empty. */
306309
DRAKE_UNREACHABLE();
307310
}
308311
}
@@ -314,12 +317,12 @@ class DeformableModel final : public multibody::PhysicalModel<T> {
314317
if constexpr (std::is_same_v<T, double>) {
315318
return deformable_bodies_.get_element(index);
316319
} else {
317-
/* A none double DeformableModel is always empty. */
320+
/* A non-double DeformableModel is always empty. */
318321
DRAKE_UNREACHABLE();
319322
}
320323
}
321324

322-
/** Returns the deformable body with the given `id`.
325+
/** Returns a mutable reference to the deformable body with the given `id`.
323326
@throws std::exception if no deformable body with the given `id` has been
324327
registered in this model. */
325328
DeformableBody<T>& GetMutableBody(DeformableBodyId id) {
@@ -328,7 +331,7 @@ class DeformableModel final : public multibody::PhysicalModel<T> {
328331
DeformableBodyIndex index = GetBodyIndex(id);
329332
return deformable_bodies_.get_mutable_element(index);
330333
} else {
331-
/* A none double DeformableModel is always empty. */
334+
/* A non-double DeformableModel is always empty. */
332335
DRAKE_UNREACHABLE();
333336
}
334337
}
@@ -344,12 +347,13 @@ class DeformableModel final : public multibody::PhysicalModel<T> {
344347

345348
/** Returns the DeformableBody with the given name.
346349
@throws std::exception if there's no body with the given name or if more than
347-
one model instance contains deformable body with the given name. */
350+
one model instance contains a deformable body with the given name. */
348351
const DeformableBody<T>& GetBodyByName(const std::string& name) const;
349352

350-
/** Returns the DeformableBody with the given name.
351-
@throws std::exception if there's no body with the given name or if more than
352-
one model instance contains deformable body with the given name. */
353+
/** Returns the DeformableBody with the given name from the given model
354+
instance.
355+
@throws std::exception if there's no body with the given name that is
356+
registered with the given model instance. */
353357
const DeformableBody<T>& GetBodyByName(
354358
const std::string& name, ModelInstanceIndex model_instance) const;
355359

@@ -472,14 +476,18 @@ class DeformableModel final : public multibody::PhysicalModel<T> {
472476
a DeformableModel that doesn't have scalar type double. */
473477
void ThrowIfNotDouble(const char* function_name) const;
474478

479+
/* Helper to throw a useful message if the given `function_name` is called on
480+
a DeformableModel that belongs to a continuous plant. */
481+
void ThrowIfNotDiscrete(const char* function_name) const;
482+
475483
/* Returns all body indices with exactly this name (no model instance check).
476484
*/
477485
std::vector<DeformableBodyIndex> GetBodyIndicesByName(
478486
const std::string& name) const;
479487

480-
/* Returns all body indices with this name *and* in the given model instance.
481-
*/
482-
std::vector<DeformableBodyIndex> GetBodyIndicesByName(
488+
/* Returns the index of the deformable body with this name *and* in the given
489+
model instance if any; otherwise returns std::nullopt. */
490+
std::optional<DeformableBodyIndex> GetBodyIndexByName(
483491
const std::string& name, ModelInstanceIndex model_instance) const;
484492

485493
/* Data members. WARNING: if you add a field here be sure to update

multibody/plant/test/deformable_model_test.cc

Lines changed: 16 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -85,6 +85,15 @@ TEST_F(DeformableModelTest, RegisterDeformableBody) {
8585
make_unique<Sphere>(1), "sphere"),
8686
default_body_config_, kRezHint),
8787
".*RegisterDeformableBody.*after system resources have been declared.*");
88+
89+
/* Registering a deformable body within a continous plant throws. */
90+
MultibodyPlant<double> continuous_plant(0.0);
91+
DRAKE_EXPECT_THROWS_MESSAGE(
92+
continuous_plant.mutable_deformable_model().RegisterDeformableBody(
93+
make_unique<GeometryInstance>(RigidTransformd(),
94+
make_unique<Sphere>(1), "sphere"),
95+
default_body_config_, kRezHint),
96+
".*RegisterDeformableBody.*continuous MultibodyPlant.*not allowed.*");
8897
}
8998

9099
/* Coarsely tests that SetWallBoundaryCondition adds some sort of boundary
@@ -428,6 +437,13 @@ TEST_F(DeformableModelTest, ExternalForces) {
428437
EXPECT_EQ(force->EvaluateAt(*plant_context, p_WQ), scale * 3.14 * p_WQ);
429438
}
430439
}
440+
441+
/* Registering an external force within a continous plant throws. */
442+
MultibodyPlant<double> continuous_plant(0.0);
443+
DRAKE_EXPECT_THROWS_MESSAGE(
444+
continuous_plant.mutable_deformable_model().AddExternalForce(
445+
std::make_unique<ConstantForceDensityField>(force_field)),
446+
".*AddExternalForce.*continuous MultibodyPlant.*not allowed.*");
431447
}
432448

433449
TEST_F(DeformableModelTest, CloneBeforeFinalizeThrows) {

multibody/tree/deformable_body.cc

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -197,7 +197,7 @@ template <typename T>
197197
std::unique_ptr<DeformableBody<double>> DeformableBody<T>::CloneToDouble()
198198
const {
199199
if constexpr (!std::is_same_v<T, double>) {
200-
/* A none double body shouldn't exist in the first place. */
200+
/* A non-double body shouldn't exist in the first place. */
201201
DRAKE_UNREACHABLE();
202202
} else {
203203
auto clone =

multibody/tree/multibody_element.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -151,7 +151,7 @@ class MultibodyElement {
151151
virtual void DoSetDefaultParameters(systems::Parameters<T>*) const;
152152

153153
/// Implementation of the NVI DeclareDiscreteState(). MultibodyElement-derived
154-
/// objects may override to declare their specific parameters.
154+
/// objects may override to declare their specific state variables.
155155
virtual void DoDeclareDiscreteState(internal::MultibodyTreeSystem<T>*);
156156

157157
/// To be used by MultibodyElement-derived objects when declaring parameters

0 commit comments

Comments
 (0)