Skip to content

Commit

Permalink
Remove usage of unintialized values. (RobotLocomotion#14313)
Browse files Browse the repository at this point in the history
* Remove usage of unintialized values.

Remove usage of uninitialized values in FemState and
LinearElasticityModelCacheTest.

- Initialize states in FemState's constructor.
- Initialize strains in DeformationGradient's constructor.

Fixes issue RobotLocomotion#14312.
  • Loading branch information
xuchenhan-tri authored Nov 10, 2020
1 parent 4fec6f9 commit 9ba321d
Show file tree
Hide file tree
Showing 7 changed files with 42 additions and 43 deletions.
3 changes: 0 additions & 3 deletions multibody/fem/dev/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -191,7 +191,6 @@ drake_cc_library(

drake_cc_googletest(
name = "fem_elasticity_test",
tags = ["manual"], # Currently fails valgrind.
deps = [
":fem_elasticity",
":fem_state",
Expand All @@ -206,7 +205,6 @@ drake_cc_googletest(

drake_cc_googletest(
name = "fem_state_test",
tags = ["manual"], # Currently fails valgrind.
deps = [
":element_cache",
":fem_state",
Expand All @@ -225,7 +223,6 @@ drake_cc_googletest(

drake_cc_googletest(
name = "linear_elasticity_model_cache_test",
tags = ["manual"], # Currently fails valgrind.
deps = [
":linear_elasticity_model_cache",
"//common/test_utilities:expect_throws_message",
Expand Down
2 changes: 1 addition & 1 deletion multibody/fem/dev/deformation_gradient_cache.h
Original file line number Diff line number Diff line change
Expand Up @@ -75,7 +75,7 @@ class DeformationGradientCache {
DeformationGradientCache(ElementIndex element_index, int num_quads)
: element_index_(element_index),
num_quads_(num_quads),
deformation_gradient_(num_quads) {
deformation_gradient_(num_quads, Matrix3<T>::Identity()) {
DRAKE_ASSERT(element_index.is_valid());
DRAKE_ASSERT(num_quads > 0);
}
Expand Down
24 changes: 13 additions & 11 deletions multibody/fem/dev/fem_state.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,11 +27,15 @@ class FemState {
another %FemState. */
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(FemState);

FemState() = default;

/** Constructs an %FemState with prescribed number of states. */
explicit FemState(int num_generalized_positions)
: qdot_(num_generalized_positions), q_(num_generalized_positions) {}
/** Constructs an %FemState with prescribed states.
@param[in] q The prescribed generalized positions.
@param[in] qdot The prescribed time derivatives of generalized positions.
@pre `q` and `qdot` must have the same size. */
FemState(const Eigen::Ref<const VectorX<T>>& q,
const Eigen::Ref<const VectorX<T>>& qdot)
: q_(q), qdot_(qdot) {
DRAKE_DEMAND(q.size() == qdot.size());
}

/** Takes ownership of the input `element_cache` and set it as the element
cache that `this` %FemState owns. This method is usually called right after
Expand All @@ -48,8 +52,8 @@ class FemState {
/** Creates a deep identical copy of `this` %FemState with all its states and
cache. Returns a unique pointer to the copy. */
std::unique_ptr<FemState<T>> Clone() const {
auto clone = std::make_unique<FemState<T>>(num_generalized_positions());
clone->SetFrom(*this);
auto clone = std::make_unique<FemState<T>>(q(), qdot());
clone->element_cache_ = element_cache_;
return clone;
}

Expand Down Expand Up @@ -86,13 +90,11 @@ class FemState {
@{ */
void set_qdot(const Eigen::Ref<const VectorX<T>>& value) {
DRAKE_ASSERT(value.size() == qdot_.size());
if (value == qdot_) return;
mutable_qdot() = value;
}

void set_q(const Eigen::Ref<const VectorX<T>>& value) {
DRAKE_ASSERT(value.size() == q_.size());
if (value == q_) return;
mutable_q() = value;
}
/** @} */
Expand Down Expand Up @@ -128,10 +130,10 @@ class FemState {
int num_generalized_positions() const { return q_.size(); }

private:
// Time derivatives of generalized node positions.
VectorX<T> qdot_;
// Generalized node positions.
VectorX<T> q_;
// Time derivatives of generalized node positions.
VectorX<T> qdot_;
// Owned element cache quantities.
std::vector<copyable_unique_ptr<ElementCache<T>>> element_cache_;
};
Expand Down
4 changes: 2 additions & 2 deletions multibody/fem/dev/linear_elasticity_model_cache.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,8 @@ class LinearElasticityModelCache : public DeformationGradientCache<T> {
@pre `num_quads` must be positive. */
LinearElasticityModelCache(ElementIndex element_index, int num_quads)
: DeformationGradientCache<T>(element_index, num_quads),
strain_(num_quads),
trace_strain_(num_quads) {}
strain_(num_quads, Matrix3<T>::Zero()),
trace_strain_(num_quads, 0) {}

/** Returns the infinitesimal strains evaluated at the quadrature locations
for the associated element. */
Expand Down
21 changes: 11 additions & 10 deletions multibody/fem/dev/test/fem_elasticity_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,10 @@ class ElasticityElementTest : public ::testing::Test {
using QuadratureType =
SimplexGaussianQuadrature<AutoDiffXd, kQuadratureOrder, kSpatialDim>;
using ShapeType = LinearSimplexElement<AutoDiffXd, kNaturalDim>;
void SetUp() override { SetupElement(); }
void SetUp() override {
SetupElement();
SetupState();
}

void SetupElement() {
std::vector<NodeIndex> node_indices = {NodeIndex(0), NodeIndex(1),
Expand All @@ -42,16 +45,15 @@ class ElasticityElementTest : public ::testing::Test {
}

void SetupState() {
state_.Resize(kDof);
state_.set_qdot(VectorX<AutoDiffXd>::Zero(kDof));
// Set arbitrary node positions and the gradient.
Eigen::Matrix<double, kDof, 1> x;
x << 0.18, 0.63, 0.54, 0.13, 0.92, 0.17, 0.03, 0.86, 0.85, 0.25, 0.53, 0.67;
const Eigen::Matrix<double, kDof, Eigen::Dynamic> gradient =
MatrixX<double>::Identity(kDof, kDof);
const VectorX<AutoDiffXd> x_autodiff =
math::initializeAutoDiffGivenGradientMatrix(x, gradient);
state_.set_q(x_autodiff);
const VectorX<AutoDiffXd> v = VectorX<AutoDiffXd>::Zero(kDof);
state_ = std::make_unique<FemState<AutoDiffXd>>(x_autodiff, v);
// Set up the element cache.
auto linear_elasticity_cache =
std::make_unique<LinearElasticityModelCache<AutoDiffXd>>(
Expand All @@ -61,7 +63,7 @@ class ElasticityElementTest : public ::testing::Test {
// ElementCache.
cache.emplace_back(std::make_unique<ElasticityElementCache<AutoDiffXd>>(
kDummyElementIndex, kNumQuads, std::move(linear_elasticity_cache)));
state_.ResetElementCache(std::move(cache));
state_->ResetElementCache(std::move(cache));
}

// Set an arbitrary reference positions such that the tetrahedron is not
Expand All @@ -76,14 +78,14 @@ class ElasticityElementTest : public ::testing::Test {
// Calculates the negative elastic force at state_.
VectorX<AutoDiffXd> CalcNegativeElasticForce() const {
VectorX<AutoDiffXd> neg_force(kDof);
fem_elasticity_->CalcNegativeElasticForce(state_, &neg_force);
fem_elasticity_->CalcNegativeElasticForce(*state_, &neg_force);
return neg_force;
}

std::unique_ptr<ElasticityElement<AutoDiffXd, ShapeType, QuadratureType>>
fem_elasticity_;
std::unique_ptr<LinearElasticityModel<AutoDiffXd>> linear_elasticity_;
FemState<AutoDiffXd> state_;
std::unique_ptr<FemState<AutoDiffXd>> state_;
};

namespace {
Expand All @@ -94,15 +96,14 @@ TEST_F(ElasticityElementTest, Basic) {
}

TEST_F(ElasticityElementTest, ElasticForceIsNegativeEnergyDerivative) {
SetupState();
AutoDiffXd energy = fem_elasticity_->CalcElasticEnergy(state_);
AutoDiffXd energy = fem_elasticity_->CalcElasticEnergy(*state_);
VectorX<AutoDiffXd> neg_force = CalcNegativeElasticForce();
EXPECT_TRUE(CompareMatrices(energy.derivatives(), neg_force,
std::numeric_limits<double>::epsilon()));
// TODO(xuchenhan-tri) Modify this to account for damping forces and inertia
// terms.
VectorX<AutoDiffXd> residual(kDof);
fem_elasticity_->CalcResidual(state_, &residual);
fem_elasticity_->CalcResidual(*state_, &residual);
EXPECT_TRUE(CompareMatrices(residual, neg_force));
}
// TODO(xuchenhan-tri): Add TEST_F as needed for damping and inertia terms
Expand Down
18 changes: 4 additions & 14 deletions multibody/fem/dev/test/fem_state_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -29,24 +29,15 @@ class MyElementCache final : public ElementCache<double> {
class FemStateTest : public ::testing::Test {
protected:
void SetUp() {
state_ = std::make_unique<FemState<double>>(kDof);
state_ = std::make_unique<FemState<double>>(q(), qdot());
// Create a couple of cache entries.
state_->ResetElementCache(MakeElementCache());
// Set default states.
SetStates();
}

// Default values for the first kDof state entries.
VectorX<double> qdot() const { return Vector3<double>(0.3, 0.4, 0.5); }
VectorX<double> q() const { return Vector3<double>(0.7, 0.8, 0.9); }

// Set the states to default values.
void SetStates() {
// Set all states to their default values.
state_->set_qdot(qdot());
state_->set_q(q());
}

std::vector<std::unique_ptr<ElementCache<double>>> MakeElementCache() const {
std::vector<std::unique_ptr<ElementCache<double>>> cache;
std::vector<int> data = {3, 5};
Expand All @@ -62,15 +53,13 @@ class FemStateTest : public ::testing::Test {
};

// Verify setters and getters are working properly.
TEST_F(FemStateTest, SetAndGet) {
SetStates();
TEST_F(FemStateTest, GetStates) {
EXPECT_EQ(state_->qdot(), qdot());
EXPECT_EQ(state_->q(), q());
}

// Verify resizing does not thrash existing values.
TEST_F(FemStateTest, ConservativeResize) {
SetStates();
state_->Resize(2 * kDof);
// The first kDof entres should remain unchanged.
EXPECT_EQ(state_->qdot().head(kDof), qdot());
Expand All @@ -93,7 +82,8 @@ TEST_F(FemStateTest, Clone) {
}

TEST_F(FemStateTest, SetFrom) {
FemState<double> dest;
// Set up an arbitrary state.
FemState<double> dest(VectorX<double>::Zero(1), VectorX<double>::Zero(1));
dest.SetFrom(*state_);
EXPECT_EQ(dest.qdot(), qdot());
EXPECT_EQ(dest.q(), q());
Expand Down
13 changes: 11 additions & 2 deletions multibody/fem/dev/test/linear_elasticity_model_cache_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -11,8 +11,18 @@ constexpr int kNumQuads = 1;

class LinearElasticityCacheTest : public ::testing::Test {
protected:
void SetUp() {
linear_elasticity_cache_.UpdateCache({MakeDeformationGradient()});
}
LinearElasticityModelCache<double> linear_elasticity_cache_{kElementIndex,
kNumQuads};

// Make an arbitrary deformation gradient.
Matrix3<double> MakeDeformationGradient() {
Matrix3<double> F;
F << 1.2, 2.3, 3.4, 4.5, 5.6, 6.7, 7.8, 8.9, 9.0;
return F;
}
};

TEST_F(LinearElasticityCacheTest, LinearElasticityCacheInitialization) {
Expand All @@ -24,8 +34,7 @@ TEST_F(LinearElasticityCacheTest, LinearElasticityCacheInitialization) {
}

TEST_F(LinearElasticityCacheTest, UpdateCache) {
const Matrix3<double> F = Matrix3<double>::Random();
linear_elasticity_cache_.UpdateCache({F});
const Matrix3<double> F = MakeDeformationGradient();
const Matrix3<double> strain =
0.5 * (F + F.transpose()) - Matrix3<double>::Identity();
const double trace_strain = strain.trace();
Expand Down

0 comments on commit 9ba321d

Please sign in to comment.