Skip to content

Commit

Permalink
Require unit vectors for functions in UnitInertia.
Browse files Browse the repository at this point in the history
  • Loading branch information
mitiguy committed Aug 4, 2023
1 parent 064f12c commit 086d891
Show file tree
Hide file tree
Showing 8 changed files with 147 additions and 126 deletions.
27 changes: 17 additions & 10 deletions bindings/pydrake/multibody/test/plant_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -727,25 +727,32 @@ def test_unit_inertia_api(self, T):
self.assertIsInstance(UnitInertia.SolidBox(Lx=1, Ly=2, Lz=3),
UnitInertia)
self.assertIsInstance(UnitInertia.SolidCube(L=2), UnitInertia)
self.assertIsInstance(UnitInertia.SolidCylinder(r=1.5, L=2),
self.assertIsInstance(UnitInertia.SolidCylinder(
radius=1.5, length=2, unit_vector=[0, 0, 1]),
UnitInertia)
self.assertIsInstance(
UnitInertia.SolidCylinder(r=1.5, L=2, b_E=[1, 2, 3]), UnitInertia)
self.assertIsInstance(UnitInertia.SolidCapsule(r=1, L=2), UnitInertia)
self.assertIsInstance(UnitInertia.SolidCapsule(r=1, L=2,
unit_vector=[0, 0, 1]),
with catch_drake_warnings(expected_count=1):
self.assertIsInstance(UnitInertia.SolidCylinder(r=1.5, L=2),
UnitInertia)
self.assertIsInstance(UnitInertia.SolidCapsule(
radius=1, length=2, unit_vector=[0, 0, 1]),
UnitInertia)
with catch_drake_warnings(expected_count=1):
self.assertIsInstance(UnitInertia.SolidCapsule(r=1, L=2),
UnitInertia)
self.assertIsInstance(UnitInertia.SolidCylinderAboutEnd(
radius=0.1, length=0.4, unit_vector=[0, 0, 1]),
UnitInertia)
with catch_drake_warnings(expected_count=1):
self.assertIsInstance(UnitInertia.SolidCylinderAboutEnd(r=1, L=4),
UnitInertia)
self.assertIsInstance(
UnitInertia.AxiallySymmetric(J=1, K=2, b_E=[0, 0, 1]), UnitInertia)
self.assertIsInstance(UnitInertia.StraightLine(K=1.5, b_E=[0, 0, 1]),
self.assertIsInstance(UnitInertia.AxiallySymmetric(
moment_parallel=1, moment_perpendicular=2, unit_vector=[0, 0, 1]),
UnitInertia)
self.assertIsInstance(UnitInertia.StraightLine(
moment_perpendicular=1.5, unit_vector=[0, 0, 1]),
UnitInertia)
self.assertIsInstance(UnitInertia.ThinRod(L=1.5, b_E=[0, 0, 1]),
self.assertIsInstance(UnitInertia.ThinRod(
length=1.5, unit_vector=[0, 0, 1]),
UnitInertia)

@numpy_compare.check_all_types
Expand Down
5 changes: 3 additions & 2 deletions bindings/pydrake/multibody/tree_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1174,8 +1174,9 @@ void DoScalarDependentDefinitions(py::module m, T) {
}),
py::arg("r"), py::arg("L"),
cls_doc.SolidCylinderAboutEnd.doc_deprecated)
.def_static("AxiallySymmetric", &Class::AxiallySymmetric, py::arg("J"),
py::arg("K"), py::arg("b_E"), cls_doc.AxiallySymmetric.doc)
.def_static("AxiallySymmetric", &Class::AxiallySymmetric,
py::arg("moment_parallel"), py::arg("moment_perpendicular"),
py::arg("unit_vector"), cls_doc.AxiallySymmetric.doc)
.def_static("StraightLine", &Class::StraightLine, py::arg("K"),
py::arg("b_E"), cls_doc.StraightLine.doc)
.def_static("ThinRod", &Class::ThinRod, py::arg("L"), py::arg("b_E"),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -65,8 +65,11 @@ GTEST_TEST(PopulateCylinderPlant, VerifyPlant) {

EXPECT_EQ(M_Bcm_B.get_mass(), mass);
EXPECT_EQ(M_Bcm_B.get_com(), Vector3d::Zero());
EXPECT_EQ(M_Bcm_B.get_unit_inertia().get_moments(),
Vector3d(G_perp, G_perp, G_axis));

// An empirical tolerance: two bits = 2^2 times machine epsilon.
const double kTolerance = 4 * std::numeric_limits<double>::epsilon();
EXPECT_TRUE(CompareMatrices(M_Bcm_B.get_unit_inertia().get_moments(),
Vector3d(G_perp, G_perp, G_axis), kTolerance));
EXPECT_EQ(M_Bcm_B.get_unit_inertia().get_products(), Vector3d::Zero());

// TODO(amcastro-tri): Verify geometry including:
Expand Down
6 changes: 4 additions & 2 deletions multibody/parsing/test/detail_mujoco_parser_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -736,9 +736,11 @@ TEST_F(MujocoParserTest, InertiaFromGeometry) {

check_body("default", UnitInertia<double>::SolidSphere(0.1));
check_body_spatial("sphere", inertia_from_inertial_tag);
check_body("capsule", UnitInertia<double>::SolidCapsule(0.1, 4.0));
check_body("capsule",
UnitInertia<double>::SolidCapsule(0.1, 4.0, Vector3d::UnitZ()));
check_body("ellipsoid", UnitInertia<double>::SolidEllipsoid(0.1, 0.2, 0.3));
check_body("cylinder", UnitInertia<double>::SolidCylinder(0.1, 4.0));
check_body("cylinder",
UnitInertia<double>::SolidCylinder(0.1, 4.0, Vector3d::UnitZ()));
check_body("box", UnitInertia<double>::SolidBox(0.2, 4.0, 6.0));
check_body("box_from_default", UnitInertia<double>::SolidBox(0.2, 0.4, 0.6));
check_body("ellipsoid_from_default",
Expand Down
2 changes: 1 addition & 1 deletion multibody/tree/test/spatial_inertia_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -880,7 +880,7 @@ GTEST_TEST(SpatialInertia, Shift) {
// First define it in frame B.
SpatialInertia<double> M_BBcm_W(
mass, Vector3d::Zero(),
UnitInertia<double>::SolidCylinder(radius, length));
UnitInertia<double>::SolidCylinder(radius, length, Vector3d::UnitZ()));
// Then re-express in frame W.
M_BBcm_W.ReExpressInPlace(R_WB);

Expand Down
17 changes: 11 additions & 6 deletions multibody/tree/test/unit_inertia_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -239,7 +239,7 @@ GTEST_TEST(UnitInertia, SolidCylinder) {
"[^]* The unit_vector argument .* is not a unit vector.");

// Form unit inertia for a cylinder oriented in an "interesting" direction.
const Vector3d v = bad_vec / bad_vec.norm(); // Make
const Vector3d v = bad_vec.normalized();
const UnitInertia<double> Gv =
UnitInertia<double>::SolidCylinder(r, L, v);
// Generate a rotation matrix from a Frame V in which Vz = v to frame Z where
Expand Down Expand Up @@ -371,9 +371,9 @@ GTEST_TEST(UnitInertia, SolidCapsule) {
I_capsule_expected.get_products(), kEpsilon));

// Ensure a bad unit vector throws an exception.
const Vector3<double> bad_vec(1, 0.1, 0);
const Vector3<double> bad_uvec(1, 0.1, 0);
DRAKE_EXPECT_THROWS_MESSAGE(
UnitInertia<double>::SolidCapsule(r, L, bad_vec),
UnitInertia<double>::SolidCapsule(r, L, bad_uvec),
"[^]* The unit_vector argument .* is not a unit vector.");
}

Expand Down Expand Up @@ -449,7 +449,7 @@ GTEST_TEST(UnitInertia, AxiallySymmetric) {
"[^]* The unit_vector argument .* is not a unit vector.");

// Cylinder's axis. A vector on the y-z plane, at -pi/4 from the z axis.
const Vector3d b_E = bad_uvec / bad_uvec.norm();
const Vector3d b_E = bad_uvec.normalized();

// Rotation of -pi/4 about the x axis, from a Z frame having its z axis
// aligned with the z-axis of the cylinder to the expressed-in frame E.
Expand Down Expand Up @@ -497,9 +497,14 @@ GTEST_TEST(UnitInertia, ThinRod) {
// Moment of inertia for an infinitesimally thin rod of length L.
const double I_rod = L * L / 12.0;

const Vector3d bad_uvec = Vector3d::UnitY() + Vector3d::UnitZ();
DRAKE_EXPECT_THROWS_MESSAGE(
UnitInertia<double>::StraightLine(I_rod, bad_uvec),
"[^]* The unit_vector argument .* is not a unit vector.");

// Rod's axis. A vector on the y-z plane, at -pi/4 from the z axis.
// The vector doesn't need to be normalized.
const Vector3d b_E = Vector3d::UnitY() + Vector3d::UnitZ();
const Vector3d b_E = bad_uvec.normalized();

// Rotation of -pi/4 about the x axis, from a Z frame having its z-axis
// aligned with the rod to the expressed-in frame E.
Expand All @@ -513,7 +518,7 @@ GTEST_TEST(UnitInertia, ThinRod) {
// The expected inertia is that of a cylinder of zero radius and height L with
// its longitudinal axis aligned with b.
UnitInertia<double> G_Z =
UnitInertia<double>::SolidCylinder(0.0, L, Vector3d::UnitZ());
UnitInertia<double>::SolidCylinder(0, L, Vector3d::UnitZ());
UnitInertia<double> G_E_expected = G_Z.ReExpress(R_EZ);

// Verify the computed values.
Expand Down
43 changes: 26 additions & 17 deletions multibody/tree/unit_inertia.cc
Original file line number Diff line number Diff line change
Expand Up @@ -98,38 +98,47 @@ UnitInertia<T> UnitInertia<T>::SolidCylinderAboutEnd(
}

template <typename T>
UnitInertia<T> UnitInertia<T>::AxiallySymmetric(
const T& J, const T& K, const Vector3<T>& unit_vector) {
DRAKE_THROW_UNLESS(J >= 0.0);
DRAKE_THROW_UNLESS(K >= 0.0);
DRAKE_THROW_UNLESS(J <= 2.0 * K); // Triangle inequality simplifies to J ≤ K.
ThrowUnlessVectorIsMagnitudeOne(unit_vector, __func__);
UnitInertia<T> UnitInertia<T>::AxiallySymmetric(const T& moment_parallel,
const T& moment_perpendicular, const Vector3<T>& unit_vector) {
const T& J = moment_parallel;
const T& K = moment_perpendicular;
DRAKE_THROW_UNLESS(moment_parallel >= 0.0); // Ensure J ≥ 0.
DRAKE_THROW_UNLESS(moment_perpendicular >= 0.0); // Ensure K ≥ 0.

// When the about-point Bp is Bcm, the moment of inertia triangle inequality
// simplifies to J ≤ 2 K. If Bp is not Bp, J ≤ 2 K is still valid because
// K_Bp (perpendicular moment of inertia about Bp) relates to
// K_Bcm (perpendicular moment of inertia about Bcm) as K_Bp = K_Bcm + dist²,
// where dist is the distance between points Bp and Bcm.
DRAKE_THROW_UNLESS(moment_parallel <= 2.0 * moment_perpendicular);

// TODO(Mitiguy) consider a "trust_me" type of parameter that can skip
// normalizing the unit_vector (it frequently is perfect on entry).
ThrowUnlessVectorIsMagnitudeOne(unit_vector, __func__);
Vector3<T> uvec = unit_vector.normalized();
Matrix3<T> G_matrix =

// Form B's unit inertia about a point Bp on B's symmetry axis,
// expressed in the same frame E as the unit_vector is expressed.
Matrix3<T> G_BBp_E =
K * Matrix3<T>::Identity() + (J - K) * uvec * uvec.transpose();
return UnitInertia<T>(G_matrix(0, 0), G_matrix(1, 1), G_matrix(2, 2),
G_matrix(0, 1), G_matrix(0, 2), G_matrix(1, 2));
return UnitInertia<T>(G_BBp_E(0, 0), G_BBp_E(1, 1), G_BBp_E(2, 2),
G_BBp_E(0, 1), G_BBp_E(0, 2), G_BBp_E(1, 2));
}

template <typename T>
UnitInertia<T> UnitInertia<T>::StraightLine(const T& K,
UnitInertia<T> UnitInertia<T>::StraightLine(const T& moment_perpendicular,
const Vector3<T>& unit_vector) {
// TODO(Mitiguy) Throw if |b_E| is not within 1.0E-14 of 1 (breaking change).
DRAKE_DEMAND(K > 0.0);
DRAKE_THROW_UNLESS(moment_perpendicular > 0.0);
ThrowUnlessVectorIsMagnitudeOne(unit_vector, __func__);
return AxiallySymmetric(0.0, K, unit_vector);
return AxiallySymmetric(0.0, moment_perpendicular, unit_vector);
}

template <typename T>
UnitInertia<T> UnitInertia<T>::ThinRod(const T& L,
UnitInertia<T> UnitInertia<T>::ThinRod(const T& length,
const Vector3<T>& unit_vector) {
// TODO(Mitiguy) Throw if |b_E| is not within 1.0E-14 of 1 (breaking change).
DRAKE_DEMAND(L > 0.0);
DRAKE_THROW_UNLESS(length > 0.0);
ThrowUnlessVectorIsMagnitudeOne(unit_vector, __func__);
return StraightLine(L * L / 12.0, unit_vector);
return StraightLine(length * length / 12.0, unit_vector);
}

template <typename T>
Expand Down

0 comments on commit 086d891

Please sign in to comment.