-
Notifications
You must be signed in to change notification settings - Fork 1.3k
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
1 parent
2cc1175
commit fad0338
Showing
18 changed files
with
271 additions
and
92 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,31 @@ | ||
#include "drake/math/fourth_order_tensor.h" | ||
|
||
#include "drake/common/default_scalars.h" | ||
|
||
namespace drake { | ||
namespace math { | ||
|
||
template <typename T> | ||
FourthOrderTensor<T>::FourthOrderTensor(const MatrixType& data) : data_(data) {} | ||
|
||
template <typename T> | ||
FourthOrderTensor<T>::FourthOrderTensor() = default; | ||
|
||
template <typename T> | ||
void FourthOrderTensor<T>::ContractWithVectors( | ||
const Eigen::Ref<const Vector3<T>>& u, | ||
const Eigen::Ref<const Vector3<T>>& v, EigenPtr<Matrix3<T>> B) const { | ||
B->setZero(); | ||
for (int l = 0; l < 3; ++l) { | ||
for (int j = 0; j < 3; ++j) { | ||
*B += data_.template block<3, 3>(3 * j, 3 * l) * u(j) * v(l); | ||
} | ||
} | ||
} | ||
|
||
} // namespace math | ||
} // namespace drake | ||
|
||
DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_NONSYMBOLIC_SCALARS( | ||
class ::drake::math::FourthOrderTensor); | ||
template class drake::math::FourthOrderTensor<float>; |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,106 @@ | ||
#pragma once | ||
|
||
#include "drake/common/drake_throw.h" | ||
#include "drake/common/eigen_types.h" | ||
|
||
namespace drake { | ||
namespace math { | ||
|
||
/** This class provides functionalities related to 4th order tensors of | ||
dimension 3*3*3*3. The tensor is represented using a a 9*9 matrix that is | ||
organized as following | ||
l = 1 l = 2 l = 3 | ||
------------------------------------- | ||
| | | | | ||
j = 1 | Aᵢ₁ₖ₁ | Aᵢ₁ₖ₂ | Aᵢ₁ₖ₃ | | ||
| | | | | ||
------------------------------------- | ||
| | | | | ||
j = 2 | Aᵢ₂ₖ₁ | Aᵢ₂ₖ₂ | Aᵢ₂ₖ₃ | | ||
| | | | | ||
------------------------------------- | ||
| | | | | ||
j = 3 | Aᵢ₃ₖ₁ | Aᵢ₃ₖ₂ | Aᵢ₃ₖ₃ | | ||
| | | | | ||
------------------------------------- | ||
Namely the ik-th entry in the jl-th block corresponds to the value Aᵢⱼₖₗ. | ||
@tparam float, double, AutoDiffXd. | ||
@experimental */ | ||
template <typename T> | ||
class FourthOrderTensor { | ||
public: | ||
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(FourthOrderTensor) | ||
using MatrixType = Eigen::Matrix<T, 9, 9>; | ||
|
||
/** Constructs a 4th-order tensor represented by the given matrix using the | ||
convention layed out in the class documentation. */ | ||
explicit FourthOrderTensor(const MatrixType& data); | ||
|
||
/** Constructs a zero 4th-order tensor. */ | ||
FourthOrderTensor(); | ||
|
||
/** Performs contraction between this 4th order tensor A and two vectors u and | ||
v and outputs 2nd order tensor B. In Einstein notation, the contraction being | ||
done is Bᵢₖ = uⱼ Aᵢⱼₖₗ vₗ. */ | ||
void ContractWithVectors(const Eigen::Ref<const Vector3<T>>& u, | ||
const Eigen::Ref<const Vector3<T>>& v, | ||
EigenPtr<Matrix3<T>> B) const; | ||
|
||
/** Returns this fourth order tensor encoded as a matrix. */ | ||
const MatrixType& data() const { return data_; } | ||
|
||
/** (Advanced) Returns this fourth order tensor encoded as a mutable matrix. | ||
*/ | ||
MatrixType& mutable_data() { return data_; } | ||
|
||
/** Returns the value of the 4th order tensor at the given indices. | ||
@pre 0 <= i, j, k, l < 3. */ | ||
const T& operator()(int i, int j, int k, int l) const { | ||
DRAKE_ASSERT(0 <= i && i < 3); | ||
DRAKE_ASSERT(0 <= j && j < 3); | ||
DRAKE_ASSERT(0 <= k && k < 3); | ||
DRAKE_ASSERT(0 <= l && l < 3); | ||
return data_(3 * j + i, 3 * l + k); | ||
} | ||
|
||
/** Returns the value of the 4th order tensor at the given indices. | ||
@pre 0 <= i, j, k, l < 3. */ | ||
T& operator()(int i, int j, int k, int l) { | ||
DRAKE_ASSERT(0 <= i && i < 3); | ||
DRAKE_ASSERT(0 <= j && j < 3); | ||
DRAKE_ASSERT(0 <= k && k < 3); | ||
DRAKE_ASSERT(0 <= l && l < 3); | ||
return data_(3 * j + i, 3 * l + k); | ||
} | ||
|
||
/** Returns the value of the 4th order tensor at the given indices, | ||
interpreted as indices into the 9x9 matrix, using the convention layed out in | ||
the class documentation. | ||
@pre 0 <= i, j < 9. */ | ||
const T& operator()(int i, int j) const { | ||
DRAKE_ASSERT(0 <= i && i < 9); | ||
DRAKE_ASSERT(0 <= j && j < 9); | ||
return data_(i, j); | ||
} | ||
|
||
/** Returns the value of the 4th order tensor at the given indices, | ||
interpreted as indices into the 9x9 matrix, using the convention layed out in | ||
the class documentation. | ||
@pre 0 <= i, j < 9. */ | ||
T& operator()(int i, int j) { | ||
DRAKE_ASSERT(0 <= i && i < 9); | ||
DRAKE_ASSERT(0 <= j && j < 9); | ||
return data_(i, j); | ||
} | ||
|
||
/** Sets the data of this 4th order tensor to the given matrix, using the | ||
convention layed out in the class documentation. */ | ||
void set_data(const MatrixType& data) { data_ = data; } | ||
|
||
private: | ||
MatrixType data_{MatrixType::Zero()}; | ||
}; | ||
|
||
} // namespace math | ||
} // namespace drake |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,76 @@ | ||
#include "drake/math/fourth_order_tensor.h" | ||
|
||
#include "drake/common/eigen_types.h" | ||
#include "drake/common/test_utilities/eigen_matrix_compare.h" | ||
|
||
using Eigen::Matrix3d; | ||
using Eigen::Vector3d; | ||
|
||
namespace drake { | ||
namespace math { | ||
namespace { | ||
|
||
Eigen::Matrix<double, 9, 9> MakeArbitraryMatrix() { | ||
Eigen::Matrix<double, 9, 9> data; | ||
for (int i = 0; i < 9; ++i) { | ||
for (int j = 0; j < 9; ++j) { | ||
data(i, j) = i + j; | ||
} | ||
} | ||
return data; | ||
} | ||
|
||
GTEST_TEST(FourthOrderTensorTest, DefaultConstructor) { | ||
FourthOrderTensor<double> tensor; | ||
EXPECT_TRUE(tensor.data().isZero()); | ||
const Vector3d u(1.0, 2.0, 3.0); | ||
const Vector3d v(4.0, 5.0, 6.0); | ||
Matrix3d B; | ||
|
||
tensor.ContractWithVectors(u, v, &B); | ||
EXPECT_TRUE(B.isZero()); | ||
} | ||
|
||
GTEST_TEST(FourthOrderTensorTest, ConstructWithData) { | ||
const Eigen::Matrix<double, 9, 9> data = MakeArbitraryMatrix(); | ||
FourthOrderTensor<double> tensor(data); | ||
EXPECT_EQ(tensor.data(), data); | ||
tensor.set_data(data.transpose()); | ||
EXPECT_EQ(tensor.data(), data.transpose()); | ||
|
||
EXPECT_EQ(tensor(0, 0, 0, 0), data(0, 0)); | ||
EXPECT_EQ(tensor(1, 1, 1, 1), data(4, 4)); | ||
} | ||
|
||
GTEST_TEST(FourthOrderTensorTest, ContractWithVectors) { | ||
FourthOrderTensor<double> tensor(MakeArbitraryMatrix()); | ||
|
||
/* If any vector input is zero, the contraction is zero. */ | ||
Vector3d u = Vector3d::Zero(); | ||
Vector3d v(4.0, 5.0, 6.0); | ||
Matrix3d B; | ||
tensor.ContractWithVectors(u, v, &B); | ||
EXPECT_TRUE(B.isZero()); | ||
tensor.ContractWithVectors(v, u, &B); | ||
EXPECT_TRUE(B.isZero()); | ||
|
||
/* If the 9x9 representation of the tensor has a repeating pattern in the | ||
blocks, the contraction is a multiple of that block. */ | ||
Matrix3d block; | ||
block << 1, 2, 3, 4, 5, 6, 7, 8, 9; | ||
Eigen::Matrix<double, 9, 9> data; | ||
for (int i = 0; i < 3; ++i) { | ||
for (int j = 0; j < 3; ++j) { | ||
data.block<3, 3>(3 * i, 3 * j) = block; | ||
} | ||
} | ||
tensor = FourthOrderTensor<double>(data); | ||
u << 1.0, 2.0, 3.0; | ||
v << 4.0, 5.0, 6.0; | ||
tensor.ContractWithVectors(u, v, &B); | ||
EXPECT_TRUE(CompareMatrices(B, block * (u * v.transpose()).sum())); | ||
} | ||
|
||
} // namespace | ||
} // namespace math | ||
} // namespace drake |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.