diff --git a/kdl_parser/src/kdl_parser.cpp b/kdl_parser/src/kdl_parser.cpp index d1b88ca..ae23ac4 100644 --- a/kdl_parser/src/kdl_parser.cpp +++ b/kdl_parser/src/kdl_parser.cpp @@ -106,7 +106,7 @@ RigidBodyInertia toKdl(boost::shared_ptr i) bool addChildrenToTree(boost::shared_ptr root, Tree& tree) { std::vector > children = root->child_links; - ROS_DEBUG("Link %s had %i children", root->name.c_str(), children.size()); + ROS_DEBUG("Link %s had %u children", root->name.c_str(), children.size()); // constructs the optional inertia RigidBodyInertia inert(0);