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

implements MultibodyPlant::RemoveJointActuator #20711

Merged

Conversation

RussTedrake
Copy link
Contributor

@RussTedrake RussTedrake commented Dec 28, 2023

In order to keep existing actuator indices valid, MultibodyTree replaces the actuator in the list with nullptr. As a result, we must also introduce new supporting api: for checking if an actuator index is valid, and for iterating over all actuator indices:

  • has_joint_actuator(actuator_index)
  • GetJointActuatorIndices()

It is no longer sound to iterate with a for loop of JointActuatorIndex from 0 to num_actuators() -- both because some elements will be omitted AND because num_actuators() is not necessarily the highest actuator index.


This is a pre-requisite for me to implement "replace all joints with weld joints", which will greatly facilitate building controller plants which use frozen version of the end effector.

@jwnimmer-tri , @sherm1 -- this is the design/implementation we discussed at the onsite. For completeness, we also discussed it on slack.
@joemasterjohn -- my understanding is that you might be the one to follow through on these changes for joints / bodies.
Anybody willing to take the feature review?

Reviewers: All of the core changes (and the core test) is in the multibody/tree directory. Everything else is derivative.


This change is Reviewable

@RussTedrake RussTedrake added priority: medium release notes: feature This pull request contains a new feature labels Dec 28, 2023
@RussTedrake RussTedrake force-pushed the remove_joint_actuator branch 3 times, most recently from e545864 to 53e7857 Compare December 29, 2023 11:56
@RussTedrake
Copy link
Contributor Author

bumping to high priority now that people are coming back online. I need this for the lbm sim.

@RussTedrake
Copy link
Contributor Author

+@jwnimmer-tri for feature review, please.

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.

Checkpoint, partway through.

Reviewed 16 of 21 files at r1.
Reviewable status: 24 unresolved discussions, LGTM missing from assignee jwnimmer-tri(platform), needs at least two assigned reviewers

a discussion (no related file):
The actuation input port indexing is pretty tricky now. As I read the code, I found 2 logic errors in MbP where it was internally using the wrong indexing.

That made me want to find a way to probe even harder, so I came up with the patch below. In the MbP constructor, the patch adds and then removes a joint actuator so that we have JointActuatorIndex{0} as a removed actuator, so that we never have the actuator.input_start() == actuator.index() invariant anymore.

Running the patch under bazel test -c dbg //multibody/... found 3 more logic errors. (All bugs have been noted in individual discussions below.) Running the patch for bazel test -c dbg //... didn't find anything beyond multibody.

--- a/multibody/tree/multibody_tree.h
+++ b/multibody/tree/multibody_tree.h
@@ -88,7 +88,7 @@ class MultibodyTree {
 
   // Creates a MultibodyTree containing only a **world** body and a
   // UniformGravityFieldElement.
-  MultibodyTree();
+  explicit MultibodyTree(bool is_clone = false);
 
   // @name Methods to add new MultibodyTree elements.
   //
@@ -2229,7 +2229,7 @@ class MultibodyTree {
           "MultibodyTree::Finalize() must be called before attempting to clone"
           " a MultibodyTree.");
     }
-    auto tree_clone = std::make_unique<MultibodyTree<ToScalar>>();
+    auto tree_clone = std::make_unique<MultibodyTree<ToScalar>>(true);
 
     tree_clone->frames_.resize(num_frames());
     // Skipping the world body at body_index = 0.
--- a/multibody/tree/multibody_tree.cc
+++ b/multibody/tree/multibody_tree.cc
@@ -65,7 +65,7 @@ class JointImplementationBuilder {
 };
 
 template <typename T>
-MultibodyTree<T>::MultibodyTree() {
+MultibodyTree<T>::MultibodyTree(const bool is_clone) {
   // Adds a "world" body to MultibodyTree having a NaN SpatialInertia.
   ModelInstanceIndex world_instance = AddModelInstance("WorldModelInstance");
 
@@ -86,6 +86,14 @@ MultibodyTree<T>::MultibodyTree() {
       AddForceElement<UniformGravityFieldElement>();
   DRAKE_DEMAND(num_force_elements() == 1);
   DRAKE_DEMAND(owned_force_elements_[0].get() == &new_field);
+
+  // XXX HACK XXX
+  if (!is_clone) {
+    // Add a joint actuator tombstone as the 0'th one, to flush out bugs.
+    owned_actuators_.push_back(nullptr);
+    topology_.add_joint_actuator(1 /* dof */);
+    topology_.RemoveJointActuator(JointActuatorIndex{0});
+  }
 }
 
 template <typename T>

I am not sure whether we should try to add some patch like this into the code, or find some other similar mechanism. The downside of the patch would be any code that assumed that the first actuator they add (or parse) was always assigned index 0. (Now, it would be index 1.) That's probably too big of a change to swallow.



manipulation/models/iiwa_description/test/iiwa_variants_parsing_test.cc line 217 at r1 (raw file):

      if (model_path.filename() == "dual_iiwa14_polytope_collision.urdf") {
        const multibody::JointActuator<double>& second_instance_joint_actuator =
            plant.get_joint_actuator(multibody::JointActuatorIndex(index + 7));

nit Redundant copy (or maybe not? I only see operator+= not operator+ defined on TypeSafeIndex).

Suggestion:

plant.get_joint_actuator(index + 7)

multibody/plant/discrete_update_manager.cc line 464 at r1 (raw file):

      VectorX<T>& actuation =
          actuator.has_controller() ? *actuation_w_pd : *actuation_wo_pd;
      actuation[v_index] = u[actuator_index];

Using actuator_index here is no longer correct. I think we want actuator.input_start(), instead.

(And a unit test.)


multibody/plant/multibody_plant.h line 408 at r1 (raw file):

be ordered by @ref JointActuatorIndex. For the get_actuation_input_port() that
covers all actuators, the iᵗʰ vector element corresponds to
`JointActuatorIndex(i)`. For the

This sentence is no longer accurate: For the get_actuation_input_port() that
covers all actuators, the iᵗʰ vector element corresponds to JointActuatorIndex(i).

Perhaps we should somehow cite JointActuator::input_start, instead.


multibody/plant/multibody_plant.h line 910 at r1 (raw file):

  /// all actuated dofs. This input port is a vector valued port indexed by
  /// @ref JointActuatorIndex, see JointActuator::index(), and can be set with
  /// JointActuator::set_actuation_vector().

This stanza is no longer accurate: This input port is a vector valued port indexed by JointActuatorIndex, see JointActuator::index(),

We are careful to say "indexed by" only when it's a literal index into the vector, which is no longer necessarily true.


multibody/plant/multibody_plant.h line 935 at r1 (raw file):

  /// Returns a constant reference to the output port that reports actuation
  /// values applied through joint actuators. This output port is a vector
  /// valued port indexed by @ref JointActuatorIndex, see

Ditto "indexed by" no longer accurate.


multibody/plant/multibody_plant.h line 1410 at r1 (raw file):

  /// will remain valid for the lifetime of `this` plant.
  /// @throws std::exception if `joint.num_velocities() > 1` since for now we
  /// only support actuators for single dof joints.

BTW It might be worth adding a @see Remove... cross-link here, since in the rendered API reference the functions will not necessarily be nearby.


multibody/plant/multibody_plant.h line 1417 at r1 (raw file):

  /// Removes `actuator` from this %MultibodyPlant and frees the corresponding
  /// memory. Any existing references to `actuator` will become invalid, and
  /// future calls to `get_joint_actuator(actuator.index())` will throw an

nit This is not 100% accurate as written. Calling any function on actuator after deletion is UB.

Suggestion:

  /// future calls to `get_joint_actuator(actuator_index)` will throw an

multibody/plant/multibody_plant.h line 3005 at r1 (raw file):

  /// `u` of actuation values for the entire plant model. Refer to @ref
  /// mbp_actuation "Actuation" for further details.
  /// @param[in] u Actuation values for the entire model, indexed by

Ditto "indexed by" no longer accurate.


multibody/plant/multibody_plant.h line 3024 at r1 (raw file):

  ///   ordered by monotonically increasing @ref JointActuatorIndex within the
  ///   model instance.
  /// @param[in,out] u Actuation values for the entire plant model, indexed by

Ditto "indexed by" no longer accurate.


multibody/plant/multibody_plant.h line 4482 at r1 (raw file):

  /// The vector u of actuation values is of size num_actuated_dofs(). For a
  /// given JointActuator, `u[JointActuator::index()]` stores the value for the
  /// external actuation corresponding to that actuator. `tau_u` on the other

This sentence is no longer accurate: For a given JointActuator, u[JointActuator::index()] stores the value for the external actuation corresponding to that actuator.

(I assume we'll want to cite JointActuator::input_start, instead.)


multibody/plant/multibody_plant.h line 4493 at r1 (raw file):

  /// Alternative signature to build an actuation selector matrix `Su` such
  /// that `u = Su⋅uₛ`, where u is the vector of actuation values for the full
  /// model (ordered by JointActuatorIndex) and uₛ is a vector of actuation

Ditto "ordered by" no longer quite accurate, or at least is too nebulous. We probably want something more like the "monotonically increasing" language from elsewhere.


multibody/plant/multibody_plant.cc line 1260 at r1 (raw file):

    // condition.
    DRAKE_DEMAND(actuator.joint().num_velocities() == 1);
    B(actuator.joint().velocity_start(), int{actuator.index()}) = 1;

The actuator.index() here is no longer correct. I think we want actuator.input_start(), instead.

(And a unit test.)


multibody/plant/multibody_plant.cc line 1689 at r1 (raw file):

  for (JointActuatorIndex actuator_index : GetJointActuatorIndices()) {
    const JointActuator<T>& actuator =
        get_joint_actuator(JointActuatorIndex(actuator_index));

nit Redundant copy

Suggestion:

    const JointActuator<T>& actuator = get_joint_actuator(actuator_index);

multibody/plant/multibody_plant.cc line 2299 at r1 (raw file):

      // We only support actuators on single dof joints for now.
      DRAKE_DEMAND(joint.num_velocities() == 1);
      (*forces)[joint.velocity_start()] += u[actuator_index];

The actuator_index here is no longer correct. I think we want actuator.input_start(), instead.

(And a unit test.)


multibody/plant/sap_driver.cc line 748 at r1 (raw file):

      if (!joint.is_locked(context)) {
        const double effort_limit = actuator.effort_limit();
        const T& qd = desired_state[actuator.index()];

Using the actuator.index() here is no longer correct. I think we want the enumerated loop count, instead. Likewise for the next two lines as well.

(And a unit test.)


multibody/plant/test/multibody_plant_reflected_inertia_test.cc line 615 at r1 (raw file):

    JointActuator<double>& joint_actuator =
        dynamic_cast<JointActuator<double>&>(
            plant_ri_.get_mutable_joint_actuator(JointActuatorIndex(index)));

nit Redundant copy

Suggestion:

plant_ri_.get_mutable_joint_actuator(index)

multibody/plant/test/multibody_plant_reflected_inertia_test.cc line 627 at r1 (raw file):

    JointActuator<double>& joint_actuator =
        dynamic_cast<JointActuator<double>&>(
            plant_ri_.get_mutable_joint_actuator(JointActuatorIndex(index)));

nit Redundant copy


multibody/plant/test/multibody_plant_reflected_inertia_test.cc line 639 at r1 (raw file):

    JointActuator<double>& joint_actuator =
        dynamic_cast<JointActuator<double>&>(
            plant_ri_.get_mutable_joint_actuator(JointActuatorIndex(index)));

nit Redundant copy


multibody/tree/multibody_tree.h line 3129 at r1 (raw file):

  // may not be the same size as owned_actuators_ (which maintains a nullptr
  // for the removed elements).
  std::vector<JointActuatorIndex> joint_actuator_indices_{};

Working

Keeping the two collections (owned & indices) in sync is somewhat tricky and brittle. I'm going to see if I can come up with an adjustment that can improve readability and brittleness.


multibody/tree/multibody_tree.cc line 3613 at r1 (raw file):

  int user_index = 0;
  for (JointActuatorIndex actuator_index : user_to_actuator_index_map) {
    Su(int{actuator_index}, user_index) = 1.0;

The int{actuator_index} here is wrong. It should be actuator.input_start().


multibody/tree/multibody_tree-inl.h line 396 at r1 (raw file):

  const JointActuatorIndex actuator_index =
      topology_.add_joint_actuator(joint.num_velocities());
  DRAKE_DEMAND(actuator_index == ssize(owned_actuators_)-1);

nit whitespace

Suggestion:

DRAKE_DEMAND(actuator_index == ssize(owned_actuators_) - 1);

multibody/tree/multibody_tree_topology.h line 321 at r1 (raw file):

  // The number of dofs actuated by this actuator.
  int num_dofs{-1};
  bool removed{false};

I am somewhat worried that the code would at some point forget to check for false somewhere that was important.

Might it be cleaner and safer to use std::vector<std::optional<JointActuatorTopology>> joint_actuators_; with nullopt to denote a removed actuator?


bindings/pydrake/examples/gym/named_view_helpers.py line 15 at r1 (raw file):

    names = [None] * plant.get_actuation_input_port().size()
    for ind in plant.GetJointActuatorIndices():
        actuator = plant.get_joint_actuator(JointActuatorIndex(ind))

nit Redundant copy

Suggestion:

plant.get_joint_actuator(ind)

Copy link
Contributor Author

@RussTedrake RussTedrake 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: 18 unresolved discussions, LGTM missing from assignee jwnimmer-tri(platform), needs at least two assigned reviewers

a discussion (no related file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

The actuation input port indexing is pretty tricky now. As I read the code, I found 2 logic errors in MbP where it was internally using the wrong indexing.

That made me want to find a way to probe even harder, so I came up with the patch below. In the MbP constructor, the patch adds and then removes a joint actuator so that we have JointActuatorIndex{0} as a removed actuator, so that we never have the actuator.input_start() == actuator.index() invariant anymore.

Running the patch under bazel test -c dbg //multibody/... found 3 more logic errors. (All bugs have been noted in individual discussions below.) Running the patch for bazel test -c dbg //... didn't find anything beyond multibody.

--- a/multibody/tree/multibody_tree.h
+++ b/multibody/tree/multibody_tree.h
@@ -88,7 +88,7 @@ class MultibodyTree {
 
   // Creates a MultibodyTree containing only a **world** body and a
   // UniformGravityFieldElement.
-  MultibodyTree();
+  explicit MultibodyTree(bool is_clone = false);
 
   // @name Methods to add new MultibodyTree elements.
   //
@@ -2229,7 +2229,7 @@ class MultibodyTree {
           "MultibodyTree::Finalize() must be called before attempting to clone"
           " a MultibodyTree.");
     }
-    auto tree_clone = std::make_unique<MultibodyTree<ToScalar>>();
+    auto tree_clone = std::make_unique<MultibodyTree<ToScalar>>(true);
 
     tree_clone->frames_.resize(num_frames());
     // Skipping the world body at body_index = 0.
--- a/multibody/tree/multibody_tree.cc
+++ b/multibody/tree/multibody_tree.cc
@@ -65,7 +65,7 @@ class JointImplementationBuilder {
 };
 
 template <typename T>
-MultibodyTree<T>::MultibodyTree() {
+MultibodyTree<T>::MultibodyTree(const bool is_clone) {
   // Adds a "world" body to MultibodyTree having a NaN SpatialInertia.
   ModelInstanceIndex world_instance = AddModelInstance("WorldModelInstance");
 
@@ -86,6 +86,14 @@ MultibodyTree<T>::MultibodyTree() {
       AddForceElement<UniformGravityFieldElement>();
   DRAKE_DEMAND(num_force_elements() == 1);
   DRAKE_DEMAND(owned_force_elements_[0].get() == &new_field);
+
+  // XXX HACK XXX
+  if (!is_clone) {
+    // Add a joint actuator tombstone as the 0'th one, to flush out bugs.
+    owned_actuators_.push_back(nullptr);
+    topology_.add_joint_actuator(1 /* dof */);
+    topology_.RemoveJointActuator(JointActuatorIndex{0});
+  }
 }
 
 template <typename T>

I am not sure whether we should try to add some patch like this into the code, or find some other similar mechanism. The downside of the patch would be any code that assumed that the first actuator they add (or parse) was always assigned index 0. (Now, it would be index 1.) That's probably too big of a change to swallow.

That's a very clever test! But I agree that I would not want to land it in master. If someone uses the new RemoveJointActuator functionality, then they will also have to update their joint actuators iterators, but only then.



manipulation/models/iiwa_description/test/iiwa_variants_parsing_test.cc line 217 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

nit Redundant copy (or maybe not? I only see operator+= not operator+ defined on TypeSafeIndex).

The compiler wants it

manipulation/models/iiwa_description/test/iiwa_variants_parsing_test.cc:218:44: error: cannot convert 'int' to 'drake::multibody::JointActuatorIndex' {aka 'drake::TypeSafeIndex<drake::multibody::JointActuatorElementTag>'}
  218 |             plant.get_joint_actuator(index + 7);
      |                                      ~~~~~~^~~
      |                                            |
      |                                            int

multibody/plant/test/multibody_plant_reflected_inertia_test.cc line 615 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

nit Redundant copy

Done.


multibody/plant/test/multibody_plant_reflected_inertia_test.cc line 627 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

nit Redundant copy

Done.


multibody/plant/test/multibody_plant_reflected_inertia_test.cc line 639 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

nit Redundant copy

Done.


multibody/tree/multibody_tree.h line 3129 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

Working

Keeping the two collections (owned & indices) in sync is somewhat tricky and brittle. I'm going to see if I can come up with an adjustment that can improve readability and brittleness.

That seems like a big change. Should I wait for it before touching everything else up?


multibody/tree/multibody_tree-inl.h line 396 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

nit whitespace

Done . (removed by your PR fix).


bindings/pydrake/examples/gym/named_view_helpers.py line 15 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

nit Redundant copy

Done.

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 6 of 17 files at r2.
Reviewable status: 19 unresolved discussions, LGTM missing from assignee jwnimmer-tri(platform), needs at least two assigned reviewers


manipulation/models/iiwa_description/test/iiwa_variants_parsing_test.cc line 217 at r1 (raw file):

Previously, RussTedrake (Russ Tedrake) wrote…

The compiler wants it

manipulation/models/iiwa_description/test/iiwa_variants_parsing_test.cc:218:44: error: cannot convert 'int' to 'drake::multibody::JointActuatorIndex' {aka 'drake::TypeSafeIndex<drake::multibody::JointActuatorElementTag>'}
  218 |             plant.get_joint_actuator(index + 7);
      |                                      ~~~~~~^~~
      |                                            |
      |                                            int

Huh. I have no idea why we overload operator+= but not operator+. Oh well, retracted.


multibody/tree/multibody_tree.h line 3129 at r1 (raw file):

Previously, RussTedrake (Russ Tedrake) wrote…

That seems like a big change. Should I wait for it before touching everything else up?

My WIP is #20752 but still needs about a day of work before it can land (ahead of this PR, which would rebase onto it). You can see which files are changed there -- it's most just MbT stuff. So fixes to the plant, update manager, topology manager, etc. should all be unaffected.


multibody/tree/multibody_tree.cc line 107 at r1 (raw file):

  topology_.RemoveJointActuator(actuator_index);
}

Working

This forgets to remove the name from the name indexing map.

I expected that my #20752 will end up fixing that.

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 6 of 17 files at r2.
Reviewable status: 19 unresolved discussions, LGTM missing from assignee jwnimmer-tri(platform), needs at least two assigned reviewers

Copy link
Contributor Author

@RussTedrake RussTedrake 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: 19 unresolved discussions, LGTM missing from assignee jwnimmer-tri(platform), needs at least two assigned reviewers


multibody/tree/multibody_tree.h line 3129 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

My WIP is #20752 but still needs about a day of work before it can land (ahead of this PR, which would rebase onto it). You can see which files are changed there -- it's most just MbT stuff. So fixes to the plant, update manager, topology manager, etc. should all be unaffected.

SGTM. FWIW, the reason I have the two lists is because I believe GetJointActuatorIndices() needs to be fast, and this is effectively precomputing that result.

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: 19 unresolved discussions, LGTM missing from assignee jwnimmer-tri(platform), needs at least two assigned reviewers


multibody/tree/multibody_tree.h line 3129 at r1 (raw file):

I believe GetJointActuatorIndices() needs to be fast, and this is effectively precomputing that result.

I agree with the motivation.

(In my WIP, the const std::vector<const Element<T>*>& elements() list of pointers is also pre-computed for the same reason. The MbP time stepper needs to walk that list during its inner loop, so should avoid the extra overhead of error-checking each item in the loop and/or skipping over nulls.)

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: 19 unresolved discussions, LGTM missing from assignee jwnimmer-tri(platform), needs at least two assigned reviewers


multibody/tree/multibody_tree.h line 3129 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

I believe GetJointActuatorIndices() needs to be fast, and this is effectively precomputing that result.

I agree with the motivation.

(In my WIP, the const std::vector<const Element<T>*>& elements() list of pointers is also pre-computed for the same reason. The MbP time stepper needs to walk that list during its inner loop, so should avoid the extra overhead of error-checking each item in the loop and/or skipping over nulls.)

The WIP is out for review now.

The rebase here atop it isn't too difficult. The only thing that needs a bit of care is during MbT cloning -- now that we can have nullable actuators the loop that clones the actuators needs to be more careful about keeping the indices matched up, so it can't just iterate over elements() or indices() anymore.

(Once the other PR merges feel free to delegate the rebase here to me, but I won't do it until you ask since otherwise I risk nuking any unpushed changes you have.)


multibody/tree/multibody_tree.cc line 107 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

Working

This forgets to remove the name from the name indexing map.

I expected that my #20752 will end up fixing that.

My PR does indeed fix this.

Because we kept the old names around here accidentally, your unit test is currently checking for the error message "the actuator named 'foo' was removed". Now that we discard the names entirely, we can no longer report the name of the removed actuator in the error message. (I think that's probably OK, but if you want we can look into keeping a graveyard of names that we could pull from later for error messages.)

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.

I pushed a merge-up to master. FYI In case you want to squash it down again, one way goes like this:

# ...checkout / fetch the branch; be sure to pull changes from origin... then ...
git merge master  # make sure it's up to date
git reset --soft master  # make everything be uncommitted (but still staged)
git commit  # commit everything afresh (you'll need to re-type the commit message)

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


multibody/tree/multibody_tree.h line 3129 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

The WIP is out for review now.

The rebase here atop it isn't too difficult. The only thing that needs a bit of care is during MbT cloning -- now that we can have nullable actuators the loop that clones the actuators needs to be more careful about keeping the indices matched up, so it can't just iterate over elements() or indices() anymore.

(Once the other PR merges feel free to delegate the rebase here to me, but I won't do it until you ask since otherwise I risk nuking any unpushed changes you have.)

Done - merged.


multibody/tree/multibody_tree.cc line 107 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

My PR does indeed fix this.

Because we kept the old names around here accidentally, your unit test is currently checking for the error message "the actuator named 'foo' was removed". Now that we discard the names entirely, we can no longer report the name of the removed actuator in the error message. (I think that's probably OK, but if you want we can look into keeping a graveyard of names that we could pull from later for error messages.)

You can close this discussion thread out now. I'm just leaving it open as an FYI about the test case change / question.

@RussTedrake
Copy link
Contributor Author

@joemasterjohn kindly offered to take over this one and push it across the finish line.

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: 17 unresolved discussions, LGTM missing from assignees jwnimmer-tri(platform),joemasterjohn, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @RussTedrake)

a discussion (no related file):

Previously, RussTedrake (Russ Tedrake) wrote…

That's a very clever test! But I agree that I would not want to land it in master. If someone uses the new RemoveJointActuator functionality, then they will also have to update their joint actuators iterators, but only then.

Yeah. I had been trying to think of some way to put this under a toggle or otherwise some kind of "show me my indexing bugs so that they are clear and obvious" since I think there's a fair chance that users will struggle to get this right. However, I wasn't able to think of anything I liked, so I guess we just set it aside for now.

Perhaps the best investment of time would be to make sure that every single code sample in Drake, Manipulation, and Underactuated does this perfectly (always using actuator.index_start() when working with actuation vectors).


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: 18 unresolved discussions, LGTM missing from assignees jwnimmer-tri(platform),joemasterjohn, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @RussTedrake)


multibody/plant/multibody_plant.cc line 1293 at r3 (raw file):

MatrixX<T> MultibodyPlant<T>::MakeActuationMatrix() const {
  MatrixX<T> B = MatrixX<T>::Zero(num_velocities(), num_actuated_dofs());
  for (JointActuatorIndex actuator_index : GetJointActuatorIndices()) {

BTW Assuming that #20975 reaches master before us, we need to remember to fix its looping likewise.

Copy link
Contributor

@joemasterjohn joemasterjohn left a comment

Choose a reason for hiding this comment

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

Reviewed 9 of 21 files at r1, 2 of 17 files at r2.
Reviewable status: 14 unresolved discussions, LGTM missing from assignees jwnimmer-tri(platform),joemasterjohn, commits need curation (https://drake.mit.edu/reviewable.html#curated-commits) (waiting on @RussTedrake)


multibody/plant/discrete_update_manager.cc line 464 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

Using actuator_index here is no longer correct. I think we want actuator.input_start(), instead.

(And a unit test.)

Working. Not sure of a great testing strategy for your requested unit tests other than to modify some existing tests for DiscreteUpdateManager etc. that have an Attorney to call these privates. Do you have any ideas?


multibody/plant/multibody_plant.h line 408 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

This sentence is no longer accurate: For the get_actuation_input_port() that
covers all actuators, the iᵗʰ vector element corresponds to JointActuatorIndex(i).

Perhaps we should somehow cite JointActuator::input_start, instead.

Done. Rewritten to be explicit about how to index the whole plant input port.


multibody/plant/multibody_plant.h line 910 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

This stanza is no longer accurate: This input port is a vector valued port indexed by JointActuatorIndex, see JointActuator::index(),

We are careful to say "indexed by" only when it's a literal index into the vector, which is no longer necessarily true.

Done. Rewritten to reference JointActuator::index_start()


multibody/plant/multibody_plant.h line 935 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

Ditto "indexed by" no longer accurate.

Done.


multibody/plant/multibody_plant.h line 1410 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

BTW It might be worth adding a @see Remove... cross-link here, since in the rendered API reference the functions will not necessarily be nearby.

Done.


multibody/plant/multibody_plant.h line 1417 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

nit This is not 100% accurate as written. Calling any function on actuator after deletion is UB.

Done.


multibody/plant/multibody_plant.h line 3005 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

Ditto "indexed by" no longer accurate.

Done.


multibody/plant/multibody_plant.h line 3024 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

Ditto "indexed by" no longer accurate.

Done.


multibody/plant/multibody_plant.h line 4482 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

This sentence is no longer accurate: For a given JointActuator, u[JointActuator::index()] stores the value for the external actuation corresponding to that actuator.

(I assume we'll want to cite JointActuator::input_start, instead.)

Done.


multibody/plant/multibody_plant.h line 4493 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

Ditto "ordered by" no longer quite accurate, or at least is too nebulous. We probably want something more like the "monotonically increasing" language from elsewhere.

Done.


multibody/plant/multibody_plant.cc line 1260 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

The actuator.index() here is no longer correct. I think we want actuator.input_start(), instead.

(And a unit test.)

Working.


multibody/plant/multibody_plant.cc line 1689 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

nit Redundant copy

Done.


multibody/plant/multibody_plant.cc line 2299 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

The actuator_index here is no longer correct. I think we want actuator.input_start(), instead.

(And a unit test.)

Working.


multibody/plant/sap_driver.cc line 748 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

Using the actuator.index() here is no longer correct. I think we want the enumerated loop count, instead. Likewise for the next two lines as well.

(And a unit test.)

Working.


multibody/tree/multibody_tree.cc line 3613 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

The int{actuator_index} here is wrong. It should be actuator.input_start().

Done.


multibody/tree/multibody_tree_topology.h line 321 at r1 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

I am somewhat worried that the code would at some point forget to check for false somewhere that was important.

Might it be cleaner and safer to use std::vector<std::optional<JointActuatorTopology>> joint_actuators_; with nullopt to denote a removed actuator?

Done.

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: 16 unresolved discussions, LGTM missing from assignee sherm1(platform)


multibody/tree/multibody_tree.cc line 130 at r17 (raw file):

Previously, joemasterjohn (Joe Masterjohn) wrote…

Hmm actually I'm seeing a problem here. If the user tried to remove twice, the second time passing a stale reference then calling actuator.index() is UB, correct? That makes me think that the public removal API should be taking an JointActuatorIndex not a (potentially stale) const JointActuator<T>&. WDYT?

Passing the object instead of the index is a more ergonomic API, so I don't think we should change it just for the UB question. If the user keeps around the reference after they have deleted it, they will have many more problems than just calling RemoveJointActuator a second time. Anything they do with that reference will be UB.

Instead, I'll propose a different check -- instead of guarding here whether the index was already removed, we should check that the actuator was actually part of this tree in the first place! We don't want the user giving us an Actuator from some other MbT and then we blindly remove the same-numbered actuator from our tree and call it a day. Instead, we should fail-fast here if the Actuator's get_parent_tree is not us. (Or alternatively, the MbP could do the likewise check, if we want a more localized error message.)

For a little extra caution, we could also null out the parent_tree_ in the MultibodyElement destructor to help possibly fail-faster as the UB occurs.

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.

Platform + extra feature review: :lgtm_strong: -- a heroic effort! Misc minor threads pending.
CI seems rather red.

Reviewed 2 of 11 files at r14, 8 of 11 files at r18.
Reviewable status: 21 unresolved discussions


multibody/plant/test/multibody_plant_test.cc line 2843 at r19 (raw file):

  // clang-format on

  // Test that MakeActuationMatrix uses the correct indices into 'u'

nit: MakeActuationMatrix -> MakeActuatorSelectionMatrix


multibody/plant/test/sap_driver_test.cc line 524 at r19 (raw file):

  // Actuator with index 1 has been removed.
  const Vector2d u_feed_forward(1.0, 2.0);
  const Vector4d x_desired(3.0, 4.0, 5.0, 6.0);

BTW I was confused about this for a while because I knew there were 6 states x in the remodeling test fixture. Now I see this is just for the PD actuators and there are two of those. A short comment here would have helped me.


multibody/plant/test/sap_driver_test.cc line 526 at r19 (raw file):

  const Vector4d x_desired(3.0, 4.0, 5.0, 6.0);

  // This is hardcoded based on internal knowledge of the model.

nit: mention that -1 means "missing" here


multibody/tree/test/joint_actuator_test.cc line 196 at r19 (raw file):

  EXPECT_EQ(tree.GetJointActuatorByName("act3").index(), new_actuator3.index());
  EXPECT_EQ(tree.GetJointActuatorByName("act3", model_instance1).index(),
            new_actuator3.index());

BTW consider checking that the new actuator has the new (double) effort limit to verify that we're not still looking at the previous one


multibody/tree/test/joint_actuator_test.cc line 217 at r19 (raw file):

      "Post-finalize calls to 'RemoveJointActuator.*' are not allowed.*");

  // Confirm that removed joint logic is preserved after cloning.

typo? joint -> actuator

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.

Reviewable status: 21 unresolved discussions


multibody/tree/multibody_tree_topology.h line 726 at r17 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

The whole premise of remodeling (as I understand it) is that we maintain the same MultibodyPlant over time rather than rebuild one from scratch (which anyone can do now).

No, I don't think that's the point at all -- at least not for the user stories Russ was working on when he started this PR. Russ' goal is to take an extant MbP and replace some actuated joints with welds, to reduce the number of dofs and the size of actuation input. That all happens just once, pre-Finalize, before creating the Simulator at all. For that use case, it is not possible to "rebuild one from scratch" since at the time where we need to lower the dofs, we have no idea how to do that. We have no record of how the MbP was created and configured in the first place, so we can start over.

Anyway, agreeing about that isn't relevant for the O(n) commentary here in any case, so we can defer the "what's the user story" for another time. It doesn't need to block this review. We'll need to revisit it, though, before anyone works on a use case other that Russ's immediate need of replace-joint-with-weld.

Make sense, thanks.

@RussTedrake
Copy link
Contributor Author

-@RussTedrake

Copy link
Contributor

@joemasterjohn joemasterjohn 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 r19, all commit messages.
Reviewable status: 3 unresolved discussions


multibody/plant/discrete_update_manager.h line 198 at r19 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW personal preference: I find this construction grating because I don't think of Actuators doing anything -- it's the programmer who's going to be indexing. Consider instead something like "The actuation value for a particular actuator can be found at offset JointActuator::input_start() in the returned vector." or even "You can find the value at ...". Feel free to ignore if you like it better this way.

Done. I see your point, I've updated all of the comments with your suggested language.


multibody/plant/multibody_plant.h line 912 at r17 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

typo: index_start() -> input_start()

Also, I found this sentence hard to parse. Consider instead:

A JointActuator's offset into this vector is given by
JointActuator::input_start().

Done.


multibody/plant/multibody_plant.h line 938 at r17 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

typo: index_start() -> input_start()

(same rewording suggestion)

Done.


multibody/plant/multibody_plant.h line 1410 at r17 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW is this still true even if the actuator was removed?

Ah good catch! Nope, the reference becomes invalid when the actuator is removed. Done.


multibody/plant/multibody_plant.h line 2930 at r17 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

nit: the doxygen indenting here is different from that in SetActuationInArray() just below. Not your fault, but consider making these consistent while you're modifying the docs.

Done.


multibody/plant/multibody_plant.h line 4423 at r17 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW this doesn't fully describe how u is put together. Consider referencing the full description in get_actuation_input_port() instead of re-describing here.

Done.


multibody/plant/multibody_plant.h line 4659 at r17 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW consider adding "but the indexes will in general not be consecutive due to actuators that were removed".

Done, thanks.


multibody/plant/multibody_plant.h line 983 at r19 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW again I don't see the Actuator doing the indexing here!

Done.


multibody/plant/multibody_plant.h line 4397 at r19 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW I like the sentence structure here better since it doesn't claim the Actuator is doing anything. Consider using "offset" or something like that rather than "index" to avoid confusion with JointActuatorIndex which is definitely not being used here. Same comments elsewhere in this file if you decide to change, but feel free to ignore if you prefer it like this.

Done. I changed all of the language in the PR that previously said "indexed by" to your suggested language.


multibody/plant/multibody_plant.cc line 1310 at r17 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

BTW the int{} cast can vanish now, too -- it's already an int.

Done.


multibody/plant/sap_driver.cc line 1121 at r17 (raw file):

Previously, joemasterjohn (Joe Masterjohn) wrote…

Working on the unit test.

Done. Added a new unit test to actuated_models_test that covers this line.


multibody/plant/test/multibody_plant_test.cc line 2843 at r19 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

nit: MakeActuationMatrix -> MakeActuatorSelectionMatrix

Done.


multibody/plant/test/sap_driver_test.cc line 524 at r19 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW I was confused about this for a while because I knew there were 6 states x in the remodeling test fixture. Now I see this is just for the PD actuators and there are two of those. A short comment here would have helped me.

Done.


multibody/plant/test/sap_driver_test.cc line 526 at r19 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

nit: mention that -1 means "missing" here

Done.


multibody/tree/model_instance.h line 113 at r18 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW consider referencing the full description in MultibodyPlant::get_actuation_input_port() or expanding the description here.

Done.


multibody/tree/multibody_tree.cc line 130 at r17 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

Passing the object instead of the index is a more ergonomic API, so I don't think we should change it just for the UB question. If the user keeps around the reference after they have deleted it, they will have many more problems than just calling RemoveJointActuator a second time. Anything they do with that reference will be UB.

Instead, I'll propose a different check -- instead of guarding here whether the index was already removed, we should check that the actuator was actually part of this tree in the first place! We don't want the user giving us an Actuator from some other MbT and then we blindly remove the same-numbered actuator from our tree and call it a day. Instead, we should fail-fast here if the Actuator's get_parent_tree is not us. (Or alternatively, the MbP could do the likewise check, if we want a more localized error message.)

For a little extra caution, we could also null out the parent_tree_ in the MultibodyElement destructor to help possibly fail-faster as the UB occurs.

Done.


multibody/tree/multibody_tree_topology.h line 718 at r17 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW I'd be inclined to DRAKE_DEMAND this since there's a lot else going on here so wouldn't be a performance hit in Release

Done.


multibody/tree/test/joint_actuator_test.cc line 196 at r19 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW consider checking that the new actuator has the new (double) effort limit to verify that we're not still looking at the previous one

Done.


multibody/tree/test/joint_actuator_test.cc line 217 at r19 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

typo? joint -> actuator

Done.

Copy link
Contributor

@joemasterjohn joemasterjohn 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 11 files at r18, 1 of 4 files at r19, 14 of 14 files at r20, all commit messages.
Reviewable status: 2 unresolved discussions

Copy link
Contributor

@joemasterjohn joemasterjohn left a comment

Choose a reason for hiding this comment

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

OK all comments addressed now. The only significant change was new unit test to catch a remaining actuator_index -> actuator.input_start() bug.

Reviewable status: 2 unresolved discussions

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.

(Checkpoint just to clear the open discussions. I'll circle back soon to finish reading all of the changes.)

Reviewed 6 of 14 files at r20, 13 of 16 files at r21, all commit messages.
Reviewable status: 2 unresolved discussions


multibody/tree/multibody_element.cc line 11 at r21 (raw file):

template <typename T>
MultibodyElement<T>::~MultibodyElement() {
  parent_tree_ = nullptr;

BTW Having code in a destructor is not typical. It's probably worth a comment to explain the thought process:

// Clear the tree to help fail-fast in case of accidental use-after-free of this MultibodyElement by end users who accidentally kept around a stale point to us.

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 9 of 14 files at r20, 16 of 16 files at r21, all commit messages.
Reviewable status: 6 unresolved discussions


multibody/plant/test/actuated_models_test.cc line 226 at r21 (raw file):

    if (test_remove_joint_actuators_) {
      // clang-format off
    const VectorXd full_model_u =

nit: indenting is odd here (and in the two similar blocks below)


multibody/plant/test/actuated_models_test.cc line 707 at r21 (raw file):

  auto [arm_u, acrobot_u, gripper_u] = MakeActuationForEachModel(
      false /* iiwa outside limits */, false /* gripper outside limits*/);

nit missing space before the last */


multibody/plant/test/actuated_models_test.cc line 717 at r21 (raw file):

  // The feedforward actuation is well over the effort limits for the arm and
  // gripper, so we expect the PD constraints to saturate to the effort limits.

BTW is the idea here that if the PD indexed correctly it wouldn't be saturated? Can clarify in the comment how this validates the indexing?


multibody/tree/multibody_tree.cc line 130 at r21 (raw file):

  // N.B. If the user passes a dangling reference to a previously removed
  // actuator, this is undefined behavior. However, MultibodyElement's
  // desctructor sets the parent tree to nullptr, so this line will hopefully

typo: desctructor -> destructor

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 except for the r18..r21 of actuated_models_test -- I ran out of time before I could review that. I'll defer to @sherm1 to decide if we need to find another reviewer for that one piece.

Reviewed 3 of 14 files at r20, 2 of 16 files at r21.
Reviewable status: 9 unresolved discussions


multibody/plant/multibody_plant.h line 2931 at r21 (raw file):

  /// mbp_actuation "Actuation" for further details.
  /// @param[in] u Actuation values for the entire model. The actuation value
  ///   in `u` for a particular actuator can be found at offset

nit The word "can" here is too weak. This is requirement that callers must meet, or else we will compute wrong answers.

I suppose we could change it to say "must" but I wonder if there isn't a different phrasing entirely that would be better.

Code quote:

can

multibody/plant/multibody_plant.h line 2951 at r21 (raw file):

  ///   model instance.
  /// @param[in,out] u Actuation values for the entire plant model. The
  ///   actuation value in `u` for a particular actuator can be found at offset

Ditto the defect on joint_actuator.h:

The purpose of the comment was not telling how they can find something in u_instance, the purpose is a precondition on u_instance about where this actuator must appear. The word "can" is not suitable here when stating a requirement.


multibody/tree/joint_actuator.h line 126 at r21 (raw file):

  ///   Actuation values for the entire plant model to which `this` actuator
  ///   belongs to. The actuation value in `u` for `this` actuator can be found
  ///   at offset input_start(). Only values corresponding to this actuator are

Ditto one of defects on multibody_plant.h:

The purpose of the comment was not telling how they can find something in u_actuator, the purpose is a precondition on u_actuator about where this actuator must appear. The word "can" is not suitable here when stating a requirement.


multibody/tree/multibody_tree.cc line 130 at r21 (raw file):

  // N.B. If the user passes a dangling reference to a previously removed
  // actuator, this is undefined behavior. However, MultibodyElement's
  // desctructor sets the parent tree to nullptr, so this line will hopefully

nit Typos aside, for my money, this whole paragraph would vanish. Checking that the actuator belongs to us is obviously right and proper so needs no justification, and the function name is self-documenting so we don't need the first line of the comment that just repeating it. The second half of the comment does not seem "nota bene" to me at all. Anywhere in the entire codebase we take in a const reference we'll have UB if the user gives us an expired reference. I don't see how this particular one is especially more notable than any other.

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.

CI failure is just use of the recently-deprecated default constructor for SpatialInertia().

LGTM except for the r18..r21 of actuated_models_test -- I ran out of time before I could review that. I'll defer to @sherm1 to decide if we need to find another reviewer for that one piece.

I think it would be worth waiting until you have a chance to look at that Jeremy -- I did review it but it's a tricky piece of multipurpose test code and was hard for me to be sure it scratches all the right itches.

Reviewable status: 9 unresolved discussions

@jwnimmer-tri
Copy link
Collaborator

I think it would be worth waiting until you have a chance to look at that Jeremy.

ETA would be either April 9th or April 15th.

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.

That's a stretch -- I'll see if I can go over it with Joe and get convinced.

Reviewable status: 9 unresolved discussions

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, I've been through the new actuated_models_test in more detail now and I get it. Looks good pending a few remaining comments here and there.

Reviewable status: 11 unresolved discussions


multibody/plant/test/actuated_models_test.cc line 180 at r21 (raw file):

  // be above effort limits for joints 1 and 2 and below effort limits for
  // joints 4, 5, and 6. The returned tuple packs each model's actuation as
  // {arm, acrobot, gripper, box}.

minor: the above comment seems wrong - no box?


multibody/plant/test/actuated_models_test.cc line 722 at r21 (raw file):

  const VectorXd arm_u_clamped =
      arm_u.array().min(arm_limits.array()).max(-arm_limits.array());
  const VectorXd gripper_limits = Eigen::Vector2d(80, 80);

BTW These limits are also in a comment in MakeActuationForEachModel(). Would be better to put them in one place and refer to them where needed rather than repeat -- too brittle. If they were available numerically you could also make sure that the in- and out-of-limit values really were in and out in MakeActuationForEachModel().

Copy link
Contributor Author

@RussTedrake RussTedrake 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 13 files at r5, 2 of 3 files at r17, 3 of 11 files at r18, 1 of 4 files at r19, 9 of 14 files at r20, 16 of 16 files at r21, all commit messages.
Reviewable status: 11 unresolved discussions

Copy link
Contributor

@joemasterjohn joemasterjohn left a comment

Choose a reason for hiding this comment

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

Reviewed 16 of 16 files at r21.
Reviewable status: 2 unresolved discussions


multibody/plant/multibody_plant.h line 2931 at r21 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

nit The word "can" here is too weak. This is requirement that callers must meet, or else we will compute wrong answers.

I suppose we could change it to say "must" but I wonder if there isn't a different phrasing entirely that would be better.

Done. I thought about something like "We expect to find.." but I found it more clunky than just saying "must" in what I wrote before.


multibody/plant/multibody_plant.h line 2951 at r21 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

Ditto the defect on joint_actuator.h:

The purpose of the comment was not telling how they can find something in u_instance, the purpose is a precondition on u_instance about where this actuator must appear. The word "can" is not suitable here when stating a requirement.

Done.


multibody/plant/test/actuated_models_test.cc line 180 at r21 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

minor: the above comment seems wrong - no box?

Right, the box is not actuated in this fixture.


multibody/plant/test/actuated_models_test.cc line 226 at r21 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

nit: indenting is odd here (and in the two similar blocks below)

Done.


multibody/plant/test/actuated_models_test.cc line 707 at r21 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

nit missing space before the last */

Done.


multibody/plant/test/actuated_models_test.cc line 717 at r21 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW is the idea here that if the PD indexed correctly it wouldn't be saturated? Can clarify in the comment how this validates the indexing?

The comment about saturation was just to note that we don't have to consider any of the math behind what the PD constraints calculate and send out of their force reporting APIs and check for some magic value. Because the constraints enforce effort limits, setting the feedforward torques well beyond the effort limits essentially nullify any PD contributions, so the reported constraints contributions (the values that eventually make their way into the net actuation vector) will just be clamped to the effort limits, make the "expected" values easy to write.

I've updated the comment above this particular test to explain further how it validates the indexing.


multibody/plant/test/actuated_models_test.cc line 722 at r21 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW These limits are also in a comment in MakeActuationForEachModel(). Would be better to put them in one place and refer to them where needed rather than repeat -- too brittle. If they were available numerically you could also make sure that the in- and out-of-limit values really were in and out in MakeActuationForEachModel().

I toyed with this a bit, but many of the other tests in this file have the same brittle hardcoded limits and expected values. Since I don't want to overhaul anything else in this file in this PR, I put a TODO to fixup all of the tests at a later date.


multibody/tree/joint_actuator.h line 126 at r21 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

Ditto one of defects on multibody_plant.h:

The purpose of the comment was not telling how they can find something in u_actuator, the purpose is a precondition on u_actuator about where this actuator must appear. The word "can" is not suitable here when stating a requirement.

Done.


multibody/tree/multibody_element.cc line 11 at r21 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

BTW Having code in a destructor is not typical. It's probably worth a comment to explain the thought process:

// Clear the tree to help fail-fast in case of accidental use-after-free of this MultibodyElement by end users who accidentally kept around a stale point to us.

Done.


multibody/tree/multibody_tree.cc line 130 at r21 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

typo: desctructor -> destructor

Done.


multibody/tree/multibody_tree.cc line 130 at r21 (raw file):

Previously, jwnimmer-tri (Jeremy Nimmer) wrote…

nit Typos aside, for my money, this whole paragraph would vanish. Checking that the actuator belongs to us is obviously right and proper so needs no justification, and the function name is self-documenting so we don't need the first line of the comment that just repeating it. The second half of the comment does not seem "nota bene" to me at all. Anywhere in the entire codebase we take in a const reference we'll have UB if the user gives us an expired reference. I don't see how this particular one is especially more notable than any other.

Done.

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 7 of 7 files at r22, all commit messages.
Reviewable status: 3 unresolved discussions


multibody/plant/test/actuated_models_test.cc line 694 at r22 (raw file):

// into the full actuation vector, `u`. When actuators are removed, the
// (unmodified) `JointActuatorIndex` is no longer a valid index into `u`. The
// correct index (regardless of whether actuators have been removed or not) is

BTW consider "correct offset" instead of "correct index" here to avoid confusion with the JointActuatorIndex

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.

+@xuchenhan-tri for platform review per rotation, please

Reviewable status: 3 unresolved discussions, LGTM missing from assignee xuchenhan-tri(platform)

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.

Dismissed @jwnimmer-tri from 2 discussions.
Reviewable status: 1 unresolved discussion, LGTM missing from assignee xuchenhan-tri(platform)

Copy link
Contributor

@joemasterjohn joemasterjohn left a comment

Choose a reason for hiding this comment

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

Actually, @sherm1 you gave the platform LGTM last week (+ extra feature review). Are you good with this, or did you want another set of platform eyes on this?

Reviewable status: 1 unresolved discussion, LGTM missing from assignee xuchenhan-tri(platform)

In order to keep existing actuator indices valid, MultibodyTree
replaces the actuator in the list with nullptr.  As a result, we must
also introduce new supporting api: for checking if an actuator index
is valid, and for iterating over all actuator indices:
- has_joint_actuator(actuator_index)
- GetJointActuatorIndices()

It is no longer sound to iterate with a for loop of JointActuatorIndex
from 0 to num_actuators() -- both because some elements will be
omitted AND because num_actuators() is not necessarily the highest
actuator index.

Co-authored-by: Joe Masterjohn <joemasterjohn@gmail.com>
Copy link
Contributor

@joemasterjohn joemasterjohn left a comment

Choose a reason for hiding this comment

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

Reviewed 7 of 7 files at r22, 1 of 1 files at r23, all commit messages.
Reviewable status: LGTM missing from assignee xuchenhan-tri(platform)


multibody/plant/test/actuated_models_test.cc line 694 at r22 (raw file):

Previously, sherm1 (Michael Sherman) wrote…

BTW consider "correct offset" instead of "correct index" here to avoid confusion with the JointActuatorIndex

Done.

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.

Oh yeah I forgot! All good then.

Reviewed 1 of 1 files at r23, all commit messages.
Reviewable status: LGTM missing from assignee xuchenhan-tri(platform)

@joemasterjohn joemasterjohn merged commit 29aa51f into RobotLocomotion:master Apr 8, 2024
9 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
priority: medium release notes: feature This pull request contains a new feature
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

6 participants