Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Require unit vectors for UnitInertia functions. #19926

Merged

Conversation

mitiguy
Copy link
Contributor

@mitiguy mitiguy commented Aug 3, 2023

This change is Reviewable

@mitiguy mitiguy force-pushed the requireUnitVectorsForInertiaCalcs branch from 086d891 to 2b6fbac Compare August 8, 2023 02:20
@mitiguy mitiguy changed the title [WIP] Require reasonable unit vectors for UnitInertia functions. Require unit vectors for UnitInertia functions. Aug 8, 2023
Copy link
Contributor Author

@mitiguy mitiguy left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Feature review +@sherm1

Reviewable status: LGTM missing from assignee sherm1(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @mitiguy)


examples/multibody/cylinder_with_multicontact/test/populate_cylinder_plant_test.cc line 72 at r1 (raw file):

  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));

FYI The new change allows for a two bit difference in the results -- rather than being exactly equal.
The old test was too strict, requiring exact bit-match when it could not be guaranteed.


multibody/tree/unit_inertia.h line 428 at r1 (raw file):

  /// @throws std::exception if moment_parallel (J) or moment_perpendicular (K)
  /// is negative or if J > 2 K (violates the triangle inequality, see
  /// CouldBePhysicallyValid()) or ‖unit_vector‖ is not within 1.0E-14 of 1.0.

FYI: Another name for the parameter moment_parallel could be moment_axial.


multibody/tree/unit_inertia.cc line 192 at r1 (raw file):

  // The distance dH between Hcm (the half-sphere H's center of mass) and Ccm
  // (the cylinder C's center of mass) is from [Kane, Figure A23, pg. 369].
  // dH = 3.0 / 8.0 * r + L / 2.0;

FYI Change to dH = ⅜ radius + ½ length.


multibody/tree/test/unit_inertia_test.cc line 215 at r1 (raw file):

  const double I_axial = r * r / 2.0;
  const UnitInertia<double> Gz_expected(I_perp, I_perp, I_axial);
  // Compute the unit inertia for a cylinder oriented along the z-axis

FYI Missing a period .


multibody/tree/test/unit_inertia_test.cc line 647 at r1 (raw file):

  const double r = 2.5;
  const double L = 1.5;
  UnitInertia<double> G_expected = UnitInertia<double>::SolidCylinderAboutEnd(

FYI Consider adding const, e.g.,
const UnitInertia G_expected ...
Similarly consider adding const for G2 and G3 (below).


bindings/pydrake/multibody/tree_py.cc line 1159 at r1 (raw file):

                const Vector3<T>&>(&Class::SolidCylinder),
            py::arg("radius"), py::arg("length"), py::arg("unit_vector"),
            cls_doc.SolidCylinder.doc)

FYI: The code below deprecates calls to SolidCylinder() with only 2 arguments.
The default value of the optional 3rd parameter was Vector3::UnitZ().

Similarly for the next block which deprecates calls to SolidCapsule() with only 2 arguments.

Copy link
Member

@sherm1 sherm1 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Feature review checkpoint.

Reviewed 7 of 9 files at r1, all commit messages.
Reviewable status: 12 unresolved discussions, LGTM missing from assignee sherm1(platform), needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @mitiguy)


multibody/tree/unit_inertia.h line 270 at r1 (raw file):

  /// @param[in] r The radius of the cylinder, it must be non-negative.
  /// @param[in] L The length of the cylinder, it must be non-negative.
  /// @param[in] b_E

minor: this argument is no longer present in the deprecated signature


multibody/tree/unit_inertia.h line 286 at r1 (raw file):

  ///   - `b_E` is the zero vector. That is if `‖b_E‖₂ ≤ ε`, where ε is the
  ///     machine epsilon.
  DRAKE_DEPRECATED("2023-11-01",

nit: our 3 month minimum deprecation promise means this has to be 2023-12-01 everywhere in this PR


multibody/tree/unit_inertia.h line 315 at r1 (raw file):

  /// @param[in] r radius of the cylinder/half-sphere parts of the capsule.
  /// @param[in] L length of the cylindrical part of the capsule.
  /// @param[in] unit_vector direction of the cylindrical part of the capsule.

minor: this argument is no longer present in the deprecated signature


multibody/tree/unit_inertia.h line 348 at r1 (raw file):

  /// @param[in] L The length of the cylinder.
  /// @throws std::exception if r or L is negative.
  DRAKE_DEPRECATED("2023-11-01",

BTW consider changing this date to 2023-12-01 to sync it with the new related deprecations


multibody/tree/unit_inertia.h line 408 at r1 (raw file):

  /// cylinders or cones and propellers with 3⁺ evenly spaced blades.
  /// For a body B with axially symmetric inertia, B's unit inertia about a
  /// point Bp on axis L can be written in terms of a unit_vector parallel to L;

BTW when I read this I was expecting to see Bp as an argument. But I see now this is just some point in the caller's mind that affects the parallel (axial) inertia value. Can you clarify that somehow?


multibody/tree/unit_inertia.h line 428 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI: Another name for the parameter moment_parallel could be moment_axial.

I could see either axial/radial or parallel/perpendicular but I think they should be a matched pair. If they are interchangeable everywhere I'd be inclined to go with the shorter words but I'm OK with either pair.


multibody/tree/unit_inertia.cc line 12 at r1 (raw file):

// Throws unless ‖unit_vector‖ is within ≈ 5.5 bits of 1.0.
// Note: 1E-14 ≈ 2^5.5 * std::numeric_limits<double>::epsilon();
// Note: This function is a no-op when type T is symbolic::Expression.

BTW consider noting that 1e-14 is the threshold we use to decide whether a user's alleged unit vector is acceptable, but is not nearly as "unit" as we typically expect when normalizing, which is an extremely well-behaved calculation typically 100X better (1±1e-16). So unless the length is exactly 1 (common since coordinate axes are popular directions) we should normalize internally even if the user's vector passes this test.


multibody/tree/unit_inertia.cc line 25 at r1 (raw file):

    // 𝐯⋅𝐯 ≤ (1 + ε)²  and 𝐯⋅𝐯 ≥ (1 - ε)².  Distributing the square results in
    // 𝐯⋅𝐯 ≤ 1 + 2 ε + ε²  and 𝐯⋅𝐯 ≥ 1 - 2 ε + ε². Since ε² ≪ 2 ε, this gives
    // 𝐯⋅𝐯 - 1 ≤ 2 ε   and 𝐯⋅𝐯 - 1 ≥ -2 ε  or  |𝐯⋅𝐯 − 1| ≤ 2 ε

BTW Nice! I don't think I've seen that derivation before.


multibody/tree/unit_inertia.cc line 32 at r1 (raw file):

    // -------------------------------------------------------------
    constexpr double kTolerance2 = 2E-14;
    if (abs(unit_vector.squaredNorm() - 1) > kTolerance2) {

BTW consider returning abs(unit_vector.squaredNorm() - 1 as the return value of this function if it doesn't fail. The caller could use that to decide at no cost whether a normalization is needed (e.g. if this return is zero then we're good).


multibody/tree/unit_inertia.cc line 82 at r1 (raw file):

  const T l2 = length * length;
  const T J = 0.5 * r2;               // Axial moment of inertia J = ½ r².
  const T K = 0.25 * r2 + l2 / 12.0;  // Transverse moment K = ¼ r² + ¹⁄₁₂ l².

BTW arggh l2/12!


multibody/tree/unit_inertia.cc line 112 at r1 (raw file):

  // 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);

BTW should we allow some epsilon slop here or require the user to clean up their own numerics? I'm fine either way as long as it's documented.


multibody/tree/unit_inertia.cc line 121 at r1 (raw file):

  // 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 =

nit: uvec and G should be const


multibody/tree/unit_inertia.cc line 192 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI Change to dH = ⅜ radius + ½ length.

minor: comment fix needed


multibody/tree/unit_inertia.cc line 217 at r1 (raw file):

  // more efficient result by factoring on mh and mc and computing numbers as
  const T l2 = length * length;
  const T Ixx = mc * (l2/12.0 + 0.25*r2) + mh * (0.51875*r2 + 2*dH*dH);

BTW wow l2/12 is hard to read! Consider l2 -> length2


multibody/tree/test/unit_inertia_test.cc line 215 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI Missing a period .

nit comment fix needed

@sherm1 sherm1 added the release notes: newly deprecated This pull request contains new deprecations label Aug 9, 2023
Copy link
Member

@sherm1 sherm1 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

There are some subtle breaking changes here, for example:

  • same signature, but vector arguments that would have been accepted are rejected now
  • unchanged functions where the argument names have changed so kwargs calls in Python will break

The specifics should be documented in the PR description so that whoever makes the next release notes will know what to say about the breaking changes. Also there are deprecations +(release notes: newly deprecated) .

Feature :lgtm: pending a few minor things
+@jwnimmer-tri for platform review per schedule, please

Reviewed 2 of 9 files at r1.
Reviewable status: 12 unresolved discussions, LGTM missing from assignee jwnimmer-tri(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @mitiguy)

Copy link
Collaborator

@jwnimmer-tri jwnimmer-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewed 5 of 9 files at r1, all commit messages.
Reviewable status: 16 unresolved discussions, LGTM missing from assignee jwnimmer-tri(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @mitiguy)

a discussion (no related file):
This is our deprecation policy: https://drake.mit.edu/stable.html. In particular, it says:

On very rare occasions it is impractical, too expensive, or logically unsound to meet the full three month deprecation window. In these cases the change will be announced in the “Breaking changes” section of the release notes.

In this PR, we have a breaking change to newly throw when a unit_vector is too far from unit. I was unable to figure out why using deprecation for that (instead of a breaking change) would be impractical, expensive, or unsound. If there is such a reason, you could reply here to help make it clear.

My assumption is that in these functions, the response to an out-of-tolerance unit vector could be to warn once and then re-normalize. After the deprecation window, we would replace the warning with an exception.


a discussion (no related file):
The attempts are python deprecations are missing a lot of important pieces. I noted a few places that I started to find, but overall it needs a lot of work. Let me know if you'd like me to push a patch to this branch with the proper code.



bindings/pydrake/multibody/tree_py.cc line 1169 at r1 (raw file):

#pragma GCC diagnostic pop
                }),
            py::arg("r"), py::arg("L"), cls_doc.SolidCylinder.doc_deprecated)

We are missing the defaulted unit_vector kwarg argument here.


bindings/pydrake/multibody/tree_py.cc line 1202 at r1 (raw file):

            cls_doc.SolidCylinderAboutEnd.doc_deprecated)
        .def_static("AxiallySymmetric", &Class::AxiallySymmetric,
            py::arg("moment_parallel"), py::arg("moment_perpendicular"),

It looks to me like a bunch of the argument-name-change deprecation shims are missing.

@mitiguy mitiguy removed the release notes: breaking change This pull request contains breaking changes label Aug 10, 2023
Copy link
Contributor Author

@mitiguy mitiguy left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 4 unresolved discussions, LGTM missing from assignee jwnimmer-tri(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)

a discussion (no related file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

This is our deprecation policy: https://drake.mit.edu/stable.html. In particular, it says:

On very rare occasions it is impractical, too expensive, or logically unsound to meet the full three month deprecation window. In these cases the change will be announced in the “Breaking changes” section of the release notes.

In this PR, we have a breaking change to newly throw when a unit_vector is too far from unit. I was unable to figure out why using deprecation for that (instead of a breaking change) would be impractical, expensive, or unsound. If there is such a reason, you could reply here to help make it clear.

My assumption is that in these functions, the response to an out-of-tolerance unit vector could be to warn once and then re-normalize. After the deprecation window, we would replace the warning with an exception.

I removed the label about breaking changes.
I am unsure how to warn once.


a discussion (no related file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

The attempts are python deprecations are missing a lot of important pieces. I noted a few places that I started to find, but overall it needs a lot of work. Let me know if you'd like me to push a patch to this branch with the proper code.

Assuming this new commit passes CI, that would be great.
Thanks Jeremy.



multibody/tree/unit_inertia.h line 270 at r1 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

minor: this argument is no longer present in the deprecated signature

Done. Removed all references to b_E.


multibody/tree/unit_inertia.h line 286 at r1 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

nit: our 3 month minimum deprecation promise means this has to be 2023-12-01 everywhere in this PR

Done here and elsewhere.


multibody/tree/unit_inertia.h line 315 at r1 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

minor: this argument is no longer present in the deprecated signature

Done. Removed all references to unit_vector.


multibody/tree/unit_inertia.h line 348 at r1 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW consider changing this date to 2023-12-01 to sync it with the new related deprecations

Done here and elsewhere.


multibody/tree/unit_inertia.h line 408 at r1 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW when I read this I was expecting to see Bp as an argument. But I see now this is just some point in the caller's mind that affects the parallel (axial) inertia value. Can you clarify that somehow?

Done. See new @pre that was added.


multibody/tree/unit_inertia.h line 428 at r1 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

I could see either axial/radial or parallel/perpendicular but I think they should be a matched pair. If they are interchangeable everywhere I'd be inclined to go with the shorter words but I'm OK with either pair.

Done. Leaving them as-is.


multibody/tree/unit_inertia.cc line 12 at r1 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW consider noting that 1e-14 is the threshold we use to decide whether a user's alleged unit vector is acceptable, but is not nearly as "unit" as we typically expect when normalizing, which is an extremely well-behaved calculation typically 100X better (1±1e-16). So unless the length is exactly 1 (common since coordinate axes are popular directions) we should normalize internally even if the user's vector passes this test.

Done.


multibody/tree/unit_inertia.cc line 25 at r1 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW Nice! I don't think I've seen that derivation before.

Done. Thanks Sherm.


multibody/tree/unit_inertia.cc line 32 at r1 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW consider returning abs(unit_vector.squaredNorm() - 1 as the return value of this function if it doesn't fail. The caller could use that to decide at no cost whether a normalization is needed (e.g. if this return is zero then we're good).

Done. Per f2f -- return magnitude squared of unit_vector.


multibody/tree/unit_inertia.cc line 82 at r1 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW arggh l2/12!

Done l2 -> lsq.


multibody/tree/unit_inertia.cc line 112 at r1 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW should we allow some epsilon slop here or require the user to clean up their own numerics? I'm fine either way as long as it's documented.

Done.


multibody/tree/unit_inertia.cc line 121 at r1 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

nit: uvec and G should be const

Done.


multibody/tree/unit_inertia.cc line 192 at r1 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

minor: comment fix needed

Done.


multibody/tree/unit_inertia.cc line 217 at r1 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW wow l2/12 is hard to read! Consider l2 -> length2

Done.


multibody/tree/test/unit_inertia_test.cc line 215 at r1 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

nit comment fix needed

Done.


bindings/pydrake/multibody/tree_py.cc line 1169 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

We are missing the defaulted unit_vector kwarg argument here.

Yes. I am unsure how to handle this.


bindings/pydrake/multibody/tree_py.cc line 1202 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

It looks to me like a bunch of the argument-name-change deprecation shims are missing.

Yes. I agree. I appreciate your offer to help by pushing a fix.

Copy link
Member

@sherm1 sherm1 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewed 1 of 4 files at r2, 3 of 3 files at r3, 1 of 1 files at r4, all commit messages.
Reviewable status: 6 unresolved discussions, LGTM missing from assignee jwnimmer-tri(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @mitiguy)


multibody/tree/unit_inertia.h line 270 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

Done. Removed all references to b_E.

I see you removed all the documentation for the deprecated function. I don't think that's a good idea because the existing documentation can be helpful for a person converting from the deprecated function to the replacement.


multibody/tree/unit_inertia.h line 315 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

Done. Removed all references to unit_vector.

Same comment about leaving the documentation.


multibody/tree/unit_inertia.cc line 70 at r3 (raw file):

        e.what());
    return unit_vector.squaredNorm();
  }

Our styleguide prohibits catching exceptions. You'll have to find a different way of doing this.


multibody/tree/unit_inertia.cc line 167 at r3 (raw file):

    const Vector3<T>& unit_vector) {
  DRAKE_THROW_UNLESS(moment_perpendicular > 0.0);
  WarnUnlessVectorIsMagnitudeOne(unit_vector, __func__);

BTW consider including a TODO comment with the deprecation date for each of these "Warns" to change them to "Throws"

Copy link
Collaborator

@jwnimmer-tri jwnimmer-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewed 3 of 3 files at r3, 1 of 1 files at r4, 1 of 1 files at r5, all commit messages.
Reviewable status: 7 unresolved discussions, LGTM missing from assignee jwnimmer-tri(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @mitiguy)

a discussion (no related file):
Done

I am unsure how to warn once.

My comment above hyperlinked to the documentation about how to do it. (Maybe the underline is a bit too subtle in Reviewable.)

In any case, I've pushed the fix:

[ RUN      ] UnitInertia.SolidCylinder
[2023-08-10 08:16:49.686] [console] [warning] SolidCylinder(): The unit_vector argument 1 2 3 is not a unit vector. Implicit normalization is deprecated; on or after 2023-12-01 this will become an exception.
[       OK ] UnitInertia.SolidCylinder (0 ms)

a discussion (no related file):

Previously, mitiguy (Mitiguy) wrote…

Assuming this new commit passes CI, that would be great.
Thanks Jeremy.

I'm still working on this part.



multibody/tree/unit_inertia.h line 270 at r1 (raw file):
The removal of the docs was my change, because it's a colossal pain in my ass to maintain the two copies of the documentation up to date.

Given this code in the header file ...

  static UnitInertia<T> SolidCylinder(const T& r, const T& L) {
    return SolidCylinder(r, L, Vector3<T>::UnitZ());

... I think the typical programmer will be able to figure out what's going on without very much difficulty at all.

I don't think that's a good idea because the existing documentation can be helpful for a person converting from the deprecated function to the replacement.

I'm interpreting this as a suggestion, not a defect. If there is a defect, please clarify.


multibody/tree/unit_inertia.cc line 70 at r3 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

Our styleguide prohibits catching exceptions. You'll have to find a different way of doing this.

We've previously allowed it within a small, bounded scope when the alternatives are substantially worse.

In any case, I've pushed the worse version now.


multibody/tree/unit_inertia.cc line 167 at r3 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW consider including a TODO comment with the deprecation date for each of these "Warns" to change them to "Throws"

OK Won't do.

In December, I will not have any problem knowing what to do here.


multibody/tree/unit_inertia.cc line 114 at r4 (raw file):

  const T J = 0.5 * rsq;                // Axial moment of inertia J = ½ r².
  const T K = 0.25 * rsq + lsq / 12.0;  // Transverse moment K = ¼ r² + ¹⁄₁₂ l².
  return AxiallySymmetric(J, K, unit_vector);

nit For my money, keeping the code clear here vastly outweights the 1 flop we might be saving introducing temporaries with cryptic names. Do we actually expect people to call SolidCylinder as part of an inner loop? (If we do care about throughput, why are we using / 12.0 instead of * (1 / 12.0)?)

My assumption is that the temporary names were intended for clarity (not performance). To me, this is more clear:

  // Axial moment of inertia J = ½ r².
  const T J = 0.5 * radius * radius;
  // Transverse moment K = ¼ r² + ¹⁄₁₂ l².
  const T K = 0.25 * radius * radius + length * length / 12.0;
  return AxiallySymmetric(J, K, unit_vector);

Ditto for all of the other code throughout.

Or if you don't want to go that far, the obvious response to Sherm's "ick" on l2 would be to named the temporary like length2. That better matches up with the math in the comments.

  const T radius2 = radius * radius;
  const T length2 = length * length;
  // Axial moment of inertia J = ½ r².
  const T J = 0.5 * radius2;
  // Transverse moment K = ¼ r² + ¹⁄₁₂ l².
  const T K = 0.25 * radius2 + length2 / 12.0;
  return AxiallySymmetric(J, K, unit_vector);

multibody/tree/unit_inertia.cc line 214 at r4 (raw file):

  // Calculate vc (the volume of cylinder C) and vh (volume of half-sphere H).
  const T rsq = radius * radius;

nit Cherry-picking one more example of a rename adjustment that made readability worse not better. There are more nearby.

Suggestion:

radius2

multibody/tree/test/unit_inertia_test.cc line 254 at r4 (raw file):

// Tests the static method to obtain the unit inertia of a solid cylinder B
// computed about a point Bp at the center of its base.
GTEST_TEST(UnitInertia, SolidCylinderAboutEnd) {

It looks like the UnitInertia.SolidCylinderAboutEnd test case got deleted by mistake in 37628e8. We should put it back, right?

Copy link
Collaborator

@jwnimmer-tri jwnimmer-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 7 unresolved discussions, LGTM missing from assignee jwnimmer-tri(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @mitiguy)


multibody/tree/unit_inertia.h line 270 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

The removal of the docs was my change, because it's a colossal pain in my ass to maintain the two copies of the documentation up to date.

Given this code in the header file ...

  static UnitInertia<T> SolidCylinder(const T& r, const T& L) {
    return SolidCylinder(r, L, Vector3<T>::UnitZ());

... I think the typical programmer will be able to figure out what's going on without very much difficulty at all.

I don't think that's a good idea because the existing documentation can be helpful for a person converting from the deprecated function to the replacement.

I'm interpreting this as a suggestion, not a defect. If there is a defect, please clarify.

The one thing we could do is improve the deprecation message string to contain more detail(s) or suggestion(s). If you have ideas on that front, feel free to push your improvements to the branch.

Copy link
Member

@sherm1 sherm1 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewed 1 of 1 files at r5, all commit messages.
Reviewable status: 6 unresolved discussions, LGTM missing from assignee jwnimmer-tri(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @mitiguy)


multibody/tree/unit_inertia.h line 270 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

The one thing we could do is improve the deprecation message string to contain more detail(s) or suggestion(s). If you have ideas on that front, feel free to push your improvements to the branch.

I thought I learned the "leave the deprecated docs alone" convention from you! If you're OK with nuking it now, so am I.

Copy link
Member

@sherm1 sherm1 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

BTW CI didn't like this:

multibody/tree/unit_inertia.cc:84:32: error: unused variable 'log_once' [-Werror,-Wunused-variable]
    static const logging::Warn log_once(

Reviewable status: 6 unresolved discussions, LGTM missing from assignee jwnimmer-tri(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @mitiguy)

@jwnimmer-tri
Copy link
Collaborator

Aha, thanks! Apparently the config I use (Jammy + GCC) was the only one that passed.

Copy link
Member

@sherm1 sherm1 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewed 2 of 2 files at r6, all commit messages.
Reviewable status: 6 unresolved discussions, LGTM missing from assignee jwnimmer-tri(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @mitiguy)

Copy link
Collaborator

@jwnimmer-tri jwnimmer-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewed 2 of 2 files at r6, all commit messages.
Reviewable status: 6 unresolved discussions, LGTM missing from assignee jwnimmer-tri(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @mitiguy)


common/text_logging.h line 200 at r6 (raw file):

/// }
/// </pre>
struct[[maybe_unused]] Warn {

FYI This is the (unfortunate) whitespace that cpplint requires. I decided not to fight it for now.

Copy link
Contributor Author

@mitiguy mitiguy left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 6 unresolved discussions, LGTM missing from assignee jwnimmer-tri(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)

a discussion (no related file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

I'm still working on this part.

OK -- I made some comments. After you are done, I'll implement subsequent changes.



multibody/tree/unit_inertia.cc line 114 at r4 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

nit For my money, keeping the code clear here vastly outweights the 1 flop we might be saving introducing temporaries with cryptic names. Do we actually expect people to call SolidCylinder as part of an inner loop? (If we do care about throughput, why are we using / 12.0 instead of * (1 / 12.0)?)

My assumption is that the temporary names were intended for clarity (not performance). To me, this is more clear:

  // Axial moment of inertia J = ½ r².
  const T J = 0.5 * radius * radius;
  // Transverse moment K = ¼ r² + ¹⁄₁₂ l².
  const T K = 0.25 * radius * radius + length * length / 12.0;
  return AxiallySymmetric(J, K, unit_vector);

Ditto for all of the other code throughout.

Or if you don't want to go that far, the obvious response to Sherm's "ick" on l2 would be to named the temporary like length2. That better matches up with the math in the comments.

  const T radius2 = radius * radius;
  const T length2 = length * length;
  // Axial moment of inertia J = ½ r².
  const T J = 0.5 * radius2;
  // Transverse moment K = ¼ r² + ¹⁄₁₂ l².
  const T K = 0.25 * radius2 + length2 / 12.0;
  return AxiallySymmetric(J, K, unit_vector);

FYI Your suggestions sound fine. I discussed Sherm's "ick" with him and it had more to do with l2 looking like the number 12 -- and thought the rsq and lsq were improvements. I'll implement as you suggest (here and elsewhere).


multibody/tree/unit_inertia.cc line 214 at r4 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

nit Cherry-picking one more example of a rename adjustment that made readability worse not better. There are more nearby.

FYI Sounds good -- I'll implement.


multibody/tree/unit_inertia.cc line 23 at r6 (raw file):

// even if unit_vector passes this test. Usually this is accomplished by handing
// the unit_vector off to other function(s) that all eventually call down into
// AxiallySymmetric() which does the normalization.

FYI: Consider wording that is more generic.

Suggestion:

// directions), the calling function should consider normalizing unit_vector
// even if unit_vector passes this test or hand the unit_vector to another
// function that eventually does the normalization.

Copy link
Collaborator

@jwnimmer-tri jwnimmer-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewable status: 6 unresolved discussions, LGTM missing from assignee jwnimmer-tri(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @mitiguy)

a discussion (no related file):

Previously, mitiguy (Mitiguy) wrote…

OK -- I made some comments. After you are done, I'll implement subsequent changes.

BTW I'm done with all of my C++ changes, feel free to push any C++ edits you'd like, at whatever pace. My only remaining work is on the Python part. Pushing C++ changes will not interfere with my work on Python.



multibody/tree/unit_inertia.cc line 23 at r6 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI: Consider wording that is more generic.

My goal here was to be as specific as possible. It took me 10 minutes to chase down exactly where and how were normalizing our vectors, to convince myself that we were doing it 100% of the time and didn't miss any.

Copy link
Collaborator

@jwnimmer-tri jwnimmer-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

:lgtm: platform.

Reviewed 2 of 2 files at r7, all commit messages.
Reviewable status: 3 unresolved discussions, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @mitiguy)

a discussion (no related file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

BTW I'm done with all of my C++ changes, feel free to push any C++ edits you'd like, at whatever pace. My only remaining work is on the Python part. Pushing C++ changes will not interfere with my work on Python.

My python edits are done. I think the deprecation shims are complete now.



multibody/tree/unit_inertia.cc line 114 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI Your suggestions sound fine. I discussed Sherm's "ick" with him and it had more to do with l2 looking like the number 12 -- and thought the rsq and lsq were improvements. I'll implement as you suggest (here and elsewhere).

(Yes, I had grokked that l2 vs 12 was the complaint.)

I think the idea to carry forward to the future is to be suspicious when abbreviating that is ever an improvement. In most cases it's not.


bindings/pydrake/multibody/tree_py.cc line 1169 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

Yes. I am unsure how to handle this.

Done


bindings/pydrake/multibody/tree_py.cc line 1202 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

Yes. I agree. I appreciate your offer to help by pushing a fix.

Done

The important clue is that when deprecating python functions, the only change we should be making to the pre-existing unit test assertions is to wrap them in catch_drake_warnings. The original unit test changes in this PR were editing and/or deleting pre-existing test cases, which should be a red flag that breaking changes are happening, and so a clue to ask for help. I went back and grabbed the old test cases from git master, and copied them back into the updated unit test (modulo some whitespace reformatting).

@jwnimmer-tri
Copy link
Collaborator

FYI the current mac-arm-ventura-clang-bazel-experimental-release failure is a flake, and can be ignored. It'll automatically clear itself up after the next push.

Copy link
Member

@sherm1 sherm1 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Notation comments addressed, PTAL @jwnimmer-tri . If you can live with that, this is ready to merge.

Reviewed 2 of 2 files at r7, all commit messages.
Dismissed @mitiguy from a discussion.
Reviewable status: 2 unresolved discussions, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @mitiguy)


multibody/tree/unit_inertia.cc line 114 at r4 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

(Yes, I had grokked that l2 vs 12 was the complaint.)

I think the idea to carry forward to the future is to be suspicious when abbreviating that is ever an improvement. In most cases it's not.

OK, looking this over just now I prefer Paul's current notation because it is easier to match up with the math. To my eyes rsq looks more like r² than does radius2. r2 would be best but is precluded by the awfulness of l2 being proximal to 12!

There is an advantage to these otherwise-bad abbreviations when they match nearby math symbols. For the same reason it's nice to have the temporaries for radius * radius etc. (performance irrelevance notwithstanding) since spelling it out takes it further from the good notation.

The mix of full spelling in the API and terse spelling for the math is best IMO.


multibody/tree/unit_inertia.cc line 214 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI Sounds good -- I'll implement.

OK as is for notation match per comments above

@sherm1 sherm1 force-pushed the requireUnitVectorsForInertiaCalcs branch from 5649406 to ceab6cb Compare August 15, 2023 21:14
Copy link
Member

@sherm1 sherm1 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Wait, one comment I missed ...

Reviewable status: 2 unresolved discussions

Deprecates the previous liberal acceptance of any-length vectors.
@sherm1 sherm1 force-pushed the requireUnitVectorsForInertiaCalcs branch from ceab6cb to eeae812 Compare August 15, 2023 21:26
Copy link
Member

@sherm1 sherm1 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

OK, PTAL now. Ready to merge pending CI.

Reviewed 1 of 1 files at r8, 1 of 1 files at r9, all commit messages.
Reviewable status: 1 unresolved discussion


multibody/tree/test/unit_inertia_test.cc line 254 at r4 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

It looks like the UnitInertia.SolidCylinderAboutEnd test case got deleted by mistake in 37628e8. We should put it back, right?

Done. Good catch!

Copy link
Collaborator

@jwnimmer-tri jwnimmer-tri left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Reviewed 1 of 1 files at r8, 1 of 1 files at r9, all commit messages.
Reviewable status: :shipit: complete! all discussions resolved, LGTM from assignees jwnimmer-tri(platform),sherm1(platform)


multibody/tree/unit_inertia.cc line 114 at r4 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

OK, looking this over just now I prefer Paul's current notation because it is easier to match up with the math. To my eyes rsq looks more like r² than does radius2. r2 would be best but is precluded by the awfulness of l2 being proximal to 12!

There is an advantage to these otherwise-bad abbreviations when they match nearby math symbols. For the same reason it's nice to have the temporaries for radius * radius etc. (performance irrelevance notwithstanding) since spelling it out takes it further from the good notation.

The mix of full spelling in the API and terse spelling for the math is best IMO.

The only valid abbreviation per GSG is to truncate the tail of a word, but neither rsq nor lsq is prefix of any word. The short variable here serve only to confuse rather than clarify.

I will relent and mark myself satisfied this time only out of exhaustion. I'll not allow it next time around.

@jwnimmer-tri jwnimmer-tri merged commit 75114dc into RobotLocomotion:master Aug 15, 2023
9 of 10 checks passed
@sherm1
Copy link
Member

sherm1 commented Aug 15, 2023

multibody/tree/unit_inertia.cc line 114 at r4 (raw file):
Thanks. Next time we can argue whether this text from our styleguide applies:

Exception: Variable and method names may violate both the capitalization standard and the “long, human-readable” standard above if a short, non-compliant name more closely matches the common conventions of the field.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
priority: medium release notes: newly deprecated This pull request contains new deprecations
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

3 participants