robotology / idyntree

Multibody Dynamics Library designed for Free Floating Robots
BSD 3-Clause "New" or "Revised" License
166 stars 66 forks source link

URDF export code exports malformed URDF models with limit tags but no velocity or effort attributes #955

Open traversaro opened 2 years ago

traversaro commented 2 years ago

According to the URDF spec (http://wiki.ros.org/urdf/XML/joint), if a joint has a limit tag, then the lower and upper attributes are optional, but the effort and velocity attributes are not exported.

To clarify the problem, if one has the following URDF model named twoLinks.urdf:

<robot name="twoLinks">
    <link name="link1">
        <inertial>
            <mass value="1" />
            <inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01" />
        </inertial>
    </link>
    <joint name="joint_1_2" type="revolute">
        <origin xyz="1 0 0" rpy="0 -0 0" />
        <axis xyz="0 0 1" />
        <parent link="link1" />
        <child link="link2" />
        <limit effort="1.56666666667" lower="-0.698131700798" upper="0.698131700798" velocity="21.2930168743"/>
    </joint>
    <link name="link2">
        <inertial>
            <mass value="1" />
            <inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01" />
            <origin xyz="1 0 0" rpy="0 -0 0" />
        </inertial>
    </link>
</robot>

and it runs it in the idyntree-model-simplify-shapes:

idyntree-model-simplify-shapes -m twoLinks.urdf -o twoLinksModified.urdf

the resulting twoLinksModified.urdf file is:

<?xml version="1.0"?>
<robot name="iDynTreeURDFModelExportModelName">
  <link name="link1">
    <inertial>
      <mass value="1"/>
      <origin xyz="0 0 0" rpy="0 -0 0"/>
      <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
    </inertial>
  </link>
  <joint name="joint_1_2" type="revolute">
    <origin xyz="1 0 0" rpy="0 -0 0"/>
    <axis xyz="0 0 1"/>
    <parent link="link1"/>
    <child link="link2"/>
    <limit lower="-0.698131700798" upper="0.698131700798"/>
  </joint>
  <link name="link2">
    <inertial>
      <mass value="1"/>
      <origin xyz="1 0 0" rpy="0 -0 0"/>
      <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.010000000000000009" iyz="0" izz="0.010000000000000009"/>
    </inertial>
  </link>
</robot>

If we then check the two models with the check_urdf utility provided by the urdfdom library, this is the output:

(idyntree) C:\src\idyntree\src\tests\data>check_urdf twoLinks.urdf
robot name is: twoLinks
---------- Successfully Parsed XML ---------------
root Link: link1 has 1 child(ren)
    child(1):  link2

(idyntree) C:\src\idyntree\src\tests\data>check_urdf twoLinksModified.urdf
Error:   joint limit: no effort
         at line 167 in D:\bld\urdfdom_1623959814707\work\urdf_parser\src\joint.cpp
Error:   Could not parse limit element for joint [joint_1_2]
         at line 565 in D:\bld\urdfdom_1623959814707\work\urdf_parser\src\joint.cpp
Error:   joint xml is not initialized correctly
         at line 206 in D:\bld\urdfdom_1623959814707\work\urdf_parser\src\model.cpp
ERROR: Model Parsing the xml failed
traversaro commented 2 years ago

fyi @Nicogene @francesco-romano @Andrea8Testa

traversaro commented 2 years ago

This is particularly problematic as it prevents to load any URDF file generated by iDynTree by any library that uses urdfdom to load URDF files.

traversaro commented 2 years ago

For the time being, a quick fix to at least being able to create a release of iDynTree that creates valid URDFs is to just add really high limits (like 1e9) for velocity and effort attributes, i.e. after https://github.com/robotology/idyntree/blob/d674619d26b221bb65100b84a250a4c60350fd92/src/model_io/urdf/src/URDFModelExport.cpp#L398 the lines:

        // Workaround for https://github.com/robotology/idyntree/issues/955
        double reallyHighLimit = 1e9;
        ok = ok && doubleToStringWithClassicLocale(reallyHighLimit, bufStr);
        xmlNewProp(limit_xml, BAD_CAST "effort", BAD_CAST bufStr.c_str());
        ok = ok && doubleToStringWithClassicLocale(reallyHighLimit, bufStr);
        xmlNewProp(limit_xml, BAD_CAST "velocity", BAD_CAST bufStr.c_str());
traversaro commented 2 years ago

@Andrea8Testa given that you have a commit that solves this in https://github.com/Andrea8Testa/idyntree/commit/6ac5ad63af33d5290ff20c75bcbc66f10fd2adec , can you open a PR for this? If necessary I can help you doing this, otherwise you can just follow GitHub docs in https://docs.github.com/en/pull-requests/collaborating-with-pull-requests/proposing-changes-to-your-work-with-pull-requests/creating-a-pull-request , thanks!

traversaro commented 2 years ago

A proper solution is tracked in https://github.com/robotology/idyntree/issues/958 .