From 2d8acc9caf07316020bca8798acba1f8025d8d98 Mon Sep 17 00:00:00 2001 From: Christoph Hertzberg Date: Tue, 2 Aug 2016 17:22:11 +0200 Subject: [PATCH 1/2] fix deprecated header --- src/kdl_parser.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/kdl_parser.cpp b/src/kdl_parser.cpp index 308de4d..ea70dfb 100644 --- a/src/kdl_parser.cpp +++ b/src/kdl_parser.cpp @@ -39,7 +39,7 @@ #include #include -#include +#include using namespace std; using namespace KDL; From bb6cc9733b9e14a249d977ac3caad1590af603f7 Mon Sep 17 00:00:00 2001 From: Christoph Hertzberg Date: Tue, 2 Aug 2016 17:23:29 +0200 Subject: [PATCH 2/2] Use SharedPtr typedefs by urdf instead of boost::shared_ptr (compatibility with newer urdf versions) --- src/kdl_parser.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/kdl_parser.cpp b/src/kdl_parser.cpp index ea70dfb..2ae45ed 100644 --- a/src/kdl_parser.cpp +++ b/src/kdl_parser.cpp @@ -35,7 +35,7 @@ /* Author: Wim Meeussen */ #include "kdl_parser.hpp" -#include +#include #include #include @@ -66,7 +66,7 @@ Frame toKdl(urdf::Pose p) } // construct joint -Joint toKdl(boost::shared_ptr jnt) +Joint toKdl(urdf::JointSharedPtr jnt) { Frame F_parent_jnt = toKdl(jnt->parent_to_joint_origin_transform); @@ -92,7 +92,7 @@ Joint toKdl(boost::shared_ptr jnt) } // construct inertia -RigidBodyInertia toKdl(boost::shared_ptr i) +RigidBodyInertia toKdl(urdf::InertialSharedPtr i) { Frame origin = toKdl(i->origin); // kdl specifies the inertia in the reference frame of the link, the urdf specifies the inertia in the inertia reference frame @@ -101,9 +101,9 @@ RigidBodyInertia toKdl(boost::shared_ptr i) // recursive function to walk through tree -bool addChildrenToTree(boost::shared_ptr root, Tree& tree) +bool addChildrenToTree(urdf::LinkConstSharedPtr root, Tree& tree) { - std::vector > children = root->child_links; + std::vector children = root->child_links; LOG_DEBUG("DEBUG: Link %s had %i children", root->name.c_str(), (int)children.size()); // constructs the optional inertia @@ -151,7 +151,7 @@ bool treeFromParam(const string& param, Tree& tree) bool treeFromString(const string& xml, Tree& tree) { - boost::shared_ptr robot_model = urdf::parseURDF(xml); + urdf::ModelInterfaceSharedPtr robot_model = urdf::parseURDF(xml); return treeFromUrdfModel(*robot_model, tree); }