Skip to content

Commit 153d805

Browse files
committed
[fem] Refactor ForceDensityField
The goal of the commit is the remove the dependency of the fem library from the tree library so that later we create deformable multibody element (in the tree library) that depends on fem.
1 parent bd7834f commit 153d805

18 files changed

+157
-86
lines changed

examples/multibody/deformable/point_source_force_field.h

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

33
#include <memory>
44

5-
#include "drake/multibody/plant/force_density_field.h"
5+
#include "drake/multibody/tree/force_density_field_impl.h"
66
#include "drake/multibody/plant/multibody_plant.h"
77

88
namespace drake {
@@ -16,7 +16,7 @@ namespace deformable {
1616
a double-valued input port (see maximum_force_density_input_port()). If the
1717
port is unconnected, it reads as zero. */
1818
class PointSourceForceField final
19-
: public multibody::ForceDensityField<double> {
19+
: public multibody::ForceDensityFieldImpl<double> {
2020
public:
2121
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(PointSourceForceField);
2222

multibody/fem/BUILD.bazel

Lines changed: 17 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,7 @@ drake_cc_package_library(
3232
":fem_solver",
3333
":fem_state",
3434
":fem_state_system",
35+
":force_density_field",
3536
":isoparametric_element",
3637
":linear_constitutive_model",
3738
":linear_constitutive_model_data",
@@ -251,9 +252,9 @@ drake_cc_library(
251252
"fem_plant_data.h",
252253
],
253254
deps = [
255+
":force_density_field",
254256
"//common:default_scalars",
255257
"//common:essential",
256-
"//multibody/plant:force_density_field",
257258
"//systems/framework:context",
258259
],
259260
)
@@ -308,6 +309,21 @@ drake_cc_library(
308309
],
309310
)
310311

312+
drake_cc_library(
313+
name = "force_density_field",
314+
srcs = [
315+
"force_density_field.cc",
316+
],
317+
hdrs = [
318+
"force_density_field.h",
319+
],
320+
deps = [
321+
"//common:default_scalars",
322+
"//common:essential",
323+
"//systems/framework:context",
324+
],
325+
)
326+
311327
drake_cc_library(
312328
name = "isoparametric_element",
313329
srcs = [

multibody/fem/fem_plant_data.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33

44
#include "drake/common/default_scalars.h"
55
#include "drake/common/drake_copyable.h"
6-
#include "drake/multibody/plant/force_density_field.h"
6+
#include "drake/multibody/fem/force_density_field.h"
77
#include "drake/systems/framework/context.h"
88

99
namespace drake {

multibody/fem/force_density_field.cc

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,13 @@
1+
#include "drake/multibody/fem/force_density_field.h"
2+
3+
namespace drake {
4+
namespace multibody {
5+
6+
template <typename T>
7+
ForceDensityField<T>::~ForceDensityField() = default;
8+
9+
} // namespace multibody
10+
} // namespace drake
11+
12+
DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS(
13+
class ::drake::multibody::ForceDensityField);

multibody/fem/force_density_field.h

Lines changed: 82 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,82 @@
1+
#pragma once
2+
3+
#include <memory>
4+
5+
#include "drake/common/default_scalars.h"
6+
#include "drake/common/drake_copyable.h"
7+
#include "drake/common/eigen_types.h"
8+
#include "drake/systems/framework/context.h"
9+
10+
namespace drake {
11+
namespace multibody {
12+
13+
template <typename T>
14+
class ForceDensityFieldImpl;
15+
16+
/** (Advanced) Enum for the type of force density in ForceDensityField. */
17+
enum class ForceDensityType {
18+
/** ForceDensityField::EvaluateAt() returns the force per unit of _current_
19+
(deformed) configuration volume. */
20+
kPerCurrentVolume,
21+
/** ForceDensityField::EvaluateAt() returns the force per unit of _reference_
22+
configuration volume where the reference undeformed configuration is defined
23+
by the input mesh provided by the user. */
24+
kPerReferenceVolume,
25+
};
26+
27+
/** The %ForceDensityField class is an abstract base class that represents a
28+
force density field affecting deformable bodies in a MultibodyPlant. The
29+
force field is described by the member function EvaluateAt() which takes as
30+
input a position in the world frame and returns the force density from the
31+
force density field at the given location, with unit [N/m³]. To create a
32+
concrete %ForceDensityField class, inherit from ForceDensityFieldImpl instead
33+
of directly inheriting from %ForceDensityField.
34+
@tparam_default_scalar */
35+
template <typename T>
36+
class ForceDensityField {
37+
public:
38+
virtual ~ForceDensityField() = 0;
39+
40+
/** Evaluates the force density [N/m³] with the given `context` of the
41+
owning MultibodyPlant and a position in world, `p_WQ`. */
42+
Vector3<T> EvaluateAt(const systems::Context<T>& context,
43+
const Vector3<T>& p_WQ) const {
44+
return DoEvaluateAt(context, p_WQ);
45+
}
46+
47+
/** Returns an identical copy of `this` ForceDensityField. */
48+
std::unique_ptr<ForceDensityField<T>> Clone() const { return DoClone(); }
49+
50+
/* (Advanced) Returns the force density type of `this` %ForceDensityFieldImpl.
51+
*/
52+
ForceDensityType density_type() const { return density_type_; }
53+
54+
protected:
55+
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(ForceDensityField);
56+
57+
/** Derived classes must override this function to provide a threadsafe
58+
implemention to the NVI EvaluateAt(). */
59+
virtual Vector3<T> DoEvaluateAt(const systems::Context<T>& context,
60+
const Vector3<T>& p_WQ) const = 0;
61+
62+
/** Derived classes must override this function to implement the NVI
63+
Clone(). */
64+
virtual std::unique_ptr<ForceDensityField<T>> DoClone() const = 0;
65+
66+
private:
67+
friend class ForceDensityFieldImpl<T>;
68+
69+
/* Private constructor exposed only to ForceDensityFieldImpl. This prevents
70+
users from creating concrete force densities that directly inherit from
71+
ForceDensityField. */
72+
explicit ForceDensityField(ForceDensityType density_type)
73+
: density_type_(density_type) {}
74+
75+
ForceDensityType density_type_;
76+
};
77+
78+
} // namespace multibody
79+
} // namespace drake
80+
81+
DRAKE_DECLARE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS(
82+
class ::drake::multibody::ForceDensityField);

multibody/fem/test/fem_element_test.cc

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@
44

55
#include "drake/multibody/fem/test/dummy_element.h"
66
#include "drake/multibody/plant/multibody_plant.h"
7+
#include "drake/multibody/tree/force_density_field_impl.h"
78

89
namespace drake {
910
namespace multibody {

multibody/fem/test/fem_model_test.cc

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,7 @@
1111
#include "drake/multibody/fem/volumetric_element.h"
1212
#include "drake/multibody/fem/volumetric_model.h"
1313
#include "drake/multibody/plant/multibody_plant.h"
14+
#include "drake/multibody/tree/force_density_field_impl.h"
1415

1516
namespace drake {
1617
namespace multibody {
@@ -118,7 +119,8 @@ GTEST_TEST(FemModelTest, CalcResidualWithContextDependentExternalForce) {
118119
unique_ptr<FemState<double>> fem_state = model.MakeFemState();
119120

120121
/* A force field where the magnitude of the force density depends on time. */
121-
class TimeScaledForceDensityField final : public ForceDensityField<double> {
122+
class TimeScaledForceDensityField final
123+
: public ForceDensityFieldImpl<double> {
122124
public:
123125
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(TimeScaledForceDensityField);
124126

multibody/fem/test/volumetric_element_test.cc

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,6 +11,7 @@
1111
#include "drake/multibody/fem/linear_simplex_element.h"
1212
#include "drake/multibody/fem/simplex_gaussian_quadrature.h"
1313
#include "drake/multibody/plant/multibody_plant.h"
14+
#include "drake/multibody/tree/force_density_field_impl.h"
1415

1516
namespace drake {
1617
namespace multibody {
@@ -419,7 +420,7 @@ TEST_F(VolumetricElementTest, PerCurrentVolumeExternalForce) {
419420

420421
const Vector3<AD> force_per_current_volume(4, 5, 6);
421422
/* A constant per current volume force density field. */
422-
class ConstantForceDensityField final : public ForceDensityField<AD> {
423+
class ConstantForceDensityField final : public ForceDensityFieldImpl<AD> {
423424
public:
424425
explicit ConstantForceDensityField(const Vector3<AD>& f) : f_(f) {}
425426

multibody/plant/BUILD.bazel

Lines changed: 1 addition & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,6 @@ drake_cc_package_library(
2626
":distance_constraint_params",
2727
":externally_applied_spatial_force",
2828
":externally_applied_spatial_force_multiplexer",
29-
":force_density_field",
3029
":internal_geometry_names",
3130
":multibody_plant_config",
3231
":multibody_plant_config_functions",
@@ -92,7 +91,7 @@ drake_cc_library(
9291
"discrete_step_memory.cc",
9392
"discrete_update_manager.cc",
9493
"dummy_physical_model.cc",
95-
"force_density_field_declare_system_resources.cc",
94+
"force_density_field_impl_declare_system_resources.cc",
9695
"geometry_contact_data.cc",
9796
"make_discrete_update_manager.cc",
9897
"multibody_element_getter.cc",
@@ -238,22 +237,6 @@ drake_cc_library(
238237
],
239238
)
240239

241-
drake_cc_library(
242-
name = "force_density_field",
243-
srcs = [
244-
"force_density_field.cc",
245-
],
246-
hdrs = [
247-
"force_density_field.h",
248-
],
249-
deps = [
250-
"//common:default_scalars",
251-
"//common:essential",
252-
"//multibody/tree",
253-
"//systems/framework:context",
254-
],
255-
)
256-
257240
drake_cc_library(
258241
name = "internal_geometry_names",
259242
srcs = ["internal_geometry_names.cc"],

multibody/plant/deformable_driver.cc

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -17,7 +17,6 @@
1717
#include "drake/multibody/fem/fem_model.h"
1818
#include "drake/multibody/plant/contact_properties.h"
1919
#include "drake/multibody/plant/discrete_update_manager.h"
20-
#include "drake/multibody/plant/force_density_field.h"
2120
#include "drake/multibody/plant/hydroelastic_quadrature_point_data.h"
2221
#include "drake/multibody/plant/multibody_plant.h"
2322
#include "drake/systems/framework/context.h"

multibody/plant/deformable_model.cc

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,7 @@
1414
#include "drake/multibody/fem/velocity_newmark_scheme.h"
1515
#include "drake/multibody/fem/volumetric_model.h"
1616
#include "drake/multibody/plant/multibody_plant.h"
17+
#include "drake/multibody/tree/force_density_field_impl.h"
1718

1819
namespace drake {
1920
namespace multibody {
@@ -583,7 +584,10 @@ void DeformableModel<T>::DoDeclareSystemResources() {
583584
them. */
584585
for (std::unique_ptr<ForceDensityField<T>>& force_density :
585586
force_densities_) {
586-
force_density->DeclareSystemResources(this->mutable_plant());
587+
/* We know that the static cast is safe because all concrete force density
588+
field is derived from ForceDensityFieldImpl. */
589+
static_cast<ForceDensityFieldImpl<T>*>(force_density.get())
590+
->DeclareSystemResources(this->mutable_plant());
587591
}
588592
}
589593

multibody/plant/deformable_model.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -13,9 +13,9 @@
1313
#include "drake/multibody/fem/deformable_body_config.h"
1414
#include "drake/multibody/fem/discrete_time_integrator.h"
1515
#include "drake/multibody/fem/fem_model.h"
16+
#include "drake/multibody/fem/force_density_field.h"
1617
#include "drake/multibody/plant/constraint_specs.h"
1718
#include "drake/multibody/plant/deformable_ids.h"
18-
#include "drake/multibody/plant/force_density_field.h"
1919
#include "drake/multibody/plant/physical_model.h"
2020
#include "drake/multibody/tree/rigid_body.h"
2121

multibody/plant/force_density_field_declare_system_resources.cc renamed to multibody/plant/force_density_field_impl_declare_system_resources.cc

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
#include "drake/common/default_scalars.h"
2-
#include "drake/multibody/plant/force_density_field.h"
32
#include "drake/multibody/plant/multibody_plant.h"
3+
#include "drake/multibody/tree/force_density_field_impl.h"
44

55
namespace drake {
66
namespace multibody {
@@ -10,7 +10,7 @@ namespace multibody {
1010
// isn't a no-op.
1111
template <typename T>
1212
template <typename>
13-
void ForceDensityField<T>::DeclareSystemResources(
13+
void ForceDensityFieldImpl<T>::DeclareSystemResources(
1414
internal::MultibodyTreeSystem<T>* tree_system) {
1515
DRAKE_DEMAND(tree_system != nullptr);
1616
/* `this` force field isn't already associated with a system. */
@@ -29,7 +29,7 @@ void ForceDensityField<T>::DeclareSystemResources(
2929

3030
// clang-format off
3131
DRAKE_DEFINE_FUNCTION_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS((
32-
&ForceDensityField<T>::template DeclareSystemResources<void>
32+
&ForceDensityFieldImpl<T>::template DeclareSystemResources<void>
3333
));
3434
// clang-format on
3535

multibody/plant/test/deformable_model_test.cc

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,7 @@
66
#include "drake/common/test_utilities/expect_throws_message.h"
77
#include "drake/multibody/plant/multibody_plant.h"
88
#include "drake/multibody/plant/multibody_plant_config_functions.h"
9+
#include "drake/multibody/tree/force_density_field_impl.h"
910
#include "drake/systems/framework/diagram_builder.h"
1011

1112
namespace drake {
@@ -348,7 +349,7 @@ TEST_F(DeformableModelTest, AddFixedConstraint) {
348349

349350
TEST_F(DeformableModelTest, ExternalForces) {
350351
/* A user defined force density field. */
351-
class ConstantForceDensityField final : public ForceDensityField<double> {
352+
class ConstantForceDensityField final : public ForceDensityFieldImpl<double> {
352353
public:
353354
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(ConstantForceDensityField);
354355

multibody/tree/BUILD.bazel

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -92,6 +92,7 @@ drake_cc_library(
9292
"door_hinge.cc",
9393
"element_collection.cc",
9494
"fixed_offset_frame.cc",
95+
"force_density_field_impl.cc",
9596
"force_element.cc",
9697
"frame.cc",
9798
"joint.cc",
@@ -137,6 +138,7 @@ drake_cc_library(
137138
"door_hinge.h",
138139
"element_collection.h",
139140
"fixed_offset_frame.h",
141+
"force_density_field_impl.h",
140142
"force_element.h",
141143
"frame.h",
142144
"joint.h",
@@ -189,6 +191,7 @@ drake_cc_library(
189191
"//common:unused",
190192
"//common/trajectories:piecewise_constant_curvature_trajectory",
191193
"//math:geometric_transform",
194+
"//multibody/fem:force_density_field",
192195
"//multibody/topology",
193196
"//systems/framework:leaf_system",
194197
],

multibody/plant/force_density_field.cc renamed to multibody/tree/force_density_field_impl.cc

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,13 @@
1-
#include "drake/multibody/plant/force_density_field.h"
1+
#include "drake/multibody/tree/force_density_field_impl.h"
22

33
namespace drake {
44
namespace multibody {
55

66
template <typename T>
7-
ForceDensityField<T>::~ForceDensityField() = default;
7+
ForceDensityFieldImpl<T>::~ForceDensityFieldImpl() = default;
88

99
template <typename T>
10-
systems::CacheEntry& ForceDensityField<T>::DeclareCacheEntry(
10+
systems::CacheEntry& ForceDensityFieldImpl<T>::DeclareCacheEntry(
1111
internal::MultibodyTreeSystem<T>* plant, std::string description,
1212
systems::ValueProducer value_producer,
1313
std::set<systems::DependencyTicket> prerequisites_of_calc) {
@@ -17,15 +17,15 @@ systems::CacheEntry& ForceDensityField<T>::DeclareCacheEntry(
1717
}
1818

1919
template <typename T>
20-
systems::InputPort<T>& ForceDensityField<T>::DeclareAbstractInputPort(
20+
systems::InputPort<T>& ForceDensityFieldImpl<T>::DeclareAbstractInputPort(
2121
internal::MultibodyTreeSystem<T>* plant, std::string name,
2222
const AbstractValue& model_value) {
2323
return internal::MultibodyTreeSystemElementAttorney<
2424
T>::DeclareAbstractInputPort(plant, std::move(name), model_value);
2525
}
2626

2727
template <typename T>
28-
systems::InputPort<T>& ForceDensityField<T>::DeclareVectorInputPort(
28+
systems::InputPort<T>& ForceDensityFieldImpl<T>::DeclareVectorInputPort(
2929
internal::MultibodyTreeSystem<T>* plant, std::string name,
3030
const systems::BasicVector<T>& model_vector) {
3131
return internal::MultibodyTreeSystemElementAttorney<
@@ -39,7 +39,7 @@ GravityForceField<T>::~GravityForceField() = default;
3939
} // namespace drake
4040

4141
DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS(
42-
class ::drake::multibody::ForceDensityField);
42+
class ::drake::multibody::ForceDensityFieldImpl);
4343

4444
DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS(
4545
class ::drake::multibody::GravityForceField);

0 commit comments

Comments
 (0)