RobotLocomotion / drake

Model-based design and verification for robotics.
https://drake.mit.edu
Other
3.17k stars 1.24k forks source link

[Multibody] `GetJointActuatorIndices(model_instance)` returns empty list pre-finalize #21547

Open siddancha opened 3 weeks ago

siddancha commented 3 weeks ago

Problem

GetJointActuatorIndices(model_instance) seems to return an empty list even when joint actuators are present in the model instance. As a sanity check, both GetJointActuatorByName() and GetJointActuatorIndices() (without any arguments) both correctly return the actuators/indices.

This seems to happen pre-finalize and works fine after the plant is finalized. Maybe I'm missing something?

Reproduction

The corresponding outputs are included as comments.

from pydrake.all import (
    AddModel,
    AddWeld,
    ModelDirective,
    ModelDirectives,
    MultibodyPlant,
    Parser,
    Rotation,
    Transform,
    ProcessModelDirectives,
)

plant = MultibodyPlant(time_step=0.05)
parser = Parser(plant)

directives = [
    ModelDirective(add_model=AddModel(
        name="iiwa",
        file="package://drake_models/iiwa_description/sdf/iiwa14_no_collision.sdf",
    )),
    ModelDirective(add_weld=AddWeld(
        parent="world",
        child="iiwa::iiwa_link_0",
    )),
    ModelDirective(add_model=AddModel(
        name="wsg",
        file="package://drake_models/wsg_50_description/sdf/schunk_wsg_50_with_tip.sdf",
    )),
    ModelDirective(add_weld=AddWeld(
        parent="iiwa::iiwa_link_7",
        child="wsg::body",
        X_PC=Transform(
            translation=[0, 0, 0.09],
            rotation=Rotation.Rpy(deg=[90, 0, 90]),
        ),
    )),
]
ProcessModelDirectives(
    directives=ModelDirectives(directives=directives),
    parser=parser,
)

# plant.Finalize()

model_instance = plant.GetModelInstanceByName("wsg")

# =============================================================================
# Bug: returns no actuator indices
# =============================================================================
wsg_actuator_indices = plant.GetJointActuatorIndices(model_instance)
print(wsg_actuator_indices)
"""
Output:
    []
"""

# =============================================================================
# Sanity check: there are two actuators associated with this instance
# =============================================================================
wsg_actuator_1 = plant.GetJointActuatorByName('left_finger_sliding_joint', model_instance)
wsg_actuator_2 = plant.GetJointActuatorByName('right_finger_sliding_joint', model_instance)
print(wsg_actuator_1); print(wsg_actuator_2)
"""
Output:
  <JointActuator name='left_finger_sliding_joint' index=7 model_instance=3>
  <JointActuator name='right_finger_sliding_joint' index=8 model_instance=3>
"""

# =============================================================================
# Sanity check: print all actuators indices in plant including wsg's
# =============================================================================
all_actuators_indices = plant.GetJointActuatorIndices()
print(all_actuators_indices)
"""
Output:
    [JointActuatorIndex(0), JointActuatorIndex(1), JointActuatorIndex(2), JointActuatorIndex(3), JointActuatorIndex(4), JointActuatorIndex(5), JointActuatorIndex(6), JointActuatorIndex(7), JointActuatorIndex(8)]
"""

Version

1.29.0

What operating system are you using?

Ubuntu 22.04

What installation option are you using?

pip install drake

jwnimmer-tri commented 3 weeks ago

Oops, thanks for reporting. The documentation says that it should "throws std::exception if called pre-finalize". Looks like we forgot to actually check and throw.

siddancha commented 3 weeks ago

@jwnimmer-tri Oh! I didn't realize that throwing an exception was the intended behavior (should've checked the docs!). I'm trying to remove joints (and therefore joint actuators) of a given model instance pre-finalize here. What would be the best way to go about this?

jwnimmer-tri commented 3 weeks ago

It seems like plant.GetJointActuatorIndices() works, so you can walk that list and decide what to remove (or not remove). I assume you'll want to remove any actuators where actuator.joint() refers to a joint that's on the way out.

siddancha commented 3 weeks ago

@jwnimmer-tri I don't fully understand why GetJointActuatorIndices() is supposed to work pre-finalize but GetJointActuatorIndices(model_instance) isn't. But given that's the way it is, you're solution works great for me!

jwnimmer-tri commented 3 weeks ago

It's mostly just an accident of history. Efficiently returning the per-model-instance list takes a bit of extra logic and careful bookkeeping, which was just never implemented. Possibly we should just implement a slow version now (scan all actuators in the plant and accumulate those which patch) instead of implementing throwing. Either way, quietly returning an empty list is terrible!