Skip to content

Commit

Permalink
[fem] Move ConstitutiveModel out of dev (#15603)
Browse files Browse the repository at this point in the history
* [fem] Move ConstitutiveModel out of dev
  • Loading branch information
xuchenhan-tri authored Aug 16, 2021
1 parent f6fa762 commit 5c7f033
Show file tree
Hide file tree
Showing 11 changed files with 116 additions and 40 deletions.
21 changes: 21 additions & 0 deletions multibody/fem/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@ drake_cc_package_library(
name = "fem",
visibility = ["//multibody/fixed_fem:__subpackages__"],
deps = [
":constitutive_model",
":deformation_gradient_data",
":isoparametric_element",
":linear_constitutive_model_data",
Expand All @@ -24,6 +25,17 @@ drake_cc_package_library(
],
)

drake_cc_library(
name = "constitutive_model",
hdrs = [
"constitutive_model.h",
],
deps = [
"//common:essential",
"//common:nice_type_name",
],
)

drake_cc_library(
name = "deformation_gradient_data",
srcs = [
Expand Down Expand Up @@ -107,6 +119,15 @@ drake_cc_library(
],
)

drake_cc_googletest(
name = "constitutive_model_test",
deps = [
":constitutive_model",
"//common/test_utilities:expect_throws_message",
"//multibody/fem:deformation_gradient_data",
],
)

drake_cc_googletest(
name = "deformation_gradient_data_test",
deps = [
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@ namespace multibody {
namespace fem {
namespace internal {

/* A constitutive model relates the strain to the stress of the material and
/* A constitutive model relates the strain to the stress of a material and
governs the material response under deformation. This constitutive relationship
is defined through a hyperelastic potential energy, which increases with
non-rigid deformation from the initial state.
Expand All @@ -27,7 +27,7 @@ namespace internal {
@tparam DerivedConstitutiveModel The concrete constitutive model that inherits
from ConstitutiveModel through CRTP.
@tparam DerivedTraits The traits class associated with the
DerivedConstitutiveModel. It muist provide the type definitions `Scalar`
DerivedConstitutiveModel. It must provide the type definitions `Scalar`
(the scalar type of the constitutive model) and `Data` (the derived
DeformationGradientData that works in tandem with the derived constitutive
model). */
Expand All @@ -44,11 +44,17 @@ class ConstitutiveModel {

/* "Calc" Methods
Methods for calculating the energy density and its derivatives given the
data required for these calculations. The constitutive model expects
that the input data are up-to-date, but cannot verify this prerequisite. It
is the responsibility of the caller to provide up-to-date input data. */

/* Calculates the energy density in reference configuration, in unit J/m³,
deformation gradient and other deformation gradient dependent data required
for these calculations.
Note that these Calc methods take output parameters
instead of returning the output value with the following considerations in
mind:
1. A typical usage of the return value is not used for initialization (See
ElasticityElement::DoComputeData()) and thus RVO can't be used.
2. The output value is of type `std::array` for which there is no helpful
move semantic.
Calculates the energy density in reference configuration in unit of J/m³,
given the deformation gradient related quantities contained in `data`.
@pre `Psi != nullptr`. */
void CalcElasticEnergyDensity(const Data& data,
Expand All @@ -57,7 +63,7 @@ class ConstitutiveModel {
derived().CalcElasticEnergyDensityImpl(data, Psi);
}

/* Calculates the First Piola stress, in unit Pa, given the deformation
/* Calculates the First Piola stress in unit of Pa, given the deformation
gradient related quantities contained in `data`.
@pre `P != nullptr`. */
void CalcFirstPiolaStress(const Data& data,
Expand Down
68 changes: 68 additions & 0 deletions multibody/fem/test/constitutive_model_test.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,68 @@
#include "drake/multibody/fem/constitutive_model.h"

#include <gtest/gtest.h>

#include "drake/common/test_utilities/expect_throws_message.h"
#include "drake/multibody/fem/deformation_gradient_data.h"

namespace drake {
namespace multibody {
namespace fem {
namespace internal {

using Eigen::Matrix3d;
constexpr int kNumLocations = 2;

/* Minimal required data type to be used in the derived constitutive model
traits. */
template <typename T, int num_locations_at_compile_time>
struct DummyData : public DeformationGradientData<
DummyData<T, num_locations_at_compile_time>> {};

struct InvalidModelTraits {
using Scalar = double;
using Data = DummyData<double, kNumLocations>;
};

/* ConstitutiveModel requires derived classes to shadow the
CalcElasticEnergyDensityImpl(), CalcFirstPiolaStressImpl(), and
CalcFirstPiolaStressDerivativeImpl() methods. Failure to do so should throw a
helpful exception. This implementation doesn't shadow the messages and
confirms the exceptions. */
class InvalidModel
: public ConstitutiveModel<InvalidModel, InvalidModelTraits> {};

namespace {
GTEST_TEST(ConstitutiveModelTest, InvalidModel) {
const InvalidModel model;
const DummyData<double, kNumLocations> data;
std::array<double, DummyData<double, kNumLocations>::num_locations>
energy_density;
DRAKE_EXPECT_THROWS_MESSAGE(
model.CalcElasticEnergyDensity(data, &energy_density), std::exception,
fmt::format("The derived class {} must provide a shadow definition of "
"CalcElasticEnergyDensityImpl.. to be correct.",
NiceTypeName::Get(model)));

std::array<Matrix3d, DummyData<double, kNumLocations>::num_locations> P;
DRAKE_EXPECT_THROWS_MESSAGE(
model.CalcFirstPiolaStress(data, &P), std::exception,
fmt::format("The derived class {} must provide a shadow definition of "
"CalcFirstPiolaStressImpl.. to be correct.",
NiceTypeName::Get(model)));

std::array<Eigen::Matrix<double, 9, 9>,
DummyData<double, kNumLocations>::num_locations>
dPdF;
DRAKE_EXPECT_THROWS_MESSAGE(
model.CalcFirstPiolaStressDerivative(data, &dPdF), std::exception,
fmt::format("The derived class {} must provide a shadow definition of "
"CalcFirstPiolaStressDerivativeImpl.. to be correct.",
NiceTypeName::Get(model)));
}

} // namespace
} // namespace internal
} // namespace fem
} // namespace multibody
} // namespace drake
29 changes: 4 additions & 25 deletions multibody/fixed_fem/dev/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -34,18 +34,6 @@ drake_cc_library(
],
)

drake_cc_library(
name = "constitutive_model",
hdrs = [
"constitutive_model.h",
],
deps = [
":fem_indexes",
"//common:essential",
"//multibody/fem:deformation_gradient_data",
],
)

drake_cc_library(
name = "constitutive_model_utilities",
hdrs = [
Expand All @@ -62,12 +50,12 @@ drake_cc_library(
"corotated_model.h",
],
deps = [
":constitutive_model",
":constitutive_model_utilities",
":corotated_model_data",
":matrix_utilities",
"//common:autodiff",
"//common:essential",
"//multibody/fem:constitutive_model",
],
)

Expand Down Expand Up @@ -267,10 +255,10 @@ drake_cc_library(
"elasticity_element.h",
],
deps = [
":constitutive_model",
":fem_element",
"//common:essential",
"//common:unused",
"//multibody/fem:constitutive_model",
"//multibody/fem:isoparametric_element",
"//multibody/fem:quadrature",
],
Expand Down Expand Up @@ -413,10 +401,10 @@ drake_cc_library(
"linear_constitutive_model.h",
],
deps = [
":constitutive_model",
":constitutive_model_utilities",
"//common:autodiff",
"//common:essential",
"//multibody/fem:constitutive_model",
"//multibody/fem:linear_constitutive_model_data",
],
)
Expand Down Expand Up @@ -599,14 +587,14 @@ drake_cc_library(
srcs = ["test/constitutive_model_test_utilities.cc"],
hdrs = ["test/constitutive_model_test_utilities.h"],
deps = [
":constitutive_model",
":corotated_model",
":linear_constitutive_model",
":test_utilities",
"//common:autodiff",
"//common/test_utilities:eigen_matrix_compare",
"//common/test_utilities:expect_throws_message",
"//math:gradient",
"//multibody/fem:constitutive_model",
],
)

Expand Down Expand Up @@ -771,15 +759,6 @@ drake_cc_googletest(
],
)

drake_cc_googletest(
name = "hyperelastic_constitutive_model_test",
deps = [
":constitutive_model",
"//common/test_utilities:expect_throws_message",
"//multibody/fem:deformation_gradient_data",
],
)

drake_cc_googletest(
name = "linear_constitutive_model_test",
deps = [
Expand Down
2 changes: 1 addition & 1 deletion multibody/fixed_fem/dev/corotated_model.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

#include <array>

#include "drake/multibody/fixed_fem/dev/constitutive_model.h"
#include "drake/multibody/fem/constitutive_model.h"
#include "drake/multibody/fixed_fem/dev/corotated_model_data.h"

namespace drake {
Expand Down
1 change: 0 additions & 1 deletion multibody/fixed_fem/dev/corotated_model_data.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,6 @@

#include "drake/common/eigen_types.h"
#include "drake/multibody/fem/deformation_gradient_data.h"
#include "drake/multibody/fixed_fem/dev/fem_indexes.h"
#include "drake/multibody/fixed_fem/dev/matrix_utilities.h"

namespace drake {
Expand Down
2 changes: 1 addition & 1 deletion multibody/fixed_fem/dev/elasticity_element.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,9 +5,9 @@

#include "drake/common/eigen_types.h"
#include "drake/common/unused.h"
#include "drake/multibody/fem/constitutive_model.h"
#include "drake/multibody/fem/isoparametric_element.h"
#include "drake/multibody/fem/quadrature.h"
#include "drake/multibody/fixed_fem/dev/constitutive_model.h"
#include "drake/multibody/fixed_fem/dev/fem_element.h"
#include "drake/multibody/fixed_fem/dev/fem_state.h"

Expand Down
2 changes: 1 addition & 1 deletion multibody/fixed_fem/dev/linear_constitutive_model.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,8 @@

#include <array>

#include "drake/multibody/fem/constitutive_model.h"
#include "drake/multibody/fem/linear_constitutive_model_data.h"
#include "drake/multibody/fixed_fem/dev/constitutive_model.h"

namespace drake {
namespace multibody {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
#include "drake/common/test_utilities/eigen_matrix_compare.h"
#include "drake/common/test_utilities/expect_throws_message.h"
#include "drake/math/autodiff_gradient.h"
#include "drake/multibody/fixed_fem/dev/constitutive_model.h"
#include "drake/multibody/fem/constitutive_model.h"
#include "drake/multibody/fixed_fem/dev/corotated_model.h"
#include "drake/multibody/fixed_fem/dev/linear_constitutive_model.h"
#include "drake/multibody/fixed_fem/dev/test/test_utilities.h"
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,9 @@
#pragma once

/** @file
This file provides utilities that facilitates testing the subclasses of
ConstitutiveModel instead of the ConstitutiveModel class itself. */

#include <array>

#include "drake/common/autodiff.h"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,8 @@

#include "drake/common/test_utilities/expect_throws_message.h"
#include "drake/multibody/fem/deformation_gradient_data.h"
#include "drake/multibody/fixed_fem/dev/constitutive_model.h"
#include "drake/multibody/fem/constitutive_model.h"

// TODO(xuchenhan-tri): Rename this file to constitutive_model_test.cc.
namespace drake {
namespace multibody {
namespace fem {
Expand Down

0 comments on commit 5c7f033

Please sign in to comment.