Open vincekurtz opened 2 years ago
I can confirm:
--- a/bindings/pydrake/multibody/BUILD.bazel
+++ b/bindings/pydrake/multibody/BUILD.bazel
@@ -271,6 +271,7 @@ drake_py_unittest(
name = "plant_test",
data = [
":models",
+ "//examples/acrobot:models",
"//manipulation/models/iiwa_description:models",
"//manipulation/models/wsg_50_description:models",
"//multibody/benchmarks/acrobot:models",
--- a/bindings/pydrake/multibody/test/plant_test.py
+++ b/bindings/pydrake/multibody/test/plant_test.py
@@ -356,6 +356,12 @@ class TestPlant(unittest.TestCase):
model_instance=model_instance))
self.assertIn("acrobot", plant.GetTopologyGraphvizString())
+ def test_16607(self):
+ plant = MultibodyPlant_[float](1e-3)
+ urdf = FindResourceOrThrow("drake/examples/acrobot/Acrobot.urdf")
+ robot = Parser(plant=plant).AddModelFromFile(urdf)
+ plant.GetBodiesWeldedTo(plant.world_body())
+
def _test_multibody_tree_element_mixin(self, T, element):
cls = type(element)
self.assertIsInstance(element.index(), get_index_class(cls, T))
bazel test -c dbg //bindings/pydrake/multibody:py/plant_test --test_arg=TestPlant.test_16607
...
File ".../drake/bindings/pydrake/multibody/test/plant_test.py", line 363, in test_16607
plant.GetBodiesWeldedTo(plant.world_body())
RuntimeError: return_value_policy = copy, but type drake::multibody::RigidBody<double> is non-copyable!
FYI #14345 #14411
@EricCousineau-TRI can you help us figure out where to choose return_value_policy::reference
for the py_keep_alive_iterable<py::list>
?
but does not occur when the model isn't loaded from urdf,
I wonder if this is because the list of welded bodies is wrong (missing the non-world body), which could be a bug in the C++ multibody graph accounting @joemasterjohn @amcastro-tri FYI.
Edit: Nevermind.
but does not occur when the model isn't loaded from urdf,
I wonder if this is because the list of welded bodies is wrong (missing the non-world body), which could be a bug in the C++ multibody graph accounting @joemasterjohn @amcastro-tri FYI.
Actually, the result is correct:
[<RigidBody_[float] name='WorldBody' index=0 model_instance=0>,
<RigidBody_[float] name='base_link' index=1 model_instance=2>]
There is also a C++ unit test that checks this:
So, not an MbP C++ bug, it's just some pydrake bindings issue. I have no idea why one works in pydrake and the other doesn't. Hopefully @EricCousineau-TRI can help once he has time.
Oh, I know why the final example works:
robot_instance = plant.AddModelInstance("robot")
robot = plant.AddRigidBody("base_link",robot_instance, SpatialInertia())
plant.WeldFrames(plant.world_frame(), plant.GetFrameByName("base_link"))
The base_link Body<double>&
reference is returned by plant.AddRigidBody
back into Python, so pybind11 knows that that reference is internal and already owned because Python added the body, so it knows not to copy it again. So that mystery is solved, at least.
The overall bug remains though -- the py_keep_alive_iterable<py::list>
binding is broken, and needs to use some kind of reference_internal
.
For now, here is a work-around ... if you fetch all of the bodies prior to asking for what's welded, then we can avoid the exception:
all_bodies = [plant.get_body(BodyIndex(i)) for i in range(plant.num_bodies())]
welded_bodies = plant.GetBodiesWeldedTo(plant.world_body())
This occurs in pydrake: I haven't tried in c++. Minimal reproduction example:
The last line fails with the following error:
This error also occurs when a weld joint is added manually, e.g.,
but does not occur when the model isn't loaded from urdf, e.g.,
Platform details:
c95ac12807
)