add warning when root link has inertia, because KDL does not support root link with inertia
This commit is contained in:
parent
2d331a60ff
commit
f7735d9607
|
@ -168,6 +168,10 @@ bool treeFromUrdfModel(const urdf::Model& robot_model, Tree& tree)
|
|||
{
|
||||
tree = Tree(robot_model.getRoot()->name);
|
||||
|
||||
// warn if root link has inertia. KDL does not support this
|
||||
if (robot_model.getRoot()->inertial)
|
||||
ROS_WARN("The root link %s has an inertia specified in the URDF, but KDL does not support a root link with an inertia. As a workaround, you can add an extra dummy link to your URDF.", robot_model.getRoot()->name.c_str());
|
||||
|
||||
// add all children
|
||||
for (size_t i=0; i<robot_model.getRoot()->child_links.size(); i++)
|
||||
if (!addChildrenToTree(robot_model.getRoot()->child_links[i], tree))
|
||||
|
|
Loading…
Reference in New Issue