summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
Diffstat (limited to 'dev-ros/kdl_parser/files')
-rw-r--r--dev-ros/kdl_parser/files/urdfdom1.patch34
1 files changed, 34 insertions, 0 deletions
diff --git a/dev-ros/kdl_parser/files/urdfdom1.patch b/dev-ros/kdl_parser/files/urdfdom1.patch
new file mode 100644
index 000000000000..c4b1d5c6e586
--- /dev/null
+++ b/dev-ros/kdl_parser/files/urdfdom1.patch
@@ -0,0 +1,34 @@
+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<urdf::Joint> jnt)
++Joint toKdl(std::shared_ptr<urdf::Joint> jnt)
+ {
+ Frame F_parent_jnt = toKdl(jnt->parent_to_joint_origin_transform);
+
+@@ -93,7 +93,7 @@ Joint toKdl(boost::shared_ptr<urdf::Join
+ }
+
+ // construct inertia
+-RigidBodyInertia toKdl(boost::shared_ptr<urdf::Inertial> i)
++RigidBodyInertia toKdl(std::shared_ptr<urdf::Inertial> 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<const urdf::Link> root, Tree& tree)
++bool addChildrenToTree(std::shared_ptr<const urdf::Link> root, Tree& tree)
+ {
+- std::vector<boost::shared_ptr<urdf::Link> > children = root->child_links;
++ std::vector<std::shared_ptr<urdf::Link> > children = root->child_links;
+ ROS_DEBUG("Link %s had %i children", root->name.c_str(), (int)children.size());
+
+ // constructs the optional inertia