RobotLocomotion / drake

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

SDFormat include of URDF treats warnings as errors #21472

Open lcbw opened 1 month ago

lcbw commented 1 month ago

What happened?

Labels: component: parsing configuration: linux

On attempt to parse the robotiq 85 gripper URDF as can be found in the apt package ros-humble-robotiq-description into Drake, warnings were thrown against using mimic joints with Drake, but then the file failed to parse anyway. Commenting out the mimic joints resolved the problem, indicating that the mimic joints aren't being ignored like the warning said they would be if they had been left in. [or something similar]

Example warning: Joint 'robotiq_85_right_knuckle_joint' specifies a mimic element that will be ignored. Mimic elements are currently only supported by MultibodyPlant with a discrete time step and using DiscreteContactSolver::kSap.

Example file which failed to parse:

<?xml version="1.0" ?>
<sdf version="1.7">
  <world name="gripper_test">
    <include>
      <uri>package://mast/descriptions/robotiq_testing/ur10e.urdf</uri>
      <name>robot</name>
    </include>

    <joint name="world_to_robot" type="fixed">
      <parent>world</parent>
      <child>robot::base_link</child>
    </joint>
    <include>
      <uri>package://mast/descriptions/robotiq_testing/gripper.urdf</uri>
      <name>gripper_body</name>
      <pose relative_to="robot::tool0">0 0 0 0 0 0</pose>
    </include>
    <joint name="robot_to_gripper_body" type="fixed">
      <parent>robot::tool0</parent>
      <child>gripper_body::ur_to_robotiq_link</child>
      <pose relative_to="robot::tool0">0 0 0 0 0 0</pose>
    </joint>
  </world>
</sdf>

Version

1.27.0

What operating system are you using?

Ubuntu 22.04

What installation option are you using?

pip install drake

Relevant log output

WARNING:drake:/home/user/workspaces/my_ws/install/my_ws/share/my_ws/descriptions/robotiq_testing/gripper.urdf:128: warning: Joint 'robotiq_85_right_knuckle_joint' specifies a mimic element that will be ignored. Mimic elements are currently only supported by MultibodyPlant with a discrete time step and using DiscreteContactSolver::kSap.
WARNING:drake:/home/user/workspaces/my_ws/install/my_ws/share/my_ws/descriptions/robotiq_testing/gripper.urdf:145: warning: Joint 'robotiq_85_left_inner_knuckle_joint' specifies a mimic element that will be ignored. Mimic elements are currently only supported by MultibodyPlant with a discrete time step and using DiscreteContactSolver::kSap.
WARNING:drake:/home/user/workspaces/my_ws/install/my_ws/share/my_ws/descriptions/robotiq_testing/gripper.urdf:152: warning: Joint 'robotiq_85_right_inner_knuckle_joint' specifies a mimic element that will be ignored. Mimic elements are currently only supported by MultibodyPlant with a discrete time step and using DiscreteContactSolver::kSap.
WARNING:drake:/home/user/workspaces/my_ws/install/my_ws/share/my_ws/descriptions/robotiq_testing/gripper.urdf:159: warning: Joint 'robotiq_85_left_finger_tip_joint' specifies a mimic element that will be ignored. Mimic elements are currently only supported by MultibodyPlant with a discrete time step and using DiscreteContactSolver::kSap.
WARNING:drake:/home/user/workspaces/my_ws/install/my_ws/share/my_ws/descriptions/robotiq_testing/gripper.urdf:166: warning: Joint 'robotiq_85_right_finger_tip_joint' specifies a mimic element that will be ignored. Mimic elements are currently only supported by MultibodyPlant with a discrete time step and using DiscreteContactSolver::kSap.
Traceback (most recent call last):
  File "/snap/pycharm-community/378/plugins/python-ce/helpers/pydev/pydevd.py", line 1534, in _exec
    pydev_imports.execfile(file, globals, locals)  # execute the script
  File "/snap/pycharm-community/378/plugins/python-ce/helpers/pydev/_pydev_imps/_pydev_execfile.py", line 18, in execfile
    exec(compile(contents+"\n", file, 'exec'), glob, loc)
  File "/home/user/workspaces/my_ws/src/my_ws/scripts/gripper_test.py", line 313, in <module>
    main()
  File "/home/user/workspaces/my_ws/src/my_ws/scripts/gripper_test.py", line 245, in main
    rdb.parser().AddModels(FindResourceOrThrow(args.resource))
RuntimeError: error: Child frame with name[gripper_body::ur_to_robotiq_link] specified by joint with name[robot_to_gripper_body] not found in world with name[gripper_test].
jwnimmer-tri commented 1 month ago

Thanks for your report! I see that the ROS apt package ros-humble-robotiq-description contains the Xacro input files, but not the actual URDF file literally. In order for us to reproduce the problem (without having to guess how you ran Xacro), could you please attach the exact URDF file that you were trying to parse? Thanks.

lcbw commented 1 month ago

gripper.txt you'll need to rename this to gripper.urdf but interestingly enough github does not allow you to attach .urdf files

jwnimmer-tri commented 1 month ago

Ah, okay. For a while I wasn't able to reproduce the problem, until I noticed the gripper file you provided had the mimic elements commented out. Once I put them back in, I can reproduce the problem.

I think the bug is that when there is an SDFormat <include> element that refers to URDF and the URDF has warnings, somehow the warning is seen by SDFormat as a error (instead of a warning) and no multibody elements are added to the tree. (And therefore the SDFormat stanza to add a joint to a missing body rightly crashes.)

Thanks for reporting, this seems somewhat serious to have never been seen before.