Open traversaro opened 2 years ago
fyi @Nicogene @francesco-romano @Andrea8Testa
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.
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());
@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!
A proper solution is tracked in https://github.com/robotology/idyntree/issues/958 .
According to the URDF spec (http://wiki.ros.org/urdf/XML/joint), if a joint has a
limit
tag, then thelower
andupper
attributes are optional, but theeffort
andvelocity
attributes are not exported.To clarify the problem, if one has the following URDF model named
twoLinks.urdf
:and it runs it in the
idyntree-model-simplify-shapes
:the resulting
twoLinksModified.urdf
file is:If we then check the two models with the
check_urdf
utility provided by the urdfdom library, this is the output: