Skip to content

[deformable] State queries for deformable bodies #23063

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

Merged
merged 1 commit into from
Jun 12, 2025

Conversation

xuchenhan-tri
Copy link
Contributor

@xuchenhan-tri xuchenhan-tri commented Jun 2, 2025

This change is Reviewable

@xuchenhan-tri xuchenhan-tri added status: do not review release notes: none This pull request should not be mentioned in the release notes labels Jun 2, 2025
Copy link
Contributor Author

@xuchenhan-tri xuchenhan-tri left a comment

Choose a reason for hiding this comment

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

+@mitiguy and +@sherm1 for feedback please. This is a very rough draft. Please pardon the abusive and vague use of terminology and notations.

Reviewable status: LGTM missing from assignees mitiguy,sherm1(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @xuchenhan-tri)

Copy link
Contributor

@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.

@xuchenhan-tri It looks good thus far (about 35% through). It might be a good time to take a look and update.

Reviewed 3 of 14 files at r1, all commit messages.
Reviewable status: LGTM missing from assignees mitiguy,sherm1(platform), commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @xuchenhan-tri)


multibody/fem/fem_model.h line 177 at r1 (raw file):

   @param[in] fem_state The FemState used to evaluate the center of mass.
   @retval com_position The 3D vector representing the center of mass position.
   @throws std::exception if the FEM state is incompatible with this model. */

FYI - Updated wording and notation, modified from:
MultibodyPlant::CalcCenterOfMassPositionInWorld()

Suggestion:

 /** Calculates the position vector from the world origin Wo to the center
   of mass of all bodies in this FemModel S, expressed in the world frame W.
   @param[in] fem_state The FemState used to evaluate the center of mass.
   @retval p_WoScm_W position vector from Wo to Scm expressed in world frame W,
   where Scm is the center of mass of the system S stored by `this` FemModel.
   @throws std::exception if the FEM state is incompatible with this model.
 Vector3<T> CalcCenterOfMassPositionInWorld(const FemState<T>& fem_state) const;

multibody/fem/fem_model.h line 187 at r1 (raw file):

                  expressed in the world frame W.
   @throws std::exception if the FEM state is incompatible with this model. */
  Vector3<T> CalcCenterOfMassLinearVelocity(const FemState<T>& fem_state) const;

FYI: Consider notation, documentation, and function names to mimic
MultibodyPlant::CalcCenterOfMassTranslationalVelocityInWorld().

Suggestion:

 
  /** Calculates system center of mass translational velocity in world frame W.
   @param[in] fem_state The FemState used for this calculation.
   @retval v_WScm_W Scm's translational velocity in frame W, expressed in W,
   where Scm is the center of mass of the system S stored by this FemModel.
   @throws std::exception if the FEM state is incompatible with this model. */
  Vector3<T> CalcCenterOfMassTranslationalVelocityInWorld(const FemState<T>& fem_state) const;

multibody/fem/fem_model.h line 206 at r1 (raw file):

   velocity of the center of mass C, measured and expressed in the world frame
   W.ncompatible with this model. */
  Vector3<T> CalcCenterOfMassAngularVelocity(

FYI -- consider slightly different text and function name.

/** Using an angular momentum analogy, calculates a "pseudo" angular velocity
for this FemModel S, measured and expressed in the world frame W.
The psudeo angular velocity is computed using an angular momentum equation
that assumes S is a rigid body (albeit we know S is deformable).

H_WSSm_W = I_SScm_W * w_WScm_W   which when solved for w_WScm_W gives
w_WScm_W = inverse(I_SScm_W) * H_WSSm_W         

H_WSSm_W is the FemModel S's angular momentum about its center of mass Scm
measured and expressed in the world frame W.
I_SScm_W is the FemModel S's rotational inertia about its center of mass Scm,
expressed in the world frame W.
w_WScm_W is the FemModel S's psuedo angular velocity for Scm, measured and
expressed in the world frame W.

@param[in] fem_state The FemState used for this calculation.
@RetVal w_WScm_W the FemModel S's psuedo angular velocity for Scm, measured
and expressed in the world frame W.
@throws std::exception if the FEM state is incompatible with this model. */
Vector3 CalcPsudeoAngularVelocityForCenterOfMass(


multibody/fem/fem_model.h line 305 at r1 (raw file):

   the NVI CalcCenterOfMassPosition(). The input `fem_state` is guaranteed to be
   compatible with `this` FEM model. */
  virtual Vector3<T> DoCalcCenterOfMassPosition(

FYI - As above, mimic with DoCalcCenterOfMassPositionInWorld()

Suggestion:

  virtual Vector3<T> DoCalcCenterOfMassPositionInWorld(

multibody/fem/fem_model.h line 311 at r1 (raw file):

   the NVI CalcCenterOfMassLinearVelocity(). The input `fem_state` is
   guaranteed to be compatible with `this` FEM model. */
  virtual Vector3<T> DoCalcCenterOfMassLinearVelocity(

FYI As above, mimic with DoCalcCenterOfMassTranslationalVelocityInWorld().

Suggestion:

 virtual Vector3<T> DoCalcCenterOfMassTranslationalVelocityInWorld(

multibody/fem/fem_model.h line 317 at r1 (raw file):

   the NVI CalcCenterOfMassAngularVelocity(). The input `fem_state` is
   guaranteed to be compatible with `this` FEM model. */
  virtual Vector3<T> DoCalcCenterOfMassAngularVelocity(

FYI As above, mimic with DoCalcPsudeoAngularVelocityForCenterOfMass().

Suggestion:

  virtual Vector3<T> DoCalcPsudeoAngularVelocityForCenterOfMass(

multibody/fem/fem_model.cc line 71 at r1 (raw file):

template <typename T>
Vector3<T> FemModel<T>::CalcCenterOfMassPosition(

FYI - As above, mimic with DoCalcCenterOfMassPositionInWorld()

Suggestion:

Vector3<T> FemModel<T>::DoCalcCenterOfMassPositionInWorld(

multibody/fem/fem_model.cc line 78 at r1 (raw file):

template <typename T>
Vector3<T> FemModel<T>::CalcCenterOfMassLinearVelocity(

FYI As above, mimic with DoCalcCenterOfMassTranslationalVelocityInWorld().

Suggestion:

Vector3<T> FemModel<T>::DoCalcCenterOfMassTranslationalVelocityInWorld(

multibody/fem/fem_model.cc line 85 at r1 (raw file):

template <typename T>
Vector3<T> FemModel<T>::CalcCenterOfMassAngularVelocity(

FYI As above, mimic with DoCalcPsudeoAngularVelocityForCenterOfMass().

Suggestion:

Vector3<T> FemModel<T>::DoCalcPsudeoAngularVelocityForCenterOfMass(

multibody/fem/fem_model_impl.h line 81 at r1 (raw file):

 private:
  Vector3<T> DoCalcCenterOfMassPosition(

FYI - As above, mimic with DoCalcCenterOfMassPositionInWorld()

Suggestion:

  Vector3<T> DoCalcCenterOfMassPositionInWorld(

multibody/fem/fem_model_impl.h line 82 at r1 (raw file):

 private:
  Vector3<T> DoCalcCenterOfMassPosition(
      const FemState<T>& fem_state) const final {

FYI -- consider putting in this comment to document the algorithm.

// p_WoScm_W = ∑ (mᵢ pᵢ) / mₛ, where mᵢ is the mass of the iᵗʰ element,
// mₛ = ∑ mᵢ is the total mass, and pᵢ is the position vector from Wo to
// the center of mass of the iᵗʰ element, expressed in the world frame W,
// and Scm is the center of mass of this FemModel S.

// Sum over all the bodies except the 0th body (which is the world body).
for (BodyIndex body_index(1); body_index < num_bodies(); ++body_index) {
const RigidBody& body = get_body(body_index);

// total_mass = ∑ mᵢ.
const T& body_mass = body.get_mass(context);
total_mass += body_mass;

// sum_mi_pi = ∑ mᵢ * pi_WoBcm_W.
const Vector3<T> pi_BoBcm_B = body.CalcCenterOfMassInBodyFrame(context);
const Vector3<T> pi_WoBcm_W = body.EvalPoseInWorld(context) * pi_BoBcm_B;
sum_mi_pi += body_mass * pi_WoBcm_W;

}


multibody/fem/fem_model_impl.h line 83 at r1 (raw file):

  Vector3<T> DoCalcCenterOfMassPosition(
      const FemState<T>& fem_state) const final {
    Vector3<T> total_moment = Vector3<T>::Zero();

FYI To mimic the calculation done in MultibodyTree, consider changing as shown below.

Suggestion:

  Vector3<T> sum_mi_pi  = Vector3<T>::Zero();

multibody/fem/fem_model_impl.h line 89 at r1 (raw file):

    for (int e = 0; e < num_elements(); ++e) {
      elements_[e].AccumulateMassAndMomentForQuadraturePoints(
          element_data[e], &total_mass, &total_moment);

FYI -- mimic as above.

Suggestion:

       element_data[e], &total_mass, &sum_mi_pi);

multibody/fem/fem_model_impl.h line 92 at r1 (raw file):

    }
    DRAKE_DEMAND(total_mass > 0.0);
    return total_moment / total_mass;

FYI -- mimic as above.

Suggestion:

 return sum_mi_pi / total_mass;

multibody/fem/fem_model_impl.h line 95 at r1 (raw file):

  }

  Vector3<T> DoCalcCenterOfMassLinearVelocity(

FYI As above, mimic with DoCalcCenterOfMassTranslationalVelocityInWorld().

Suggestion:

  Vector3<T> DoCalcCenterOfMassTranslationalVelocityInWorld(

multibody/fem/fem_model_impl.h line 99 at r1 (raw file):

    T total_mass = 0.0;
    Vector3<T> dummy_moment = Vector3<T>::Zero();
    Vector3<T> linear_momentum = Vector3<T>::Zero();

FYI -- to mimic what is done in MultibodyTree::

Suggestion:

 Vector3<T> sum_mi_vi = Vector3<T>::Zero();

multibody/fem/fem_model_impl.h line 103 at r1 (raw file):

        fem_state.template EvalElementData<Data>(element_data_index_);
    for (int e = 0; e < num_elements(); ++e) {
      elements_[e].AccumulateMassAndMomentForQuadraturePoints(

Fyi -- I wonder if accumulating mass and moment is significantly more expensive than accumulating just mass.
A different thought -- does the mass of an FemModel every change? If not, can this be stored (not recalculated)?

Suggestion:

      total_mass += elements_[e].GetMass(element_data[e]);

multibody/fem/fem_model_impl.h line 106 at r1 (raw file):

          element_data[e], &total_mass, &dummy_moment);
      elements_[e].AccumulateLinearMomentumForQuadraturePoints(
          element_data[e], &linear_momentum);

FYI -- Consider using "translational" momentum (instead of "linear").
Perhaps this change could take in a later PR?

Suggestion:

      elements_[e].AccumulateTranslationalMomentumForQuadraturePoints(
          element_data[e], &sum_mi_vi);

multibody/fem/fem_model_impl.h line 109 at r1 (raw file):

    }
    DRAKE_DEMAND(total_mass > 0.0);
    return linear_momentum / total_mass;

FYI -- using the notation as above.
Also, to mimic documentation as done in MultibodyTree::CalcCenterOfMassTranslationalVelocityInWorld)

// For a system S with center of mass Scm, Scm's translational velocity in the
// world frame W is calculated as v_WScm_W = ∑ (mᵢ vᵢ) / mₛ, where mₛ = ∑ mᵢ,
// mᵢ is the mass of the iᵗʰ element, and vᵢ is the velocity of the center of mass
// of the ith element in the world frame W.

Suggestion:

  return sum_mi_vi / total_mass;

multibody/fem/fem_model_impl.h line 112 at r1 (raw file):

  }

  Vector3<T> DoCalcCenterOfMassAngularVelocity(

FYI As above, mimic with DoCalcPsudeoAngularVelocityForCenterOfMass().

Suggestion:

  Vector3<T> DoCalcPsudeoAngularVelocityForCenterOfMass(

multibody/fem/fem_model_impl.h line 116 at r1 (raw file):

    T total_mass = 0.0;
    Vector3<T> total_moment = Vector3<T>::Zero();
    Vector3<T> total_linear_momentum = Vector3<T>::Zero();

FYI -- as above, and please use this sums again below.

Suggestion:

    Vector3<T> sum_mi_pi = Vector3<T>::Zero();
    Vector3<T> sum_mi_pi = Vector3<T>::Zero();

multibody/fem/fem_model_impl.h line 120 at r1 (raw file):

    const std::vector<Data>& element_data =
        fem_state.template EvalElementData<Data>(element_data_index_);
    // First pass: Calculate total mass, CoM position, and CoM linear velocity.

FYI Change CoM to CM

Suggestion:

    // First pass: Calculate total mass, CM position, and CM linear velocity.

multibody/fem/fem_model_impl.h line 130 at r1 (raw file):

    const Vector3<T> p_WCcm = total_moment / total_mass;
    const Vector3<T> v_WCcm = total_linear_momentum / total_mass;

FYI -- I do not think we need to do two passes.
If desirable, we can calculate the angular momentum of the system about the world origin and then do a single calculation to shift it to Scm. Similar for the rotational inertia.


multibody/fem/fem_model_impl.h line 139 at r1 (raw file):

              element_data[e], p_WCcm, v_WCcm, &H_WCcm_total, &I_W_Ccm_total);
    }
    return I_W_Ccm_total.ldlt().solve(H_WCcm_total);

FYI -- if convenient for now, all good.
A few notational updates below.

Suggestion:

    Vector3<T> H_WSScm_W_total = Vector3<T>::Zero();
    Matrix3<T> I_SScm_W_total = Matrix3<T>::Zero();
    for (int e = 0; e < num_elements(); ++e) {
      elements_[e]
          .AccumulateAngularMomentumAndInertiaAboutCoMForQuadraturePoints(
              element_data[e], p_WCcm, v_WCcm, &H_WSScm_W_total , &I_SScm_W_total);
    }
    return I_SScm_W_total_total.ldlt().solve(H_WSScm_W_total);

Copy link
Contributor Author

@xuchenhan-tri xuchenhan-tri left a comment

Choose a reason for hiding this comment

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

-@sherm1 I meant to just mention you (not to assign you). Apologies for the confusion.
+@mitiguy thanks for the detailed review. Since you are already providing a in-depth feature review, I'll make that official here.
-(status: do not review)

I addressed a subset of the existing comments. We can discuss the rest f2f tomorrow.

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


multibody/fem/fem_model.h line 177 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI - Updated wording and notation, modified from:
MultibodyPlant::CalcCenterOfMassPositionInWorld()

Done


multibody/fem/fem_model.h line 187 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI: Consider notation, documentation, and function names to mimic
MultibodyPlant::CalcCenterOfMassTranslationalVelocityInWorld().

Done


multibody/fem/fem_model.h line 206 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- consider slightly different text and function name.

/** Using an angular momentum analogy, calculates a "pseudo" angular velocity
for this FemModel S, measured and expressed in the world frame W.
The psudeo angular velocity is computed using an angular momentum equation
that assumes S is a rigid body (albeit we know S is deformable).

H_WSSm_W = I_SScm_W * w_WScm_W   which when solved for w_WScm_W gives
w_WScm_W = inverse(I_SScm_W) * H_WSSm_W         

H_WSSm_W is the FemModel S's angular momentum about its center of mass Scm
measured and expressed in the world frame W.
I_SScm_W is the FemModel S's rotational inertia about its center of mass Scm,
expressed in the world frame W.
w_WScm_W is the FemModel S's psuedo angular velocity for Scm, measured and
expressed in the world frame W.

@param[in] fem_state The FemState used for this calculation.
@RetVal w_WScm_W the FemModel S's psuedo angular velocity for Scm, measured
and expressed in the world frame W.
@throws std::exception if the FEM state is incompatible with this model. */
Vector3 CalcPsudeoAngularVelocityForCenterOfMass(

Let's discuss this f2f.


multibody/fem/fem_model.h line 305 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI - As above, mimic with DoCalcCenterOfMassPositionInWorld()

Done


multibody/fem/fem_model.h line 311 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI As above, mimic with DoCalcCenterOfMassTranslationalVelocityInWorld().

Done


multibody/fem/fem_model.cc line 71 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI - As above, mimic with DoCalcCenterOfMassPositionInWorld()

Done


multibody/fem/fem_model.cc line 78 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI As above, mimic with DoCalcCenterOfMassTranslationalVelocityInWorld().

Done


multibody/fem/fem_model_impl.h line 81 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI - As above, mimic with DoCalcCenterOfMassPositionInWorld()

Done


multibody/fem/fem_model_impl.h line 82 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- consider putting in this comment to document the algorithm.

// p_WoScm_W = ∑ (mᵢ pᵢ) / mₛ, where mᵢ is the mass of the iᵗʰ element,
// mₛ = ∑ mᵢ is the total mass, and pᵢ is the position vector from Wo to
// the center of mass of the iᵗʰ element, expressed in the world frame W,
// and Scm is the center of mass of this FemModel S.

// Sum over all the bodies except the 0th body (which is the world body).
for (BodyIndex body_index(1); body_index < num_bodies(); ++body_index) {
const RigidBody& body = get_body(body_index);

// total_mass = ∑ mᵢ.
const T& body_mass = body.get_mass(context);
total_mass += body_mass;

// sum_mi_pi = ∑ mᵢ * pi_WoBcm_W.
const Vector3<T> pi_BoBcm_B = body.CalcCenterOfMassInBodyFrame(context);
const Vector3<T> pi_WoBcm_W = body.EvalPoseInWorld(context) * pi_BoBcm_B;
sum_mi_pi += body_mass * pi_WoBcm_W;

}

Done (with slight modification)


multibody/fem/fem_model_impl.h line 83 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI To mimic the calculation done in MultibodyTree, consider changing as shown below.

Done


multibody/fem/fem_model_impl.h line 89 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- mimic as above.

Done


multibody/fem/fem_model_impl.h line 92 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- mimic as above.

Done


multibody/fem/fem_model_impl.h line 95 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI As above, mimic with DoCalcCenterOfMassTranslationalVelocityInWorld().

Done


multibody/fem/fem_model_impl.h line 99 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- to mimic what is done in MultibodyTree::

Done


multibody/fem/fem_model_impl.h line 103 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

Fyi -- I wonder if accumulating mass and moment is significantly more expensive than accumulating just mass.
A different thought -- does the mass of an FemModel every change? If not, can this be stored (not recalculated)?

Working.

You are correct. The mass can be precomputed.


multibody/fem/fem_model_impl.h line 106 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- Consider using "translational" momentum (instead of "linear").
Perhaps this change could take in a later PR?

Done


multibody/fem/fem_model_impl.h line 109 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- using the notation as above.
Also, to mimic documentation as done in MultibodyTree::CalcCenterOfMassTranslationalVelocityInWorld)

// For a system S with center of mass Scm, Scm's translational velocity in the
// world frame W is calculated as v_WScm_W = ∑ (mᵢ vᵢ) / mₛ, where mₛ = ∑ mᵢ,
// mᵢ is the mass of the iᵗʰ element, and vᵢ is the velocity of the center of mass
// of the ith element in the world frame W.

Done


multibody/fem/fem_model_impl.h line 120 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI Change CoM to CM

Done


multibody/fem/fem_model_impl.h line 130 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- I do not think we need to do two passes.
If desirable, we can calculate the angular momentum of the system about the world origin and then do a single calculation to shift it to Scm. Similar for the rotational inertia.

Working

Like we discussed in the f2f, it's probably desirable to compute the angular velocity about the world origin instead?


multibody/fem/fem_model_impl.h line 139 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- if convenient for now, all good.
A few notational updates below.

Done

Copy link
Contributor

@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.

Checking in changes. I'll be back in contact tomorrow.

Reviewed 3 of 8 files at r2, all commit messages.
Reviewable status: 4 unresolved discussions, LGTM missing from assignee mitiguy, needs platform reviewer assigned, needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @xuchenhan-tri)


multibody/fem/fem_model.h line 206 at r1 (raw file):

Previously, xuchenhan-tri wrote…

Let's discuss this f2f.

More to discuss. Perhaps implement the comment, and we'll converge later on a function name.


multibody/fem/fem_model_impl.h line 103 at r1 (raw file):

Previously, xuchenhan-tri wrote…

Working.

You are correct. The mass can be precomputed.

Will this be done in a subsequent PR -- or not needed.


multibody/fem/fem_model_impl.h line 130 at r1 (raw file):

Previously, xuchenhan-tri wrote…

Working

Like we discussed in the f2f, it's probably desirable to compute the angular velocity about the world origin instead?

Yes -- and then do a shift after those calculations have concluded, back to Scm.
For example, this is a one-time calculation after the for-loop is concluded.

For example, the angular momentum "shift theorem" gives:
H_WSScm_W = H_WSWo_W + Cross( p_ScmWo_W, m_total * v_WScm_W ), where
H_WSScm_W is the FemModel S's angular momentum in world W about Scm, expressed in W.
H_WSWo_W is the FemModel S's angular momentum in world W about Wo, expressed in W.
p_ScmWo_W is the position vector from Scm to Wo, expressed in W.
v_WScm_W is the translational velocity of Scm in world W, expressed in W.

There is a different shift theorem to shift I_SWo_W to I_SScm_W.
(documented in RotationalInertia.h ? -- if not, I'll type it in), where
I_SWo_W is the FemModel S's rotational inertia about Wo, expressed in W.
I_SScm_W is the FemModel S's rotational inertia about Scm, expressed in W.

Thereafter, you are returning (as done in your code already).
return I_SScm_W_total.ldlt().solve(H_WSScm_W_total);


multibody/fem/fem_model_impl.h line 84 at r2 (raw file):

      const FemState<T>& fem_state) const final {
    /* p_WoScm_W = ∑ (mᵢ pᵢ) / mₛ, where mᵢ is the mass of the iᵗʰ element,
     mₛ = ∑ mᵢ is the total mass,  and pᵢ is the position vector from Wo to

Self-blocking. Paul -- improve suggested comment based on f2f with Xuchen.


multibody/fem/fem_model_impl.h line 103 at r2 (raw file):

    /* For a system S with center of mass Scm, Scm's translational velocity in
     the world frame W is calculated as v_WScm_W = ∑ (mᵢ vᵢ) / mₛ, where mₛ = ∑
     mᵢ, mᵢ is the mass of the iᵗʰ element, and vᵢ is the velocity evaluated at

Paul -- self blocking. Provide updated suggested documentation based on quadrature point conversation with Xuchen.

Copy link
Contributor Author

@xuchenhan-tri xuchenhan-tri left a comment

Choose a reason for hiding this comment

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

I pushed a new revision to address all existing comments. PTAL.

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


multibody/fem/fem_model.h line 206 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

More to discuss. Perhaps implement the comment, and we'll converge later on a function name.

Done (I modified the comment, but not the name just yet).


multibody/fem/fem_model.h line 317 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI As above, mimic with DoCalcPsudeoAngularVelocityForCenterOfMass().

Done (dropping Pseudo).


multibody/fem/fem_model.cc line 85 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI As above, mimic with DoCalcPsudeoAngularVelocityForCenterOfMass().

Done (dropping Pseudo).


multibody/fem/fem_model_impl.h line 103 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

Will this be done in a subsequent PR -- or not needed.

Done

We usually use the "working" status to indicate that "I see your point, I'll push some changes to this PR to address your comment, but I haven't got around to do it yet".


multibody/fem/fem_model_impl.h line 112 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI As above, mimic with DoCalcPsudeoAngularVelocityForCenterOfMass().

Done (dropping the word Pseudo).


multibody/fem/fem_model_impl.h line 116 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- as above, and please use this sums again below.

Done


multibody/fem/fem_model_impl.h line 130 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

Yes -- and then do a shift after those calculations have concluded, back to Scm.
For example, this is a one-time calculation after the for-loop is concluded.

For example, the angular momentum "shift theorem" gives:
H_WSScm_W = H_WSWo_W + Cross( p_ScmWo_W, m_total * v_WScm_W ), where
H_WSScm_W is the FemModel S's angular momentum in world W about Scm, expressed in W.
H_WSWo_W is the FemModel S's angular momentum in world W about Wo, expressed in W.
p_ScmWo_W is the position vector from Scm to Wo, expressed in W.
v_WScm_W is the translational velocity of Scm in world W, expressed in W.

There is a different shift theorem to shift I_SWo_W to I_SScm_W.
(documented in RotationalInertia.h ? -- if not, I'll type it in), where
I_SWo_W is the FemModel S's rotational inertia about Wo, expressed in W.
I_SScm_W is the FemModel S's rotational inertia about Scm, expressed in W.

Thereafter, you are returning (as done in your code already).
return I_SScm_W_total.ldlt().solve(H_WSScm_W_total);

Done

Copy link
Contributor

@amcastro-tri amcastro-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: 3 unresolved discussions, LGTM missing from assignee mitiguy, needs platform reviewer assigned, needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @xuchenhan-tri)


multibody/tree/deformable_body.h line 243 at r3 (raw file):

   @throws std::exception if `context` does not belong to the MultibodyPlant
   that owns this body. */
  Vector3<T> GetAngularVelocityAboutCom(

per f2f, my suggestion would be to name this something like "CalcEffectiveAngularVelocity()" (I'd leave out the about CoM since usually for rigid bodies that is not relevant and we don't even have monogram notation for that) so that when a user sees that, they'd go "what does effective mean"? and they go and read the docs in detail.

Copy link
Contributor

@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.

Reviewed 4 of 9 files at r3, all commit messages.
Reviewable status: 1 unresolved discussion, LGTM missing from assignee mitiguy, needs platform reviewer assigned, needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @xuchenhan-tri)


multibody/fem/fem_model.h line 206 at r1 (raw file):

Previously, xuchenhan-tri wrote…

Done (I modified the comment, but not the name just yet).

I like Alejandro's suggestion of something like "CalcEffectiveAngularVelocity()" so that when a user sees that, they'd go "what does Effective mean"? and they go and read the docs in detail. @amcastro-tri Another reasonable possibility is something like "CalcDeformableAngularVelocity()". Regardless, some qualifier is helpful.


multibody/fem/fem_model.h line 317 at r1 (raw file):

Previously, xuchenhan-tri wrote…

Done (dropping Pseudo).

Consider "CalcEffectiveAngularVelocity()" or "CalcDeformableAngularVelocity()" or similar, here and elsewhere.


multibody/fem/fem_model.cc line 85 at r1 (raw file):

Previously, xuchenhan-tri wrote…

Done (dropping Pseudo).

Consider "CalcEffectiveAngularVelocity()" or "CalcDeformableAngularVelocity()" or similar, here and elsewhere.


multibody/fem/fem_model_impl.h line 112 at r1 (raw file):

Previously, xuchenhan-tri wrote…

Done (dropping the word Pseudo).

Consider "CalcEffectiveAngularVelocity()" or "CalcDeformableAngularVelocity()" or similar, here and elsewhere.


multibody/fem/fem_model_impl.h line 128 at r3 (raw file):

    // First pass: Calculate CM position and CM linear velocity.
    for (int e = 0; e < num_elements(); ++e) {
      sum_mi_pi += elements_[e].CalcMomentForQuadraturePoints(element_data[e]);

FYI Due to the mathematical underpinnings, the word "moment" is so overused in mechanics, e.g., moment of inertia, moment of a force moment of area, ... To be more explicit, consider
CalcMassTimesPositionForQuadraturePoints( element_data[e] );
Consider "CalcEffectiveAngularVelocity()" or "CalcDeformableAngularVelocity()" or similar, here and elsewhere.


multibody/fem/fem_model_impl.h line 128 at r3 (raw file):

    // First pass: Calculate CM position and CM linear velocity.
    for (int e = 0; e < num_elements(); ++e) {
      sum_mi_pi += elements_[e].CalcMomentForQuadraturePoints(element_data[e]);

FYI Due to the mathematical underpinnings, the word "moment" is so overused in mechanics, e.g., moment of inertia, moment of a force moment of area, ... Consider being more explicit, e.g., as shown below.

Suggestion:

     sum_mi_pi += elements_[e].CalcMassTimesPositionForQuadraturePoints(element_data[e]);

multibody/fem/fem_model_impl.h line 138 at r3 (raw file):

    const Vector3<T> p_WoScm_W = sum_mi_pi / total_mass;
    const Vector3<T> v_WScm_W = sum_mi_vi / total_mass;
    /* Convert angular momentum from world origin to center of mass

FYI -- the word "Convert" is ambiguous. Please use "Shift".

Suggestion:

    /* Shift angular momentum from world origin to center of mass

multibody/fem/fem_model_impl.h line 145 at r3 (raw file):

    /* Convert inertia from world origin to center of mass using parallel axis
     theorem
       I_Scm = I_O - m(p_WoScm·p_WoScm)I + m(p_WoScm⊗p_WoScm). */

FYI -- The word "Convert" is not specific enough and the underlying theorems for both angular momentum and inertia are frequently called "Shift" theorems. The "parallel axis theorem" was named for shifting moments of inertia, albeit folks can interpret the intent.

Suggestion:

    /* Shift inertia from world origin to center of mass using the "parallel
     axis theorem" below, with I₃₃ is the 3x3 identity matrix.
       I_SScm = I_SWO - m(p_WoScm · p_WoScm) I₃₃ + m(p_WoScm ⊗ p_WoScm). */

multibody/fem/volumetric_element.h line 227 at r3 (raw file):

    return elastic_energy;
  }

Self-blocking. Restart here.

Copy link
Contributor Author

@xuchenhan-tri xuchenhan-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: 1 unresolved discussion, LGTM missing from assignee mitiguy, needs platform reviewer assigned, needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)


multibody/fem/fem_model.h line 206 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

I like Alejandro's suggestion of something like "CalcEffectiveAngularVelocity()" so that when a user sees that, they'd go "what does Effective mean"? and they go and read the docs in detail. @amcastro-tri Another reasonable possibility is something like "CalcDeformableAngularVelocity()". Regardless, some qualifier is helpful.

Done


multibody/fem/fem_model.h line 317 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

Consider "CalcEffectiveAngularVelocity()" or "CalcDeformableAngularVelocity()" or similar, here and elsewhere.

Done


multibody/fem/fem_model.cc line 85 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

Consider "CalcEffectiveAngularVelocity()" or "CalcDeformableAngularVelocity()" or similar, here and elsewhere.

Done


multibody/fem/fem_model_impl.h line 112 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

Consider "CalcEffectiveAngularVelocity()" or "CalcDeformableAngularVelocity()" or similar, here and elsewhere.

Done


multibody/fem/fem_model_impl.h line 128 at r3 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI Due to the mathematical underpinnings, the word "moment" is so overused in mechanics, e.g., moment of inertia, moment of a force moment of area, ... To be more explicit, consider
CalcMassTimesPositionForQuadraturePoints( element_data[e] );
Consider "CalcEffectiveAngularVelocity()" or "CalcDeformableAngularVelocity()" or similar, here and elsewhere.

Done


multibody/fem/fem_model_impl.h line 128 at r3 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI Due to the mathematical underpinnings, the word "moment" is so overused in mechanics, e.g., moment of inertia, moment of a force moment of area, ... Consider being more explicit, e.g., as shown below.

Done


multibody/fem/fem_model_impl.h line 138 at r3 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- the word "Convert" is ambiguous. Please use "Shift".

Done


multibody/fem/fem_model_impl.h line 145 at r3 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- The word "Convert" is not specific enough and the underlying theorems for both angular momentum and inertia are frequently called "Shift" theorems. The "parallel axis theorem" was named for shifting moments of inertia, albeit folks can interpret the intent.

Done


multibody/tree/deformable_body.h line 243 at r3 (raw file):

Previously, amcastro-tri (Alejandro Castro) wrote…

per f2f, my suggestion would be to name this something like "CalcEffectiveAngularVelocity()" (I'd leave out the about CoM since usually for rigid bodies that is not relevant and we don't even have monogram notation for that) so that when a user sees that, they'd go "what does effective mean"? and they go and read the docs in detail.

Done

Copy link
Contributor

@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.

Reviewed 5 of 14 files at r1, 1 of 8 files at r2, 1 of 9 files at r3, 8 of 9 files at r4, all commit messages.
Reviewable status: 5 unresolved discussions, LGTM missing from assignee mitiguy, needs platform reviewer assigned, needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @xuchenhan-tri)


multibody/fem/fem_model.h line 206 at r1 (raw file):

Previously, xuchenhan-tri wrote…

Done

Note: I think Alejandro's suggestion (below) was CalcEffectiveAngularVelocity() instead of CalcEffectiveAngularVelocityForCenterOfMass(). Let's ask @sherm1 to weigh in here on names.

"per f2f, my suggestion would be to name this something like "CalcEffectiveAngularVelocity()" (I'd leave out the about CoM since usually for rigid bodies that is not relevant and we don't even have monogram notation for that) so that when a user sees that, they'd go "what does effective mean"? and they go and read the docs in detail."


multibody/tree/test/deformable_body_test.cc line 134 at r4 (raw file):

  EXPECT_TRUE(CompareMatrices(com, Vector3d::Zero(), kEpsilon));

  /* Move the sphere and check CoM. */

FYI -- to help with standard notation below.

Suggestion:

  /* Move the sphere center So to a new location and check CoM. */

multibody/tree/test/deformable_body_test.cc line 136 at r4 (raw file):

  /* Move the sphere and check CoM. */
  Matrix3X<double> q = body_->GetPositions(*plant_context_);
  const Vector3d translation(1.0, 2.0, 3.0);

FYI -- consider using standard notation.

Suggestion:

  const Vector3d p_WoSo_W(1.0, 2.0, 3.0);

multibody/tree/test/deformable_body_test.cc line 150 at r4 (raw file):

  const Vector3d com_translated =
      body_->CalcCenterOfMassPositionInWorld(*plant_context_);
  EXPECT_TRUE(CompareMatrices(com_translated, translation, kEpsilon));

FYI -- as alove

Suggestion:

  EXPECT_TRUE(CompareMatrices(com_translated, p_WoSo_W, kEpsilon));

multibody/tree/test/deformable_body_test.cc line 216 at r4 (raw file):

  body_->SetPositions(plant_context_, q_matrix);
  /* Set v to be a uniform angular velocity about axis through (1, 0, 0) and
   parallel to the z-axis. */

I do not understand this part of the code yet. How does setting the position p_WQ cause there to be some kind of velocity. We can talk f2f tomorrow.


multibody/tree/test/deformable_body_test.cc line 224 at r4 (raw file):

  plant_context_->SetDiscreteState(body_->discrete_state_index(),
                                   discrete_state);
  const Vector3d w_WC =

To ensure I fully understand this notation, please make it fully explicit, e.g., w_WC_W? However, I am unsure what is meant by C? Is that the same as the set S of points associated with this deformable body. I am assuming this is expressed in world W. If it is S, we could call it S instead of C, but either way, some introduction would help tons.


multibody/tree/test/deformable_body_test.cc line 226 at r4 (raw file):

  const Vector3d w_WC =
      body_->CalcEffectiveAngularVelocityForCenterOfMass(*plant_context_);
  EXPECT_TRUE(CompareMatrices(w_WC, Vector3d(0.0, 0.0, 1.0), kEpsilon));

FYI -- Xuchen -- this is an interesting calculation and I think it should converge for a rigid body. It would be good to do more extensive testing. I am happy to help.


multibody/fem/test/dummy_element.h line 105 at r4 (raw file):

  /* Arbitrary values for testing. Returns the moment for this element.
   @returns The moment of this element. */

Please add more explicit wording.
Add language to make "moment" more explicit and provide an "about point" and an expressed-in frame.
Important: The language below is my guess at what is meant.

Suggestion:

  /* Arbitrary values for testing.  For this element's quadrature points, returns the
    first moment of mass (mass * position) about World origin, expressed in World. */

multibody/fem/test/dummy_element.h line 113 at r4 (raw file):

  /* Arbitrary values for testing. Returns the translational momentum for this
   element.
   @returns The translational momentum for this element. */

FYI -- more explicit, less repetitive.
Important: Language below is my guess at what is meant.

Suggestion:

  /* Arbitrary values for testing. Returns this element's translational momentum
   measured and expressed in World */

multibody/fem/test/dummy_element.h line 131 at r4 (raw file):

   @returns The rotational inertia tensor about the world origin, expressed in
            the world frame. */
  Matrix3<T> CalcInertiaAboutWorldOrigin(const Data& /*data*/) const {

FYI -- more explicit, less repetitive.
Important: Language below is my guess at what is meant.

Suggestion:

  /* Arbitrary values for testing. Returns this element's rotational inertia
     about world origin, expressed in the world frame. */
  Matrix3<T> CalcRotationalInertiaAboutWorldOrigin(const Data& /*data*/) const {

multibody/fem/volumetric_element.h line 230 at r4 (raw file):

  /* Returns the moment for the quadrature points in this element.
   @param[in] data The FEM data containing quadrature point positions.
   @returns The moment of this element (mass * position). */

Please add more explicit wording.
Add language to make "moment" more explicit and provide an "about point" and an expressed-in frame.
Important: The language below is my guess at what is meant.

Suggestion:

  /* For this element's quadrature points, returns the first moment of
    mass (mass * position) about World origin, expressed in World.
   @param[in] data The FEM data containing quadrature point positions. */

multibody/fem/volumetric_element.h line 234 at r4 (raw file):

    Vector3<T> element_moment = Vector3<T>::Zero();
    for (int q = 0; q < num_quadrature_points; ++q) {
      const T quadrature_point_mass = density_ * reference_volume_[q];

FYI -- To speed calculations, is is possible to store the quadrature_point_mass for each element or does deformability negate this possibility?


multibody/fem/volumetric_element.h line 247 at r4 (raw file):

    Vector3<T> element_translational_momentum = Vector3<T>::Zero();
    for (int q = 0; q < num_quadrature_points; ++q) {
      const T quadrature_point_mass = density_ * reference_volume_[q];

FYI -- It seems this quadrature_point_mass is calculated multiple times. Is this storable?


multibody/fem/volumetric_element.h line 258 at r4 (raw file):

                   velocities.
   @returns The angular momentum about the world origin, expressed in the world
            frame. */

FYI -- consider more explicit, less repetitive.

Suggestion:

  /* Returns this element S's angular momentum about world origin, measured
     and expressed in World.
   @param[in] data The FEM data containing quadrature point positions and
                   velocities. */

multibody/fem/volumetric_element.h line 260 at r4 (raw file):

            frame. */
  Vector3<T> CalcAngularMomentumAboutWorldOrigin(const Data& data) const {
    Vector3<T> H_WO = Vector3<T>::Zero();

FYI -- Consider more explicit.

Suggestion:

    Vector3<T> H_SWWo_W = Vector3<T>::Zero();

multibody/fem/volumetric_element.h line 262 at r4 (raw file):

    Vector3<T> H_WO = Vector3<T>::Zero();
    for (int q = 0; q < num_quadrature_points; ++q) {
      const T quadrature_point_mass = density_ * reference_volume_[q];

FYI -- Hmmm. 3rd calculation of this? There is a 4th one in CalcInertiaAboutWorldOrigin().


multibody/fem/volumetric_element.h line 264 at r4 (raw file):

      const T quadrature_point_mass = density_ * reference_volume_[q];
      const Vector3<T>& p_Wqp = data.quadrature_positions[q];
      const Vector3<T>& v_Wqp = data.quadrature_velocities[q];

FYI I do not understand this notation yet. If p_Wqp is the position from Wo (World origin) to a quadrature point P, expressed in the world frame, the shorthand notation would be p_WP, or the fully explicit would be p_WoP_W. I might guess that qp is a quadrature point, but why qp is needed in place of P? Does it have to do with something specific to this class?

Suggestion:

      const Vector3<T>& p_WP = data.quadrature_positions[q];
      const Vector3<T>& v_WP = data.quadrature_velocities[q];

multibody/fem/volumetric_element.h line 266 at r4 (raw file):

      const Vector3<T>& v_Wqp = data.quadrature_velocities[q];

      H_WO += p_Wqp.cross(v_Wqp * quadrature_point_mass);

FYI -- Consider more explicit.

Suggestion:

 H_SWWo_W += p_WP.cross(v_WP * quadrature_point_mass);

multibody/fem/volumetric_element.h line 276 at r4 (raw file):

   @returns The rotational inertia tensor about the world origin, expressed in
            the world frame. */
  Matrix3<T> CalcInertiaAboutWorldOrigin(const Data& data) const {

FYI -- consider more explicit, less repetitive.

Suggestion:

  /* Returns this element's rotational inertia about world origin, expressed in World.
   @param[in] data The FEM data containing quadrature point positions. */
  Matrix3<T> CalcRotationalInertiaAboutWorldOrigin(const Data& data) const {

multibody/fem/volumetric_element.h line 277 at r4 (raw file):

            the world frame. */
  Matrix3<T> CalcInertiaAboutWorldOrigin(const Data& data) const {
    Matrix3<T> I_W_O = Matrix3<T>::Zero();

Notation needs update.

Suggestion:

    // Rotational inertia for this element S, about Wo, expressed in W.
    Matrix3<T> I_SWo_W = Matrix3<T>::Zero();  

multibody/fem/test/volumetric_element_test.cc line 507 at r4 (raw file):

      element().CalcAngularMomentumAboutWorldOrigin(data);

  const Vector3<AD> p_WQ = data.quadrature_positions[0];

FYI -- Here you are using Q as the name of a quadrature point.
I like that in place of the name qp which is used in
VolumetricElement::Vector3 CalcAngularMomentumAboutWorldOrigin(const Data& data)


multibody/fem/test/volumetric_element_test.cc line 516 at r4 (raw file):

}

TEST_F(VolumetricElementTest, CalcInertiaAboutWorldOrigin) {

FYI RotationalInertia?

Suggestion:

TEST_F(VolumetricElementTest, CalcRotationalInertiaAboutWorldOrigin) {

multibody/fem/test/volumetric_element_test.cc line 520 at r4 (raw file):

  const auto& data = EvalElementData(*fem_state);

  Matrix3<AD> inertia = element().CalcInertiaAboutWorldOrigin(data);

FYI RotationalInertia? Also, I like the use of the quadrature point Q.

Suggestion:

  Matrix3<AD> inertia = element().CalcRotationalInertiaAboutWorldOrigin(data);

Copy link
Contributor Author

@xuchenhan-tri xuchenhan-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: 5 unresolved discussions, LGTM missing from assignee mitiguy, needs platform reviewer assigned, needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @xuchenhan-tri)


multibody/fem/fem_model.h line 206 at r1 (raw file):

Previously, mitiguy (Mitiguy) wrote…

Note: I think Alejandro's suggestion (below) was CalcEffectiveAngularVelocity() instead of CalcEffectiveAngularVelocityForCenterOfMass(). Let's ask @sherm1 to weigh in here on names.

"per f2f, my suggestion would be to name this something like "CalcEffectiveAngularVelocity()" (I'd leave out the about CoM since usually for rigid bodies that is not relevant and we don't even have monogram notation for that) so that when a user sees that, they'd go "what does effective mean"? and they go and read the docs in detail."

I misread that. Now done.


multibody/fem/volumetric_element.h line 230 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

Please add more explicit wording.
Add language to make "moment" more explicit and provide an "about point" and an expressed-in frame.
Important: The language below is my guess at what is meant.

Done


multibody/fem/volumetric_element.h line 234 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- To speed calculations, is is possible to store the quadrature_point_mass for each element or does deformability negate this possibility?

Done


multibody/fem/volumetric_element.h line 247 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- It seems this quadrature_point_mass is calculated multiple times. Is this storable?

Done


multibody/fem/volumetric_element.h line 258 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- consider more explicit, less repetitive.

Done


multibody/fem/volumetric_element.h line 260 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- Consider more explicit.

Done


multibody/fem/volumetric_element.h line 262 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- Hmmm. 3rd calculation of this? There is a 4th one in CalcInertiaAboutWorldOrigin().

Done


multibody/fem/volumetric_element.h line 264 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI I do not understand this notation yet. If p_Wqp is the position from Wo (World origin) to a quadrature point P, expressed in the world frame, the shorthand notation would be p_WP, or the fully explicit would be p_WoP_W. I might guess that qp is a quadrature point, but why qp is needed in place of P? Does it have to do with something specific to this class?

Done


multibody/fem/volumetric_element.h line 266 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- Consider more explicit.

Done


multibody/fem/volumetric_element.h line 276 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- consider more explicit, less repetitive.

Done


multibody/fem/volumetric_element.h line 277 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

Notation needs update.

Done


multibody/fem/test/dummy_element.h line 105 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

Please add more explicit wording.
Add language to make "moment" more explicit and provide an "about point" and an expressed-in frame.
Important: The language below is my guess at what is meant.

Done.

This is just an arbitrary non-sense value for compiling. Same below.


multibody/fem/test/dummy_element.h line 113 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- more explicit, less repetitive.
Important: Language below is my guess at what is meant.

Done


multibody/fem/test/dummy_element.h line 131 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- more explicit, less repetitive.
Important: Language below is my guess at what is meant.

Done


multibody/fem/test/volumetric_element_test.cc line 516 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI RotationalInertia?

Done


multibody/fem/test/volumetric_element_test.cc line 520 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI RotationalInertia? Also, I like the use of the quadrature point Q.

Done


multibody/tree/test/deformable_body_test.cc line 134 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- to help with standard notation below.

Done


multibody/tree/test/deformable_body_test.cc line 136 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- consider using standard notation.

Done


multibody/tree/test/deformable_body_test.cc line 150 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- as alove

Done


multibody/tree/test/deformable_body_test.cc line 216 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

I do not understand this part of the code yet. How does setting the position p_WQ cause there to be some kind of velocity. We can talk f2f tomorrow.

This is not setting the position p_WQ. Instead, it's setting the velocity as a function of p_WQ.


multibody/tree/test/deformable_body_test.cc line 224 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

To ensure I fully understand this notation, please make it fully explicit, e.g., w_WC_W? However, I am unsure what is meant by C? Is that the same as the set S of points associated with this deformable body. I am assuming this is expressed in world W. If it is S, we could call it S instead of C, but either way, some introduction would help tons.

Done. I modified the variable name and added some comments.


multibody/tree/test/deformable_body_test.cc line 226 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

FYI -- Xuchen -- this is an interesting calculation and I think it should converge for a rigid body. It would be good to do more extensive testing. I am happy to help.

Yes, that would be nice for a follow up PR. Right now though, this PR is blocking progress on setting up deformable scene for LBM, so I'd like to explore that later.

Copy link
Contributor

@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.

Nearing the finish line. Requesting a small iteration to CalcEffectiveAngularVelocity() tests in deformable_body_test.cc
TEST_F(DeformableBodyTest, CalcEffectiveAngularVelocity).

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


multibody/fem/volumetric_element.h line 264 at r4 (raw file):

Previously, xuchenhan-tri wrote…

Done

Note: In a volumetric_element_tests.cc, you use Q for a quadrature point. I thought that was a clever use of notation, alliteration , and language. The change to P is good. Q may even be better. Kaizen.


multibody/tree/test/deformable_body_test.cc line 224 at r4 (raw file):

Previously, xuchenhan-tri wrote…

Done. I modified the variable name and added some comments.

I think we can converge on this quickly today and it is one of the last remaining things for this PR. Perhaps you might have time to do it together at your computer?


multibody/tree/test/deformable_body_test.cc line 226 at r4 (raw file):

Previously, xuchenhan-tri wrote…

Yes, that would be nice for a follow up PR. Right now though, this PR is blocking progress on setting up deformable scene for LBM, so I'd like to explore that later.

OK -- per f2f2, let's do the zero angular velocity degenerate case and then move on. If more testing is needed later, great. If not, it seems this will be sufficient.


multibody/tree/test/deformable_body_test.cc line 200 at r5 (raw file):

  constexpr double kEpsilon = 1e-14;
  /* Set a uniform rotational velocity about the world origin. */
  /* Set q to be a sphere centered at (1, 0, 0). */

It would help to better understand what is meant by q and what is happening in this function.

Copy link
Contributor Author

@xuchenhan-tri xuchenhan-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: 3 unresolved discussions, LGTM missing from assignee mitiguy, needs platform reviewer assigned, needs at least two assigned reviewers, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits)


multibody/fem/volumetric_element.h line 264 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

Note: In a volumetric_element_tests.cc, you use Q for a quadrature point. I thought that was a clever use of notation, alliteration , and language. The change to P is good. Q may even be better. Kaizen.

Done


multibody/tree/test/deformable_body_test.cc line 226 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

OK -- per f2f2, let's do the zero angular velocity degenerate case and then move on. If more testing is needed later, great. If not, it seems this will be sufficient.

Done, I added the zero angular velocity test.


multibody/tree/test/deformable_body_test.cc line 200 at r5 (raw file):

Previously, mitiguy (Mitiguy) wrote…

It would help to better understand what is meant by q and what is happening in this function.

Done, PTAL.

Copy link
Contributor

@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.

:lgtm: Nice work.
Platform review +@rpoyner-tri (since the Wednesday platform reviewer is Xuchen).

Reviewed 1 of 2 files at r6, 1 of 1 files at r7.
Reviewable status: 2 unresolved discussions, LGTM missing from assignee rpoyner-tri(platform)


multibody/tree/test/deformable_body_test.cc line 224 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

I think we can converge on this quickly today and it is one of the last remaining things for this PR. Perhaps you might have time to do it together at your computer?

Thanks Xuchen.

Copy link
Contributor Author

@xuchenhan-tri xuchenhan-tri left a comment

Choose a reason for hiding this comment

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

Dismissed @mitiguy from a discussion.
Reviewable status: 1 unresolved discussion, LGTM missing from assignee rpoyner-tri(platform)


multibody/tree/test/deformable_body_test.cc line 224 at r4 (raw file):

Previously, mitiguy (Mitiguy) wrote…

I think we can converge on this quickly today and it is one of the last remaining things for this PR. Perhaps you might have time to do it together at your computer?

Done.

Copy link
Contributor

@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.

@xuchenhan-tri the bindings look good too.

Reviewed 7 of 7 files at r8, all commit messages.
Reviewable status: LGTM missing from assignee rpoyner-tri(platform)

Add DeformableBody::CalcCenterOfMassPositionInWorld,
DeformableBody::CalcCenterOfMassTranslationalVelocityInWorld, and
DeformableBody::CalcEffectiveAngularVelocity
Copy link
Contributor Author

@xuchenhan-tri xuchenhan-tri left a comment

Choose a reason for hiding this comment

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

Rebased to fix merge conflicts.

Reviewable status: LGTM missing from assignee rpoyner-tri(platform)

Copy link
Contributor

@rpoyner-tri rpoyner-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:

Reviewed 4 of 14 files at r1, 2 of 9 files at r3, 5 of 9 files at r5, 1 of 2 files at r6, 1 of 7 files at r8, 6 of 6 files at r9, all commit messages.
Reviewable status: :shipit: complete! all discussions resolved, LGTM from assignees rpoyner-tri(platform),mitiguy

@rpoyner-tri rpoyner-tri merged commit 4331827 into RobotLocomotion:master Jun 12, 2025
10 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
release notes: none This pull request should not be mentioned in the release notes
Projects
None yet
Development

Successfully merging this pull request may close these issues.

5 participants