Skip to content

Commit 8f02c60

Browse files
committed
rename
1 parent e6be317 commit 8f02c60

22 files changed

+102
-101
lines changed

examples/multibody/deformable/point_source_force_field.cc

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@ namespace drake {
44
namespace examples {
55
namespace deformable {
66

7-
using multibody::ForceDensityField;
7+
using multibody::ForceDensityFieldBase;
88
using multibody::MultibodyPlant;
99
using multibody::RigidBody;
1010
using systems::BasicVector;
@@ -38,7 +38,7 @@ Vector3<double> PointSourceForceField::DoEvaluateAt(
3838
return magnitude * p_QC_W / p_QC_W.norm();
3939
}
4040

41-
std::unique_ptr<ForceDensityField<double>> PointSourceForceField::DoClone()
41+
std::unique_ptr<ForceDensityFieldBase<double>> PointSourceForceField::DoClone()
4242
const {
4343
return std::make_unique<PointSourceForceField>(
4444
*plant_, plant_->get_body(body_), p_BC_, falloff_distance_);

examples/multibody/deformable/point_source_force_field.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
#include <memory>
44

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

88
namespace drake {
99
namespace examples {
@@ -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::ForceDensityFieldImpl<double> {
19+
: public multibody::ForceDensityField<double> {
2020
public:
2121
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(PointSourceForceField);
2222

@@ -61,7 +61,7 @@ class PointSourceForceField final
6161
Vector3<double> DoEvaluateAt(const systems::Context<double>& context,
6262
const Vector3<double>& p_WQ) const final;
6363

64-
std::unique_ptr<ForceDensityField<double>> DoClone() const final;
64+
std::unique_ptr<ForceDensityFieldBase<double>> DoClone() const final;
6565

6666
void DoDeclareCacheEntries(multibody::MultibodyPlant<double>* plant) final;
6767

multibody/fem/BUILD.bazel

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,7 @@ drake_cc_package_library(
3232
":fem_solver",
3333
":fem_state",
3434
":fem_state_system",
35-
":force_density_field",
35+
":force_density_field_base",
3636
":isoparametric_element",
3737
":linear_constitutive_model",
3838
":linear_constitutive_model_data",
@@ -252,7 +252,7 @@ drake_cc_library(
252252
"fem_plant_data.h",
253253
],
254254
deps = [
255-
":force_density_field",
255+
":force_density_field_base",
256256
"//common:default_scalars",
257257
"//common:essential",
258258
"//systems/framework:context",
@@ -310,12 +310,12 @@ drake_cc_library(
310310
)
311311

312312
drake_cc_library(
313-
name = "force_density_field",
313+
name = "force_density_field_base",
314314
srcs = [
315-
"force_density_field.cc",
315+
"force_density_field_base.cc",
316316
],
317317
hdrs = [
318-
"force_density_field.h",
318+
"force_density_field_base.h",
319319
],
320320
deps = [
321321
"//common:default_scalars",
@@ -732,9 +732,9 @@ drake_cc_googletest(
732732
)
733733

734734
drake_cc_googletest(
735-
name = "force_density_field_test",
735+
name = "force_density_field_base_test",
736736
deps = [
737-
":force_density_field",
737+
":force_density_field_base",
738738
"//multibody/plant",
739739
],
740740
)

multibody/fem/fem_plant_data.h

Lines changed: 5 additions & 5 deletions
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/fem/force_density_field.h"
6+
#include "drake/multibody/fem/force_density_field_base.h"
77
#include "drake/systems/framework/context.h"
88

99
namespace drake {
@@ -19,14 +19,14 @@ template <typename T>
1919
struct FemPlantData {
2020
public:
2121
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(FemPlantData);
22-
FemPlantData(
23-
const systems::Context<T>& plant_context_in,
24-
const std::vector<const ForceDensityField<T>*>& force_density_fields_in)
22+
FemPlantData(const systems::Context<T>& plant_context_in,
23+
const std::vector<const ForceDensityFieldBase<T>*>&
24+
force_density_fields_in)
2525
: plant_context(plant_context_in),
2626
force_density_fields(force_density_fields_in) {}
2727

2828
const systems::Context<T>& plant_context;
29-
std::vector<const ForceDensityField<T>*> force_density_fields;
29+
std::vector<const ForceDensityFieldBase<T>*> force_density_fields;
3030
};
3131

3232
} // namespace fem
Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,13 @@
1-
#include "drake/multibody/fem/force_density_field.h"
1+
#include "drake/multibody/fem/force_density_field_base.h"
22

33
namespace drake {
44
namespace multibody {
55

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

99
} // namespace multibody
1010
} // namespace drake
1111

1212
DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS(
13-
class ::drake::multibody::ForceDensityField);
13+
class ::drake::multibody::ForceDensityFieldBase);

multibody/fem/force_density_field.h renamed to multibody/fem/force_density_field_base.h

Lines changed: 22 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -11,31 +11,31 @@ namespace drake {
1111
namespace multibody {
1212

1313
template <typename T>
14-
class ForceDensityFieldImpl;
14+
class ForceDensityField;
1515

16-
/** (Advanced) Enum for the type of force density in ForceDensityField. */
16+
/** (Advanced) Enum for the type of force density in ForceDensityFieldBase. */
1717
enum class ForceDensityType {
18-
/** ForceDensityField::EvaluateAt() returns the force per unit of _current_
19-
(deformed) configuration volume. */
18+
/** ForceDensityFieldBase::EvaluateAt() returns the force per unit of
19+
_current_ (deformed) configuration volume. */
2020
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. */
21+
/** ForceDensityFieldBase::EvaluateAt() returns the force per unit of
22+
_reference_ configuration volume where the reference undeformed configuration
23+
is defined by the input mesh provided by the user. */
2424
kPerReferenceVolume,
2525
};
2626

27-
/** The %ForceDensityField class is an abstract base class that represents a
27+
/** The %ForceDensityFieldBase class is an abstract base class that represents a
2828
force density field affecting deformable bodies in a MultibodyPlant. The
2929
force field is described by the member function EvaluateAt() which takes as
3030
input a position in the world frame and returns the force density from the
3131
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.
32+
concrete %ForceDensityFieldBase class, inherit from ForceDensityField instead
33+
of directly inheriting from %ForceDensityFieldBase.
3434
@tparam_default_scalar */
3535
template <typename T>
36-
class ForceDensityField {
36+
class ForceDensityFieldBase {
3737
public:
38-
virtual ~ForceDensityField() = 0;
38+
virtual ~ForceDensityFieldBase() = 0;
3939

4040
/** Evaluates the force density [N/m³] with the given `context` of the
4141
owning MultibodyPlant and a position in world, `p_WQ`. */
@@ -44,15 +44,15 @@ class ForceDensityField {
4444
return DoEvaluateAt(context, p_WQ);
4545
}
4646

47-
/** Returns an identical copy of `this` ForceDensityField. */
48-
std::unique_ptr<ForceDensityField<T>> Clone() const { return DoClone(); }
47+
/** Returns an identical copy of `this` ForceDensityFieldBase. */
48+
std::unique_ptr<ForceDensityFieldBase<T>> Clone() const { return DoClone(); }
4949

50-
/* (Advanced) Returns the force density type of `this` %ForceDensityFieldImpl.
50+
/* (Advanced) Returns the force density type of `this` %ForceDensityField.
5151
*/
5252
ForceDensityType density_type() const { return density_type_; }
5353

5454
protected:
55-
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(ForceDensityField);
55+
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(ForceDensityFieldBase);
5656

5757
/** Derived classes must override this function to provide a threadsafe
5858
implemention to the NVI EvaluateAt(). */
@@ -61,15 +61,15 @@ class ForceDensityField {
6161

6262
/** Derived classes must override this function to implement the NVI
6363
Clone(). */
64-
virtual std::unique_ptr<ForceDensityField<T>> DoClone() const = 0;
64+
virtual std::unique_ptr<ForceDensityFieldBase<T>> DoClone() const = 0;
6565

6666
private:
67-
friend class ForceDensityFieldImpl<T>;
67+
friend class ForceDensityField<T>;
6868

69-
/* Private constructor exposed only to ForceDensityFieldImpl. This prevents
69+
/* Private constructor exposed only to ForceDensityField. This prevents
7070
users from creating concrete force densities that directly inherit from
71-
ForceDensityField. */
72-
explicit ForceDensityField(ForceDensityType density_type)
71+
ForceDensityFieldBase. */
72+
explicit ForceDensityFieldBase(ForceDensityType density_type)
7373
: density_type_(density_type) {}
7474

7575
ForceDensityType density_type_;
@@ -79,4 +79,4 @@ class ForceDensityField {
7979
} // namespace drake
8080

8181
DRAKE_DECLARE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS(
82-
class ::drake::multibody::ForceDensityField);
82+
class ::drake::multibody::ForceDensityFieldBase);

multibody/fem/test/dummy_element.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -151,7 +151,7 @@ class DummyElement final : public FemElement<DummyElement<is_linear>> {
151151
EigenPtr<Vector<T, kNumDofs>> result) const {
152152
for (int i = 0; i < this->num_nodes; ++i) {
153153
const auto node_q = data.element_q.template segment<3>(3 * i);
154-
for (const multibody::ForceDensityField<T>* force_density :
154+
for (const multibody::ForceDensityFieldBase<T>* force_density :
155155
plant_data.force_density_fields) {
156156
result->template segment<3>(3 * i) +=
157157
scale * force_density->EvaluateAt(plant_data.plant_context, node_q);

multibody/fem/test/fem_element_test.cc

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -4,7 +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"
7+
#include "drake/multibody/tree/force_density_field.h"
88

99
namespace drake {
1010
namespace multibody {

multibody/fem/test/fem_model_test.cc

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -11,7 +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"
14+
#include "drake/multibody/tree/force_density_field.h"
1515

1616
namespace drake {
1717
namespace multibody {
@@ -119,8 +119,7 @@ GTEST_TEST(FemModelTest, CalcResidualWithContextDependentExternalForce) {
119119
unique_ptr<FemState<double>> fem_state = model.MakeFemState();
120120

121121
/* A force field where the magnitude of the force density depends on time. */
122-
class TimeScaledForceDensityField final
123-
: public ForceDensityFieldImpl<double> {
122+
class TimeScaledForceDensityField final : public ForceDensityField<double> {
124123
public:
125124
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(TimeScaledForceDensityField);
126125

@@ -136,7 +135,7 @@ GTEST_TEST(FemModelTest, CalcResidualWithContextDependentExternalForce) {
136135
return context.get_time() * unit_vector_;
137136
};
138137

139-
std::unique_ptr<ForceDensityField<double>> DoClone() const final {
138+
std::unique_ptr<ForceDensityFieldBase<double>> DoClone() const final {
140139
return std::make_unique<TimeScaledForceDensityField>(*this);
141140
}
142141

multibody/fem/test/force_density_field_test.cc renamed to multibody/fem/test/force_density_field_base_test.cc

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,9 @@
1-
#include "drake/multibody/fem/force_density_field.h"
1+
#include "drake/multibody/fem/force_density_field_base.h"
22

33
#include <gtest/gtest.h>
44

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

88
namespace drake {
99
namespace multibody {
@@ -14,7 +14,7 @@ using drake::systems::BasicVector;
1414
using Eigen::Vector3d;
1515

1616
/* A concrete force density field for testing. */
17-
class ConstantForceDensityField final : public ForceDensityFieldImpl<double> {
17+
class ConstantForceDensityField final : public ForceDensityField<double> {
1818
public:
1919
/* Constructs an force density field that has the functional form given by
2020
input `field` which is then scaled by a scalar value via input port. */
@@ -36,7 +36,7 @@ class ConstantForceDensityField final : public ForceDensityFieldImpl<double> {
3636
return get_input_port().Eval(context)(0) * field_(p_WQ);
3737
};
3838

39-
std::unique_ptr<ForceDensityField<double>> DoClone() const final {
39+
std::unique_ptr<ForceDensityFieldBase<double>> DoClone() const final {
4040
return std::unique_ptr<ConstantForceDensityField>(
4141
new ConstantForceDensityField(*this));
4242
}

multibody/fem/test/volumetric_element_test.cc

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -11,7 +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"
14+
#include "drake/multibody/tree/force_density_field.h"
1515

1616
namespace drake {
1717
namespace multibody {
@@ -420,7 +420,7 @@ TEST_F(VolumetricElementTest, PerCurrentVolumeExternalForce) {
420420

421421
const Vector3<AD> force_per_current_volume(4, 5, 6);
422422
/* A constant per current volume force density field. */
423-
class ConstantForceDensityField final : public ForceDensityFieldImpl<AD> {
423+
class ConstantForceDensityField final : public ForceDensityField<AD> {
424424
public:
425425
explicit ConstantForceDensityField(const Vector3<AD>& f) : f_(f) {}
426426

@@ -430,7 +430,7 @@ TEST_F(VolumetricElementTest, PerCurrentVolumeExternalForce) {
430430
return f_;
431431
};
432432

433-
std::unique_ptr<ForceDensityField<AD>> DoClone() const final {
433+
std::unique_ptr<ForceDensityFieldBase<AD>> DoClone() const final {
434434
return std::make_unique<ConstantForceDensityField>(*this);
435435
}
436436

multibody/fem/volumetric_element.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -441,7 +441,7 @@ class VolumetricElement
441441
const Matrix3<T>& deformation_gradient =
442442
data.deformation_gradient_data[q].deformation_gradient();
443443
Vector3<T> scaled_force = Vector3<T>::Zero();
444-
for (const multibody::ForceDensityField<T>* force_density :
444+
for (const multibody::ForceDensityFieldBase<T>* force_density :
445445
plant_data.force_density_fields) {
446446
DRAKE_ASSERT(force_density != nullptr);
447447
const T change_of_volume =

multibody/plant/BUILD.bazel

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -91,7 +91,7 @@ drake_cc_library(
9191
"discrete_step_memory.cc",
9292
"discrete_update_manager.cc",
9393
"dummy_physical_model.cc",
94-
"force_density_field_impl_declare_system_resources.cc",
94+
"force_density_field_declare_system_resources.cc",
9595
"geometry_contact_data.cc",
9696
"make_discrete_update_manager.cc",
9797
"multibody_element_getter.cc",

multibody/plant/deformable_model.cc

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -14,7 +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"
17+
#include "drake/multibody/tree/force_density_field.h"
1818

1919
namespace drake {
2020
namespace multibody {
@@ -264,14 +264,14 @@ Matrix3X<T> DeformableModel<T>::GetPositions(const systems::Context<T>& context,
264264

265265
template <typename T>
266266
void DeformableModel<T>::AddExternalForce(
267-
std::unique_ptr<ForceDensityField<T>> force_density) {
267+
std::unique_ptr<ForceDensityFieldBase<T>> force_density) {
268268
this->ThrowIfSystemResourcesDeclared(__func__);
269269
ThrowIfNotDouble(__func__);
270270
force_densities_.push_back(std::move(force_density));
271271
}
272272

273273
template <typename T>
274-
const std::vector<const ForceDensityField<T>*>&
274+
const std::vector<const ForceDensityFieldBase<T>*>&
275275
DeformableModel<T>::GetExternalForces(DeformableBodyId id) const {
276276
this->ThrowIfSystemResourcesNotDeclared(__func__);
277277
ThrowUnlessRegistered(__func__, id);
@@ -582,11 +582,11 @@ void DeformableModel<T>::DoDeclareSystemResources() {
582582

583583
/* Declare cache entries and input ports for force density fields that need
584584
them. */
585-
for (std::unique_ptr<ForceDensityField<T>>& force_density :
585+
for (std::unique_ptr<ForceDensityFieldBase<T>>& force_density :
586586
force_densities_) {
587587
/* 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())
588+
field is derived from ForceDensityField. */
589+
static_cast<ForceDensityField<T>*>(force_density.get())
590590
->DeclareSystemResources(this->mutable_plant());
591591
}
592592
}

0 commit comments

Comments
 (0)