[sdformat] 01/01: Add patch to replace boost pointers by std

Jose Luis Rivero jrivero-guest at moszumanska.debian.org
Tue Aug 30 22:52:03 UTC 2016


This is an automated email from the git hooks/post-receive script.

jrivero-guest pushed a commit to branch master
in repository sdformat.

commit b3cfbe3447c549acb5f7bc4f123fb1f9136070b7
Author: Jose Luis Rivero <jrivero at osrfoundation.org>
Date:   Tue Aug 30 22:50:41 2016 +0000

    Add patch to replace boost pointers by std
    
    After the new urdfdom-headers needs to migrate pointers
    to std.
---
 debian/patches/0003-urdfdom-replace-boost.patch | 274 ++++++++++++++++++++++++
 debian/patches/series                           |   1 +
 2 files changed, 275 insertions(+)

diff --git a/debian/patches/0003-urdfdom-replace-boost.patch b/debian/patches/0003-urdfdom-replace-boost.patch
new file mode 100644
index 0000000..a6f0b55
--- /dev/null
+++ b/debian/patches/0003-urdfdom-replace-boost.patch
@@ -0,0 +1,274 @@
+Description: use std pointers instead of boost
+Author: Jose Luis Rivero <jrivero at osrfoundation.org>
+Forwarded: No
+
+diff --git a/src/parser_urdf.cc b/src/parser_urdf.cc
+index fe9bb9b..a343b22 100644
+--- a/src/parser_urdf.cc
++++ b/src/parser_urdf.cc
+@@ -32,10 +34,10 @@
+ 
+ using namespace sdf;
+ 
+-typedef boost::shared_ptr<urdf::Collision> UrdfCollisionPtr;
+-typedef boost::shared_ptr<urdf::Visual> UrdfVisualPtr;
+-typedef boost::shared_ptr<urdf::Link> UrdfLinkPtr;
+-typedef boost::shared_ptr<const urdf::Link> ConstUrdfLinkPtr;
++typedef std::shared_ptr<urdf::Collision> UrdfCollisionPtr;
++typedef std::shared_ptr<urdf::Visual> UrdfVisualPtr;
++typedef std::shared_ptr<urdf::Link> UrdfLinkPtr;
++typedef std::shared_ptr<const urdf::Link> ConstUrdfLinkPtr;
+ typedef std::shared_ptr<TiXmlElement> TiXmlElementPtr;
+ typedef std::shared_ptr<SDFExtension> SDFExtensionPtr;
+ typedef std::map<std::string, std::vector<SDFExtensionPtr> >
+@@ -78,7 +80,7 @@ void InsertSDFExtensionJoint(TiXmlElement *_elem,
+ /// reduced fixed joints:  check if a fixed joint should be lumped
+ ///   checking both the joint type and if disabledFixedJointLumping
+ ///   option is set
+-bool FixedJointShouldBeReduced(boost::shared_ptr<urdf::Joint> _jnt);
++bool FixedJointShouldBeReduced(std::shared_ptr<urdf::Joint> _jnt);
+ 
+ /// reduced fixed joints:  apply transform reduction for ray sensors
+ ///   in extensions when doing fixed joint reduction
+@@ -217,9 +219,9 @@ std::string Values2str(unsigned int _count, const double *_values);
+ 
+ 
+ void CreateGeometry(TiXmlElement* _elem,
+-    boost::shared_ptr<urdf::Geometry> _geometry);
++    std::shared_ptr<urdf::Geometry> _geometry);
+ 
+-std::string GetGeometryBoundingBox(boost::shared_ptr<urdf::Geometry> _geometry,
++std::string GetGeometryBoundingBox(std::shared_ptr<urdf::Geometry> _geometry,
+     double *_sizeVals);
+ 
+ ignition::math::Pose3d inverseTransformToParentFrame(
+@@ -326,10 +328,10 @@ std::string Vector32Str(const urdf::Vector3 _vector)
+ // In urdfdom_headers 0.2.x, there are group names for
+ // visuals and collisions in Link class:
+ //   std::map<std::string,
+-//     boost::shared_ptr<std::vector<boost::shared_ptr<Visual> > >
++//     std::shared_ptr<std::vector<std::shared_ptr<Visual> > >
+ //     > visual_groups;
+ //   std::map<std::string,
+-//     boost::shared_ptr<std::vector<boost::shared_ptr<Collision> > >
++//     std::shared_ptr<std::vector<std::shared_ptr<Collision> > >
+ //     > collision_groups;
+ // and we have Visual::group_name and
+ //             Collision::group_name
+@@ -345,7 +347,7 @@ void ReduceCollisionToParent(UrdfLinkPtr _parentLink,
+     UrdfCollisionPtr _collision)
+ {
+ #ifndef URDF_GE_0P3
+-  boost::shared_ptr<std::vector<UrdfCollisionPtr> > cols;
++  std::shared_ptr<std::vector<UrdfCollisionPtr> > cols;
+   cols = _parentLink->getCollisions(_name);
+ 
+   if (!cols)
+@@ -404,10 +406,10 @@ void ReduceCollisionToParent(UrdfLinkPtr _parentLink,
+ // In urdfdom_headers 0.2.x, there are group names for
+ // visuals and collisions in Link class:
+ //   std::map<std::string,
+-//     boost::shared_ptr<std::vector<boost::shared_ptr<Visual> > >
++//     std::shared_ptr<std::vector<std::shared_ptr<Visual> > >
+ //     > visual_groups;
+ //   std::map<std::string,
+-//     boost::shared_ptr<std::vector<boost::shared_ptr<Collision> > >
++//     std::shared_ptr<std::vector<std::shared_ptr<Collision> > >
+ //     > collision_groups;
+ // and we have Visual::group_name and
+ //             Collision::group_name
+@@ -423,7 +425,7 @@ void ReduceVisualToParent(UrdfLinkPtr _parentLink,
+     UrdfVisualPtr _visual)
+ {
+ #ifndef URDF_GE_0P3
+-  boost::shared_ptr<std::vector<UrdfVisualPtr> > viss;
++  std::shared_ptr<std::vector<UrdfVisualPtr> > viss;
+   viss = _parentLink->getVisuals(_name);
+ 
+   if (!viss)
+@@ -946,7 +948,7 @@ void ReduceVisualsToParent(UrdfLinkPtr _link)
+   // (original parent link name before lumping/reducing).
+ #ifndef URDF_GE_0P3
+   for (std::map<std::string,
+-      boost::shared_ptr<std::vector<UrdfVisualPtr> > >::iterator
++      std::shared_ptr<std::vector<UrdfVisualPtr> > >::iterator
+       visualsIt = _link->visual_groups.begin();
+       visualsIt != _link->visual_groups.end(); ++visualsIt)
+   {
+@@ -1053,7 +1055,7 @@ void ReduceCollisionsToParent(UrdfLinkPtr _link)
+   // (original parent link name before lumping/reducing).
+ #ifndef URDF_GE_0P3
+   for (std::map<std::string,
+-      boost::shared_ptr<std::vector<UrdfCollisionPtr> > >::iterator
++      std::shared_ptr<std::vector<UrdfCollisionPtr> > >::iterator
+       collisionsIt = _link->collision_groups.begin();
+       collisionsIt != _link->collision_groups.end(); ++collisionsIt)
+   {
+@@ -1156,7 +1158,7 @@ void ReduceJointsToParent(UrdfLinkPtr _link)
+   // a parent link up stream that does not have a fixed parentJoint
+   for (unsigned int i = 0 ; i < _link->child_links.size() ; ++i)
+   {
+-    boost::shared_ptr<urdf::Joint> parentJoint =
++    std::shared_ptr<urdf::Joint> parentJoint =
+       _link->child_links[i]->parent_joint;
+     if (!FixedJointShouldBeReduced(parentJoint))
+     {
+@@ -2335,7 +2337,7 @@ void InsertSDFExtensionRobot(TiXmlElement *_elem)
+ 
+ ////////////////////////////////////////////////////////////////////////////////
+ void CreateGeometry(TiXmlElement* _elem,
+-    boost::shared_ptr<urdf::Geometry> _geom)
++    std::shared_ptr<urdf::Geometry> _geom)
+ {
+   TiXmlElement *sdfGeometry = new TiXmlElement("geometry");
+ 
+@@ -2347,8 +2349,8 @@ void CreateGeometry(TiXmlElement* _elem,
+     case urdf::Geometry::BOX:
+       type = "box";
+       {
+-        boost::shared_ptr<const urdf::Box> box;
+-        box = boost::dynamic_pointer_cast< const urdf::Box >(_geom);
++        std::shared_ptr<const urdf::Box> box;
++        box = std::dynamic_pointer_cast< const urdf::Box >(_geom);
+         int sizeCount = 3;
+         double sizeVals[3];
+         sizeVals[0] = box->dim.x;
+@@ -2362,8 +2364,8 @@ void CreateGeometry(TiXmlElement* _elem,
+     case urdf::Geometry::CYLINDER:
+       type = "cylinder";
+       {
+-        boost::shared_ptr<const urdf::Cylinder> cylinder;
+-        cylinder = boost::dynamic_pointer_cast<const urdf::Cylinder >(_geom);
++        std::shared_ptr<const urdf::Cylinder> cylinder;
++        cylinder = std::dynamic_pointer_cast<const urdf::Cylinder >(_geom);
+         geometryType = new TiXmlElement(type);
+         AddKeyValue(geometryType, "length",
+             Values2str(1, &cylinder->length));
+@@ -2374,8 +2376,8 @@ void CreateGeometry(TiXmlElement* _elem,
+     case urdf::Geometry::SPHERE:
+       type = "sphere";
+       {
+-        boost::shared_ptr<const urdf::Sphere> sphere;
+-        sphere = boost::dynamic_pointer_cast<const urdf::Sphere >(_geom);
++        std::shared_ptr<const urdf::Sphere> sphere;
++        sphere = std::dynamic_pointer_cast<const urdf::Sphere >(_geom);
+         geometryType = new TiXmlElement(type);
+         AddKeyValue(geometryType, "radius",
+             Values2str(1, &sphere->radius));
+@@ -2384,8 +2386,8 @@ void CreateGeometry(TiXmlElement* _elem,
+     case urdf::Geometry::MESH:
+       type = "mesh";
+       {
+-        boost::shared_ptr<const urdf::Mesh> mesh;
+-        mesh = boost::dynamic_pointer_cast<const urdf::Mesh >(_geom);
++        std::shared_ptr<const urdf::Mesh> mesh;
++        mesh = std::dynamic_pointer_cast<const urdf::Mesh >(_geom);
+         geometryType = new TiXmlElement(type);
+         AddKeyValue(geometryType, "scale", Vector32Str(mesh->scale));
+         // do something more to meshes
+@@ -2447,7 +2449,7 @@ void CreateGeometry(TiXmlElement* _elem,
+ 
+ ////////////////////////////////////////////////////////////////////////////////
+ std::string GetGeometryBoundingBox(
+-    boost::shared_ptr<urdf::Geometry> _geom, double *_sizeVals)
++    std::shared_ptr<urdf::Geometry> _geom, double *_sizeVals)
+ {
+   std::string type;
+ 
+@@ -2456,8 +2458,8 @@ std::string GetGeometryBoundingBox(
+     case urdf::Geometry::BOX:
+       type = "box";
+       {
+-        boost::shared_ptr<const urdf::Box> box;
+-        box = boost::dynamic_pointer_cast<const urdf::Box >(_geom);
++        std::shared_ptr<const urdf::Box> box;
++        box = std::dynamic_pointer_cast<const urdf::Box >(_geom);
+         _sizeVals[0] = box->dim.x;
+         _sizeVals[1] = box->dim.y;
+         _sizeVals[2] = box->dim.z;
+@@ -2466,8 +2468,8 @@ std::string GetGeometryBoundingBox(
+     case urdf::Geometry::CYLINDER:
+       type = "cylinder";
+       {
+-        boost::shared_ptr<const urdf::Cylinder> cylinder;
+-        cylinder = boost::dynamic_pointer_cast<const urdf::Cylinder >(_geom);
++        std::shared_ptr<const urdf::Cylinder> cylinder;
++        cylinder = std::dynamic_pointer_cast<const urdf::Cylinder >(_geom);
+         _sizeVals[0] = cylinder->radius * 2;
+         _sizeVals[1] = cylinder->radius * 2;
+         _sizeVals[2] = cylinder->length;
+@@ -2476,16 +2478,16 @@ std::string GetGeometryBoundingBox(
+     case urdf::Geometry::SPHERE:
+       type = "sphere";
+       {
+-        boost::shared_ptr<const urdf::Sphere> sphere;
+-        sphere = boost::dynamic_pointer_cast<const urdf::Sphere >(_geom);
++        std::shared_ptr<const urdf::Sphere> sphere;
++        sphere = std::dynamic_pointer_cast<const urdf::Sphere >(_geom);
+         _sizeVals[0] = _sizeVals[1] = _sizeVals[2] = sphere->radius * 2;
+       }
+       break;
+     case urdf::Geometry::MESH:
+       type = "trimesh";
+       {
+-        boost::shared_ptr<const urdf::Mesh> mesh;
+-        mesh = boost::dynamic_pointer_cast<const urdf::Mesh >(_geom);
++        std::shared_ptr<const urdf::Mesh> mesh;
++        mesh = std::dynamic_pointer_cast<const urdf::Mesh >(_geom);
+         _sizeVals[0] = mesh->scale.x;
+         _sizeVals[1] = mesh->scale.y;
+         _sizeVals[2] = mesh->scale.z;
+@@ -2509,7 +2511,7 @@ void PrintCollisionGroups(UrdfLinkPtr _link)
+     << static_cast<int>(_link->collision_groups.size())
+     << "] collisions.\n";
+   for (std::map<std::string,
+-      boost::shared_ptr<std::vector<UrdfCollisionPtr > > >::iterator
++      std::shared_ptr<std::vector<UrdfCollisionPtr > > >::iterator
+       colsIt = _link->collision_groups.begin();
+       colsIt != _link->collision_groups.end(); ++colsIt)
+   {
+@@ -2902,7 +2904,7 @@ void CreateCollisions(TiXmlElement* _elem,
+   //   lumped meshes (fixed joint reduction)
+ #ifndef URDF_GE_0P3
+   for (std::map<std::string,
+-      boost::shared_ptr<std::vector<UrdfCollisionPtr> > >::const_iterator
++      std::shared_ptr<std::vector<UrdfCollisionPtr> > >::const_iterator
+       collisionsIt = _link->collision_groups.begin();
+       collisionsIt != _link->collision_groups.end(); ++collisionsIt)
+   {
+@@ -3024,7 +3026,7 @@ void CreateVisuals(TiXmlElement* _elem,
+   //   lumped meshes (fixed joint reduction)
+ #ifndef URDF_GE_0P3
+   for (std::map<std::string,
+-      boost::shared_ptr<std::vector<UrdfVisualPtr> > >::const_iterator
++      std::shared_ptr<std::vector<UrdfVisualPtr> > >::const_iterator
+       visualsIt = _link->visual_groups.begin();
+       visualsIt != _link->visual_groups.end(); ++visualsIt)
+   {
+@@ -3397,7 +3399,7 @@ TiXmlDocument URDF2SDF::InitModelString(const std::string &_urdfStr,
+   g_enforceLimits = _enforceLimits;
+ 
+   // Create a RobotModel from string
+-  boost::shared_ptr<urdf::ModelInterface> robotModel =
++  std::shared_ptr<urdf::ModelInterface> robotModel =
+     urdf::parseURDF(_urdfStr.c_str());
+ 
+   // an xml object to hold the xml result
+@@ -3439,7 +3441,7 @@ TiXmlDocument URDF2SDF::InitModelString(const std::string &_urdfStr,
+   // fixed joint lumping only for selected joints
+   if (g_reduceFixedJoints)
+     ReduceFixedJoints(robot,
+-        (boost::const_pointer_cast< urdf::Link >(rootLink)));
++        (std::const_pointer_cast< urdf::Link >(rootLink)));
+ 
+   if (rootLink->name == "world")
+   {
+@@ -3500,7 +3502,7 @@ TiXmlDocument URDF2SDF::InitModelFile(const std::string &_filename)
+ }
+ 
+ ////////////////////////////////////////////////////////////////////////////////
+-bool FixedJointShouldBeReduced(boost::shared_ptr<urdf::Joint> _jnt)
++bool FixedJointShouldBeReduced(std::shared_ptr<urdf::Joint> _jnt)
+ {
+     // A joint should be lumped only if its type is fixed and
+     // the disabledFixedJointLumping joint option is not set
diff --git a/debian/patches/series b/debian/patches/series
index d873eff..6f41405 100644
--- a/debian/patches/series
+++ b/debian/patches/series
@@ -1,2 +1,3 @@
 0001-c++11-unconditional.patch
 0002_use_system_gtest.patch
+0003-urdfdom-replace-boost.patch

-- 
Alioth's /usr/local/bin/git-commit-notice on /srv/git.debian.org/git/debian-science/packages/sdformat.git



More information about the debian-science-commits mailing list