Index: kdl_parser/src/kdl_parser.cpp =================================================================== --- kdl_parser.orig/src/kdl_parser.cpp +++ kdl_parser/src/kdl_parser.cpp @@ -64,7 +64,7 @@ Frame toKdl(urdf::Pose p) } // construct joint -Joint toKdl(boost::shared_ptr jnt) +Joint toKdl(std::shared_ptr jnt) { Frame F_parent_jnt = toKdl(jnt->parent_to_joint_origin_transform); @@ -93,7 +93,7 @@ Joint toKdl(boost::shared_ptr i) +RigidBodyInertia toKdl(std::shared_ptr i) { Frame origin = toKdl(i->origin); @@ -124,9 +124,9 @@ RigidBodyInertia toKdl(boost::shared_ptr // recursive function to walk through tree -bool addChildrenToTree(boost::shared_ptr root, Tree& tree) +bool addChildrenToTree(std::shared_ptr root, Tree& tree) { - std::vector > children = root->child_links; + std::vector > children = root->child_links; ROS_DEBUG("Link %s had %i children", root->name.c_str(), (int)children.size()); // constructs the optional inertia