Skip to content

Commit

Permalink
[fem] Move quadrature classes out of dev (#15334)
Browse files Browse the repository at this point in the history
* [fem] Move quadrature classes out of dev

Along with the file moving:

* Move the quadrature classes to internal:: namespace.
* Change template integral constant names to be style-guide compliant.
* Clean up unit test.
  • Loading branch information
xuchenhan-tri authored Jul 13, 2021
1 parent a12ac50 commit 3783258
Show file tree
Hide file tree
Showing 18 changed files with 453 additions and 415 deletions.
57 changes: 57 additions & 0 deletions multibody/fem/BUILD.bazel
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
#- * - python - * -
load("//tools/lint:lint.bzl", "add_lint_tests")
load(
"//tools/skylark:drake_cc.bzl",
"drake_cc_googletest",
"drake_cc_library",
"drake_cc_package_library",
)

package(
default_visibility = ["//multibody/fixed_fem:__subpackages__"],
)

drake_cc_package_library(
name = "fem",
visibility = ["//multibody/fixed_fem:__subpackages__"],
deps = [
":quadrature",
":simplex_gaussian_quadrature",
],
)

drake_cc_library(
name = "quadrature",
srcs = [
"quadrature.cc",
],
hdrs = [
"quadrature.h",
],
deps = [
"//common:default_scalars",
"//common:essential",
],
)

drake_cc_library(
name = "simplex_gaussian_quadrature",
srcs = [
"simplex_gaussian_quadrature.cc",
],
hdrs = [
"simplex_gaussian_quadrature.h",
],
deps = [
":quadrature",
],
)

drake_cc_googletest(
name = "simplex_gaussian_quadrature_test",
deps = [
":simplex_gaussian_quadrature",
],
)

add_lint_tests()
1 change: 1 addition & 0 deletions multibody/fem/quadrature.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1 @@
#include "drake/multibody/fem/quadrature.h"
84 changes: 84 additions & 0 deletions multibody/fem/quadrature.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,84 @@
#pragma once

#include <array>
#include <utility>

#include "drake/common/eigen_types.h"

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

/* A base class for quadratures that facilitates numerical integrations in FEM.
This class provides the common methods and the data for all the quadrature
rules with no heap allocation or virtual methods. The specification of
particular quadrature rules will be provided in the derived classes.
@tparam natural_dimension_at_compile_time Dimension of the domain of
integration.
@tparam num_locations_at_compile_time Number of quadrature locations. */
template <int natural_dimension_at_compile_time,
int num_quadrature_points_at_compile_time>
class Quadrature {
public:
/* The dimension of the parent domain. */
static constexpr int natural_dimension = natural_dimension_at_compile_time;

/* The number of quadrature locations. */
static constexpr int num_quadrature_points =
num_quadrature_points_at_compile_time;

static_assert(1 <= natural_dimension && natural_dimension <= 3,
"Only 1, 2 and 3 dimensional shapes are supported.");
static_assert(1 <= num_quadrature_points,
"There has to be at least one quadrature point.");

using VectorD = Eigen::Matrix<double, natural_dimension, 1>;
using LocationsType = std::array<VectorD, num_quadrature_points>;
using WeightsType = std::array<double, num_quadrature_points>;

/* The position in parent domain coordinates of all quadrature points. */
const LocationsType& get_points() const { return points_; }

/* The weight of all quadrature points. */
const WeightsType& get_weights() const { return weights_; }

/* The position in parent domain coordinates of the q-th quadrature point. */
const VectorD& get_point(int q) const {
DRAKE_ASSERT(0 <= q && q < num_quadrature_points);
return points_[q];
}

/* The weight of the q-th quadrature point. */
double get_weight(int q) const {
DRAKE_ASSERT(0 <= q && q < num_quadrature_points);
return weights_[q];
}

protected:
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(Quadrature);

/* Constructs a Quadrature object given the quadrature locations and the
weights of the quadrature points. */
explicit Quadrature(
std::pair<LocationsType, WeightsType>&& points_and_weights)
: points_(std::move(points_and_weights.first)),
weights_(std::move(points_and_weights.second)) {}

private:
LocationsType points_;
WeightsType weights_;
};

template <class ObjectType>
struct is_quadrature {
static constexpr bool value =
std::is_base_of_v<Quadrature<ObjectType::natural_dimension,
ObjectType::num_quadrature_points>,
ObjectType>;
};

} // namespace internal
} // namespace fem
} // namespace multibody
} // namespace drake
129 changes: 129 additions & 0 deletions multibody/fem/simplex_gaussian_quadrature.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,129 @@
#include "drake/multibody/fem/simplex_gaussian_quadrature.h"

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

using std::make_pair;
using std::move;

/* Linear triangle quadrature. */
template <>
std::pair<SimplexGaussianQuadrature<2, 1>::LocationsType,
SimplexGaussianQuadrature<2, 1>::WeightsType>
SimplexGaussianQuadrature<2, 1>::ComputePointsAndWeights() {
/* quadrature point location, weight/area
(1/3, 1/3) 1.0 */
LocationsType points = {{{1.0 / 3.0, 1.0 / 3.0}}};
/* For a unit triangle, area = 0.5. */
WeightsType weights = {{0.5}};
return make_pair(move(points), move(weights));
}

/* Quadratic triangle quadrature. */
template <>
std::pair<SimplexGaussianQuadrature<2, 2>::LocationsType,
SimplexGaussianQuadrature<2, 2>::WeightsType>
SimplexGaussianQuadrature<2, 2>::ComputePointsAndWeights() {
/* quadrature point location, weight/area
(1/6, 1/6) 1/3
(2/3, 1/6) 1/3
(1/6, 2/3) 1/3
Note: Here we choose r=1/2 in section 3 of [Hammer, 1956]. They also
mentioned the other choice with r=-1/2. We do not use r=-1/2 as it
lies out side of the element. */
LocationsType points;
points[0] = {1.0 / 6.0, 1.0 / 6.0};
points[1] = {2.0 / 3.0, 1.0 / 6.0};
points[2] = {1.0 / 6.0, 2.0 / 3.0};
/* For a unit triangle, area = 0.5. */
WeightsType weights = {{1.0 / 6.0, 1.0 / 6.0, 1.0 / 6.0}};
return make_pair(move(points), move(weights));
}

/* Cubic triangle quadrature. */
template <>
std::pair<SimplexGaussianQuadrature<2, 3>::LocationsType,
SimplexGaussianQuadrature<2, 3>::WeightsType>
SimplexGaussianQuadrature<2, 3>::ComputePointsAndWeights() {
/* quadrature point location, weight/area
(1/3, 1/3) -9/16
(3/5, 1/5) 25/48
(1/5, 3/5) 25/48
(1/5, 1/5) 25/48 */
LocationsType points;
points[0] = {1.0 / 3.0, 1.0 / 3.0};
points[1] = {0.6, 0.2};
points[2] = {0.2, 0.6};
points[3] = {0.2, 0.2};
/* For a unit triangle, area = 0.5. */
WeightsType weights = {{-9.0 / 32.0, 25.0 / 96.0, 25.0 / 96.0, 25.0 / 96.0}};
return make_pair(move(points), move(weights));
}

/* Linear tetrahedral quadrature. */
template <>
std::pair<SimplexGaussianQuadrature<3, 1>::LocationsType,
SimplexGaussianQuadrature<3, 1>::WeightsType>
SimplexGaussianQuadrature<3, 1>::ComputePointsAndWeights() {
/* quadrature point location, weight/area
(1/4, 1/4, 1/4) 1.0 */
LocationsType points = {{{0.25, 0.25, 0.25}}};
/* For a unit tetrahedron, area = 1/6. */
WeightsType weights = {{1.0 / 6.0}};
return make_pair(move(points), move(weights));
}

/* Quadratic tetrahedral quadrature. */
template <>
std::pair<SimplexGaussianQuadrature<3, 2>::LocationsType,
SimplexGaussianQuadrature<3, 2>::WeightsType>
SimplexGaussianQuadrature<3, 2>::ComputePointsAndWeights() {
/* quadrature point location, weight/area
(a, b, b) 1/4
(b, a, b) 1/4
(b, b, a) 1/4
(b, b, b) 1/4
where a = (1+3*sqrt(1/5))/4, b = (1-1/sqrt(1/5))/4. */
LocationsType points;
double a = (1.0 + 3.0 * sqrt(0.2)) / 4.0;
double b = (1.0 - sqrt(0.2)) / 4.0;
points[0] = {a, b, b};
points[1] = {b, a, b};
points[2] = {b, b, a};
points[3] = {b, b, b};
/* For a unit tetrahedron, area = 1/6. */
WeightsType weights = {{1.0 / 24.0, 1.0 / 24.0, 1.0 / 24.0, 1.0 / 24.0}};
return make_pair(move(points), move(weights));
}

/* Cubic tetrahedral quadrature. */
template <>
std::pair<SimplexGaussianQuadrature<3, 3>::LocationsType,
SimplexGaussianQuadrature<3, 3>::WeightsType>
SimplexGaussianQuadrature<3, 3>::ComputePointsAndWeights() {
/* quadrature point location, weight/area
(1/4, 1/4, 1/4) -4/5
(a, b, b) 9/20
(b, a, b) 9/20
(b, b, a) 9/20
(b, b, b) 9/20
where a = 1/2, b = 1/6. */
LocationsType points;
double a = 0.5;
double b = 1.0 / 6.0;
points[0] = {0.25, 0.25, 0.25};
points[1] = {a, b, b};
points[2] = {b, a, b};
points[3] = {b, b, a};
points[4] = {b, b, b};
/* For a unit tetrahedron, area = 1/6. */
WeightsType weights = {
{-2.0 / 15.0, 3.0 / 40.0, 3.0 / 40.0, 3.0 / 40.0, 3.0 / 40.0}};
return make_pair(move(points), move(weights));
}
} // namespace internal
} // namespace fem
} // namespace multibody
} // namespace drake
70 changes: 70 additions & 0 deletions multibody/fem/simplex_gaussian_quadrature.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,70 @@
#pragma once

#include <utility>

#include "drake/common/eigen_types.h"
#include "drake/multibody/fem/quadrature.h"

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

/* Calculates the number of quadrature points used for simplices given the
natural dimension and the order of the quadrature rule as template
parameters. */
template <int natural_dimension, int order>
constexpr int num_simplex_quadrature_locations() {
static_assert(
1 <= order && order <= 3,
"Only linear, quadratic and cubic quadrature rules are supported.");
if constexpr (order == 1) {
return 1;
} else if constexpr (order == 2) {
return natural_dimension + 1;
} else if constexpr (order == 3) {
return natural_dimension + 2;
}
}

// TODO(xuchenhan-tri): Support natural_dimension = 1 if it turns out useful.
/* Calculates the Gaussian quadrature rule for 2D and 3D unit simplices
(triangles and tetrahedrons up to cubic order as described section 3 in
[Hammer, 1956] as well as section 9.10 of [Zienkiewics, 2005]. The 2D unit
triangle has vertices located at (0,0), (1,0) and (0,1). The 3D unit
tetrahedron has vertices located at (0,0,0), (1,0,0), (0,1,0) and (0,0,1).
@tparam order Order of the quadrature rule. Must be 1, 2, or 3.
The quadrature rule will be exact for polynomials of
degree less than or equal to `order`.
@tparam natural_dimension Dimension of the unit simplex. Must be 2 (triangles)
or 3 (tetrahedrons).
[Hammer, 1956] P.C. Hammer, O.P. Marlowe, and A.H. Stroud. Numerical
integration over simplexes and cones. Math. Tables Aids Comp. 10, 130-7, 1956.
[Zienkiewicz, 2005] Zienkiewicz, Olek C., Robert L. Taylor, and Jian Z. Zhu.
The finite element method: its basis and fundamentals. Elsevier, 2005. */
template <int natural_dimension, int order>
class SimplexGaussianQuadrature
: public Quadrature<natural_dimension, num_simplex_quadrature_locations<
natural_dimension, order>()> {
public:
using Base =
Quadrature<natural_dimension,
num_simplex_quadrature_locations<natural_dimension, order>()>;
using VectorD = typename Base::VectorD;
using LocationsType = typename Base::LocationsType;
using WeightsType = typename Base::WeightsType;

DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(SimplexGaussianQuadrature);

SimplexGaussianQuadrature() : Base(ComputePointsAndWeights()) {}

private:
/* Helper function to initialize quadrature locations and weights. */
static std::pair<LocationsType, WeightsType> ComputePointsAndWeights();
};

} // namespace internal
} // namespace fem
} // namespace multibody
} // namespace drake
Loading

0 comments on commit 3783258

Please sign in to comment.