[sdformat] 02/05: Remove patch. Already merged upstream \o/

Jose Luis Rivero jrivero-guest at moszumanska.debian.org
Wed Feb 4 02:40:29 UTC 2015


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

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

commit 8b55889a1bbc8d70d111109ffa38476efba170b1
Author: Jose Luis Rivero <jrivero at osrfoundation.org>
Date:   Wed Feb 4 02:48:34 2015 +0100

    Remove patch. Already merged upstream \o/
---
 debian/patches/0001-fix-external-urdfdom.patch | 1133 ------------------------
 debian/patches/series                          |    1 -
 2 files changed, 1134 deletions(-)

diff --git a/debian/patches/0001-fix-external-urdfdom.patch b/debian/patches/0001-fix-external-urdfdom.patch
deleted file mode 100644
index e615119..0000000
--- a/debian/patches/0001-fix-external-urdfdom.patch
+++ /dev/null
@@ -1,1133 +0,0 @@
-From: Jose Luis Rivero <jrivero at osrfoundation.org>
-Date: Mon, 21 Nov 2014 01:45 +0200
-Subject: Patch to use new version of urdfdom 0.3.0
-Bug: https://bitbucket.org/osrf/sdformat/issue/59
-Origin: https://bitbucket.org/osrf/sdformat/pull-request/122
-
-Last commit in pull request: afad3d3e12e43f42552d41c0114053ce91282562
-
-diff -r b5ef37039cc7aaf7d3ba69cf30b5be54ec30b8f7 -r 944d3f38d9a4d895996acc45692f05988e58398a cmake/SearchForStuff.cmake
---- a/cmake/SearchForStuff.cmake
-+++ b/cmake/SearchForStuff.cmake
-@@ -79,6 +79,9 @@
-     set(URDF_INCLUDE_DIRS ${URDF_INCLUDEDIR})
-     set(URDF_LIBRARY_DIRS ${URDF_LIBDIR})
-   endif()
-+else()
-+  # the internal copy is currently 0.3.0
-+  set (URDF_GE_0P3 TRUE)
- endif()
- 
- #################################################
-diff -r b5ef37039cc7aaf7d3ba69cf30b5be54ec30b8f7 -r 944d3f38d9a4d895996acc45692f05988e58398a cmake/sdf_config.h.in
---- a/cmake/sdf_config.h.in
-+++ b/cmake/sdf_config.h.in
-@@ -26,7 +26,7 @@
- #cmakedefine BUILD_TYPE_RELEASE 1
- #cmakedefine HAVE_URDFDOM 1
- #cmakedefine USE_EXTERNAL_URDF 1
--#cmakedefine URDF_GT_0P3 1
-+#cmakedefine URDF_GE_0P3 1
- 
- #define SDF_SHARE_PATH "${CMAKE_INSTALL_PREFIX}/share/"
- #define SDF_VERSION_PATH "${CMAKE_INSTALL_PREFIX}/share/sdformat/${SDF_PKG_VERSION}"
-diff -r b5ef37039cc7aaf7d3ba69cf30b5be54ec30b8f7 -r 944d3f38d9a4d895996acc45692f05988e58398a src/parser_urdf.cc
---- a/src/parser_urdf.cc
-+++ b/src/parser_urdf.cc
-@@ -298,82 +298,103 @@
- 
- ////////////////////////////////////////////////////////////////////////////////
- void ReduceCollisionToParent(UrdfLinkPtr _link,
--    const std::string &_groupName, UrdfCollisionPtr _collision)
-+#ifndef URDF_GE_0P3
-+    const std::string &_groupName,
-+#else
-+    const std::string &/*_groupName*/,
-+#endif
-+    UrdfCollisionPtr _collision)
- {
--  boost::shared_ptr<std::vector<UrdfCollisionPtr> > cols;
--#if USE_EXTERNAL_URDF && defined(URDF_GE_0P3)
-+ typedef std::vector<UrdfCollisionPtr> UrdfCollisionPtrVector;
-+
-+  // Define cols as the shared pointer which default to a copy of 
-+  // collision_array vector
-+  boost::shared_ptr<UrdfCollisionPtrVector> cols(
-+      new UrdfCollisionPtrVector(_link->collision_array));
-+
-+#ifndef URDF_GE_0P3
-+
-   if (_link->collision)
-   {
--    cols.reset(new std::vector<UrdfCollisionPtr>);
-+    cols.reset(new UrdfCollisionPtrVector());
-     cols->push_back(_link->collision);
-   }
--  else
-+
-+  if (cols->empty())
-   {
--    cols = boost::shared_ptr<std::vector<UrdfCollisionPtr> >(
--            &_link->collision_array);
-+    // new group name, create vector, add vector to map and
-+    // add Collision to the vector
-+    _link->collision_groups.insert(make_pair(_groupName, cols));
-+    sdfdbg << "successfully added a new collision group name ["
-+          << _groupName << "]\n";
-   }
--#else
--  cols = _link->getCollisions(_groupName);
- #endif
- 
--  if (!cols)
--  {
--    // group does not exist, create one and add to map
--    cols.reset(new std::vector<UrdfCollisionPtr>);
--    // new group name, create add vector to map and add Collision to the vector
--    _link->collision_groups.insert(make_pair(_groupName, cols));
--  }
--
--  // group exists, add Collision to the vector in the map
--  std::vector<UrdfCollisionPtr>::iterator colIt =
--    find(cols->begin(), cols->end(), _collision);
-+  // group exists, add Collision to the vector in the map if it's not there
-+  UrdfCollisionPtrVector::iterator colIt
-+    = find(cols->begin(), cols->end(), _collision);
-+
-   if (colIt != cols->end())
-     sdfwarn << "attempted to add collision to link ["
-       << _link->name
-+#ifndef URDF_GE_0P3
-       << "], but it already exists under group ["
-       << _groupName << "]\n";
-+#else
-+      << "], but it already exists in link.\n";
-+#endif
-   else
-     cols->push_back(_collision);
- }
- 
- ////////////////////////////////////////////////////////////////////////////////
- void ReduceVisualToParent(UrdfLinkPtr _link,
--    const std::string &_groupName, UrdfVisualPtr _visual)
-+#ifndef URDF_GE_0P3
-+    const std::string &_groupName,
-+#else
-+    const std::string &/*_groupName*/,
-+#endif
-+    UrdfVisualPtr _visual)
- {
--  boost::shared_ptr<std::vector<UrdfVisualPtr> > viss;
--#if USE_EXTERNAL_URDF && defined(URDF_GE_0P3)
-+
-+  typedef std::vector<UrdfVisualPtr> UrdfVisualPtrVector;
-+
-+  // Define viss as the shared pointer which default to a copy of 
-+  // visual_array vector
-+  boost::shared_ptr<UrdfVisualPtrVector> viss(
-+      new UrdfVisualPtrVector(_link->visual_array));
-+
-+#ifndef URDF_GE_0P3
-+
-   if (_link->visual)
-   {
--    viss.reset(new std::vector<UrdfVisualPtr>);
-+    viss.reset(new UrdfVisualPtrVector());
-     viss->push_back(_link->visual);
-   }
--  else
-+
-+  if (viss->empty())
-   {
--    viss = boost::shared_ptr<std::vector<UrdfVisualPtr> >(&_link->visual_array);
--  }
--#else
--  viss = _link->getVisuals(_groupName);
--#endif
--
--  if (!viss)
--  {
--    // group does not exist, create one and add to map
--    viss.reset(new std::vector<UrdfVisualPtr>);
-     // new group name, create vector, add vector to map and
--    //   add Visual to the vector
-+    // add Visual to the vector
-     _link->visual_groups.insert(make_pair(_groupName, viss));
-     sdfdbg << "successfully added a new visual group name ["
-           << _groupName << "]\n";
-   }
-+#endif
- 
-   // group exists, add Visual to the vector in the map if it's not there
--  std::vector<UrdfVisualPtr>::iterator visIt
-+  UrdfVisualPtrVector::iterator visIt
-     = find(viss->begin(), viss->end(), _visual);
-+
-   if (visIt != viss->end())
-     sdfwarn << "attempted to add visual to link ["
-       << _link->name
-+#ifndef URDF_GE_0P3
-       << "], but it already exists under group ["
-       << _groupName << "]\n";
-+#else
-+      << "], but it already exists in link.\n";
-+#endif
-   else
-     viss->push_back(_visual);
- }
-@@ -844,6 +865,7 @@
-   // "lump::"+group name+"::'+_link name
-   // lump but keep the _link name in(/as) the group name,
-   // so we can correlate visuals to visuals somehow.
-+#ifndef URDF_GE_0P3
-   for (std::map<std::string,
-       boost::shared_ptr<std::vector<UrdfVisualPtr> > >::iterator
-       visualsIt = _link->visual_groups.begin();
-@@ -888,6 +910,21 @@
-       }
-     }
-   }
-+#else
-+  std::string lumpGroupName = std::string("lump::")+_link->name;
-+  for (std::vector<UrdfVisualPtr>::iterator
-+      visualIt = _link->visual_array.begin();
-+      visualIt != _link->visual_array.end(); ++visualIt)
-+  {
-+    // transform visual origin from _link frame to
-+    // parent link frame before adding to parent
-+    (*visualIt)->origin = TransformToParentFrame((*visualIt)->origin,
-+        _link->parent_joint->parent_to_joint_origin_transform);
-+    // add the modified visual to parent
-+    ReduceVisualToParent(_link->getParent(), lumpGroupName,
-+        *visualIt);
-+  }
-+#endif
- }
- 
- /////////////////////////////////////////////////
-@@ -899,6 +936,7 @@
-   // "lump::"+group name+"::'+_link name
-   // lump but keep the _link name in(/as) the group name,
-   // so we can correlate visuals to collisions somehow.
-+#ifndef URDF_GE_0P3
-   for (std::map<std::string,
-       boost::shared_ptr<std::vector<UrdfCollisionPtr> > >::iterator
-       collisionsIt = _link->collision_groups.begin();
-@@ -951,6 +989,23 @@
-     }
-   }
-   // this->PrintCollisionGroups(_link->getParent());
-+#else
-+  std::string lumpGroupName = std::string("lump::")+_link->name;
-+  for (std::vector<UrdfCollisionPtr>::iterator
-+      collisionIt = _link->collision_array.begin();
-+      collisionIt != _link->collision_array.end(); ++collisionIt)
-+  {
-+    // transform collision origin from _link frame to
-+    // parent link frame before adding to parent
-+    (*collisionIt)->origin = TransformToParentFrame(
-+        (*collisionIt)->origin,
-+        _link->parent_joint->parent_to_joint_origin_transform);
-+
-+    // add the modified collision to parent
-+    ReduceCollisionToParent(_link->getParent(), lumpGroupName,
-+        *collisionIt);
-+  }
-+#endif
- }
- 
- /////////////////////////////////////////////////
-@@ -1163,6 +1218,19 @@
-       }
-       else if (childElem->ValueStr() == "visual")
-       {
-+        // anything inside of visual tags:
-+        // <gazebo reference="link_name">
-+        //   <visual>
-+        //     <extention_stuff_here/>
-+        //   </visual>
-+        // </gazebl>
-+        // are treated as blobs that gets inserted
-+        // into visuals for the link
-+        // <visual name="link_name[anything here]">
-+        //   <stuff_from_urdf_link_visuals/>
-+        //   <extention_stuff_here/>
-+        // </visual>
-+
-         // a place to store converted doc
-         for (TiXmlElement* e = childElem->FirstChildElement(); e;
-             e = e->NextSiblingElement())
-@@ -1834,6 +1902,7 @@
- ////////////////////////////////////////////////////////////////////////////////
- void PrintCollisionGroups(UrdfLinkPtr _link)
- {
-+#ifndef URDF_GE_0P3
-   sdfdbg << "COLLISION LUMPING: link: [" << _link->name << "] contains ["
-     << static_cast<int>(_link->collision_groups.size())
-     << "] collisions.\n";
-@@ -1846,6 +1915,11 @@
-       << static_cast<int>(colsIt->second->size())
-       << "] Collision objects\n";
-   }
-+#else
-+  sdfdbg << "COLLISION LUMPING: link: [" << _link->name << "] contains ["
-+    << static_cast<int>(_link->collision_array.size())
-+    << "] collisions.\n";
-+#endif
- }
- 
- ////////////////////////////////////////////////////////////////////////////////
-@@ -2219,6 +2293,7 @@
- {
-   // loop through all collision groups. as well as additional collision from
-   //   lumped meshes (fixed joint reduction)
-+#ifndef URDF_GE_0P3
-   for (std::map<std::string,
-       boost::shared_ptr<std::vector<UrdfCollisionPtr> > >::const_iterator
-       collisionsIt = _link->collision_groups.begin();
-@@ -2295,6 +2370,33 @@
-       }
-     }
-   }
-+#else
-+  unsigned int defaultMeshCount = 0;
-+  for (std::vector<UrdfCollisionPtr>::const_iterator
-+      collision = _link->collision_array.begin();
-+      collision != _link->collision_array.end();
-+      ++collision)
-+  {
-+    sdfdbg << "creating default collision for link [" << _link->name
-+           << "]";
-+
-+    std::string collisionPrefix = _link->name;
-+
-+    if (defaultMeshCount > 0)
-+    {
-+      // append _[meshCount] to link name for additional collisions
-+      std::ostringstream collisionNameStream;
-+      collisionNameStream << collisionPrefix << "_" << defaultMeshCount;
-+      collisionPrefix = collisionNameStream.str();
-+    }
-+
-+    /* make a <collision> block */
-+    CreateCollision(_elem, _link, *collision, collisionPrefix);
-+
-+    // only 1 default mesh
-+    ++defaultMeshCount;
-+  }
-+#endif
- }
- 
- ////////////////////////////////////////////////////////////////////////////////
-@@ -2303,6 +2405,7 @@
- {
-   // loop through all visual groups. as well as additional visuals from
-   //   lumped meshes (fixed joint reduction)
-+#ifndef URDF_GE_0P3
-   for (std::map<std::string,
-       boost::shared_ptr<std::vector<UrdfVisualPtr> > >::const_iterator
-       visualsIt = _link->visual_groups.begin();
-@@ -2379,6 +2482,33 @@
-       }
-     }
-   }
-+#else
-+  unsigned int defaultMeshCount = 0;
-+  for (std::vector<UrdfVisualPtr>::const_iterator
-+      visual = _link->visual_array.begin();
-+      visual != _link->visual_array.end();
-+      ++visual)
-+  {
-+    sdfdbg << "creating default visual for link [" << _link->name
-+           << "]";
-+
-+    std::string visualPrefix = _link->name;
-+
-+    if (defaultMeshCount > 0)
-+    {
-+      // append _[meshCount] to _link name for additional visuals
-+      std::ostringstream visualNameStream;
-+      visualNameStream << visualPrefix << "_" << defaultMeshCount;
-+      visualPrefix = visualNameStream.str();
-+    }
-+
-+    // create a <visual> block
-+    CreateVisual(_elem, _link, *visual, visualPrefix);
-+
-+    // only 1 default mesh
-+    ++defaultMeshCount;
-+  }
-+#endif
- }
- 
- ////////////////////////////////////////////////////////////////////////////////
-diff -r b5ef37039cc7aaf7d3ba69cf30b5be54ec30b8f7 -r 944d3f38d9a4d895996acc45692f05988e58398a src/urdf/urdf_model/link.h
---- a/src/urdf/urdf_model/link.h
-+++ b/src/urdf/urdf_model/link.h
-@@ -62,7 +62,7 @@
- class SDFORMAT_HIDDEN Sphere : public Geometry
- {
- public:
--  Sphere() { this->clear(); };
-+  Sphere() { this->clear(); type = SPHERE; };
-   double radius;
- 
-   void clear()
-@@ -74,7 +74,7 @@
- class SDFORMAT_HIDDEN Box : public Geometry
- {
- public:
--  Box() { this->clear(); };
-+  Box() { this->clear(); type = BOX; };
-   Vector3 dim;
- 
-   void clear()
-@@ -86,7 +86,7 @@
- class SDFORMAT_HIDDEN Cylinder : public Geometry
- {
- public:
--  Cylinder() { this->clear(); };
-+  Cylinder() { this->clear(); type = CYLINDER; };
-   double length;
-   double radius;
- 
-@@ -100,7 +100,7 @@
- class SDFORMAT_HIDDEN Mesh : public Geometry
- {
- public:
--  Mesh() { this->clear(); };
-+  Mesh() { this->clear(); type = MESH; };
-   std::string filename;
-   Vector3 scale;
- 
-@@ -162,9 +162,10 @@
-     material_name.clear();
-     material.reset();
-     geometry.reset();
--    this->group_name.clear();
-+    name.clear();
-   };
--  std::string group_name;
-+
-+  std::string name;
- };
- 
- class SDFORMAT_HIDDEN Collision
-@@ -178,9 +179,11 @@
-   {
-     origin.clear();
-     geometry.reset();
--    this->group_name.clear();
-+    name.clear();
-   };
--  std::string group_name;
-+
-+  std::string name;
-+
- };
- 
- 
-@@ -200,11 +203,11 @@
-   /// collision element
-   boost::shared_ptr<Collision> collision;
- 
--  /// a collection of visual elements, keyed by a string tag called "group"
--  std::map<std::string, boost::shared_ptr<std::vector<boost::shared_ptr<Visual> > > > visual_groups;
-+  /// if more than one collision element is specified, all collision elements are placed in this array (the collision member points to the first element of the array)
-+  std::vector<boost::shared_ptr<Collision> > collision_array;
- 
--  /// a collection of collision elements, keyed by a string tag called "group"
--  std::map<std::string, boost::shared_ptr<std::vector<boost::shared_ptr<Collision> > > > collision_groups;
-+  /// if more than one visual element is specified, all visual elements are placed in this array (the visual member points to the first element of the array)
-+  std::vector<boost::shared_ptr<Visual> > visual_array;
- 
-   /// Parent Joint element
-   ///   explicitly stating "parent" because we want directional-ness for tree structure
-@@ -229,30 +232,10 @@
-     this->parent_joint.reset();
-     this->child_joints.clear();
-     this->child_links.clear();
--    this->collision_groups.clear();
-+    this->collision_array.clear();
-+    this->visual_array.clear();
-   };
- 
--  boost::shared_ptr<std::vector<boost::shared_ptr<Visual > > > getVisuals(const std::string& group_name) const
--  {
--    if (this->visual_groups.find(group_name) != this->visual_groups.end())
--      return this->visual_groups.at(group_name);
--    return boost::shared_ptr<std::vector<boost::shared_ptr<Visual > > >();
--  }
--
--  boost::shared_ptr<std::vector<boost::shared_ptr<Collision > > > getCollisions(const std::string& group_name) const
--  {
--    if (this->collision_groups.find(group_name) != this->collision_groups.end())
--      return this->collision_groups.at(group_name);
--    return boost::shared_ptr<std::vector<boost::shared_ptr<Collision > > >();
--  }
--  
--  /*
--  void setParentJoint(boost::shared_ptr<Joint> child);
--  void addChild(boost::shared_ptr<Link> child);
--  void addChildJoint(boost::shared_ptr<Joint> child);
--
--
--  */
- private:
-   boost::weak_ptr<Link> parent_link_;
- 
-diff -r b5ef37039cc7aaf7d3ba69cf30b5be54ec30b8f7 -r 944d3f38d9a4d895996acc45692f05988e58398a src/urdf/urdf_model/model.h
---- a/src/urdf/urdf_model/model.h
-+++ b/src/urdf/urdf_model/model.h
-@@ -192,12 +192,10 @@
-   /// \brief complete list of Materials
-   std::map<std::string, boost::shared_ptr<Material> > materials_;
- 
-+  /// \brief The name of the robot model
-   std::string name_;
- 
--  /// ModelInterface is restricted to a tree for now, which means there exists one root link
--  ///  typically, root link is the world(inertial).  Where world is a special link
--  /// or is the root_link_ the link attached to the world by PLANAR/FLOATING joint?
--  ///  hmm...
-+  /// \brief The root is always a link (the parent of the tree describing the robot)
-   boost::shared_ptr<Link> root_link_;
- 
- 
-diff -r b5ef37039cc7aaf7d3ba69cf30b5be54ec30b8f7 -r 944d3f38d9a4d895996acc45692f05988e58398a src/urdf/urdf_parser/link.cpp
---- a/src/urdf/urdf_parser/link.cpp
-+++ b/src/urdf/urdf_parser/link.cpp
-@@ -94,8 +94,8 @@
-   if (!has_rgb && !has_filename) {
-     if (!only_name_is_ok) // no need for an error if only name is ok
-     {
--      //if (!has_rgb) logError(std::string("Material ["+material.name+"] color has no rgba").c_str());
--      //if (!has_filename) logError(std::string("Material ["+material.name+"] not defined in file").c_str());
-+      // if (!has_rgb) logError(std::string("Material ["+material.name+"] color has no rgba").c_str());
-+      // if (!has_filename) logError(std::string("Material ["+material.name+"] not defined in file").c_str());
-     }
-     return false;
-   }
-@@ -362,6 +362,10 @@
-   if (!vis.geometry)
-     return false;
- 
-+  const char *name_char = config->Attribute("name");
-+  if (name_char)
-+    vis.name = name_char;
-+
-   // Material
-   TiXmlElement *mat = config->FirstChildElement("material");
-   if (mat) {
-@@ -376,19 +380,10 @@
-     vis.material.reset(new Material());
-     if (!parseMaterial(*vis.material, mat, true))
-     {
--      //vis.material.reset();
--      //return false;
--      //logDebug("material has only name, actual material definition may be in the model");
-+      //logDebug("urdfdom: material has only name, actual material definition may be in the model");
-     }
-   }
-   
--  // Group Tag (optional)
--  // collision blocks without a group tag are designated to the "default" group
--  const char *group_name_char = config->Attribute("group");
--  if (!group_name_char)
--    vis.group_name = std::string("default");
--  else
--    vis.group_name = std::string(group_name_char);
-   return true;
- }
- 
-@@ -409,13 +404,10 @@
-   if (!col.geometry)
-     return false;
- 
--  // Group Tag (optional)
--  // collision blocks without a group tag are designated to the "default" group
--  const char *group_name_char = config->Attribute("group");
--  if (!group_name_char)
--    col.group_name = std::string("default");
--  else
--    col.group_name = std::string(group_name_char);
-+  const char *name_char = config->Attribute("name");
-+  if (name_char)
-+    col.name = name_char;
-+
-   return true;
- }
- 
-@@ -452,19 +444,7 @@
-     vis.reset(new Visual());
-     if (parseVisual(*vis, vis_xml))
-     {
--      boost::shared_ptr<std::vector<boost::shared_ptr<Visual > > > viss = link.getVisuals(vis->group_name);
--      if (!viss)
--      {
--        // group does not exist, create one and add to map
--        viss.reset(new std::vector<boost::shared_ptr<Visual > >);
--        // new group name, create vector, add vector to map and add Visual to the vector
--        link.visual_groups.insert(make_pair(vis->group_name,viss));
--        //logDebug("successfully added a new visual group name '%s'",vis->group_name.c_str());
--      }
--      
--      // group exists, add Visual to the vector in the map
--      viss->push_back(vis);
--      //logDebug("successfully added a new visual under group name '%s'",vis->group_name.c_str());
-+      link.visual_array.push_back(vis);
-     }
-     else
-     {
-@@ -475,27 +455,10 @@
-   }
- 
-   // Visual (optional)
--  // Assign one single default visual pointer from the visual_groups map
--  link.visual.reset();
--  boost::shared_ptr<std::vector<boost::shared_ptr<Visual > > > default_visual = link.getVisuals("default");
--  if (!default_visual)
--  {
--    //("No 'default' visual group for Link '%s'", this->name.c_str());
--  }
--  else if (default_visual->empty())
--  {
--    //("'default' visual group is empty for Link '%s'", this->name.c_str());
--  }
--  else
--  {
--    if (default_visual->size() > 1)
--    {
--      //("'default' visual group has %d visuals for Link '%s', taking the first one as default",(int)default_visual->size(), this->name.c_str());
--    }
--    link.visual = (*default_visual->begin());
--  }
--
--
-+  // Assign the first visual to the .visual ptr, if it exists
-+  if (!link.visual_array.empty())
-+    link.visual = link.visual_array[0];
-+  
-   // Multiple Collisions (optional)
-   for (TiXmlElement* col_xml = config->FirstChildElement("collision"); col_xml; col_xml = col_xml->NextSiblingElement("collision"))
-   {
-@@ -503,20 +466,7 @@
-     col.reset(new Collision());
-     if (parseCollision(*col, col_xml))
-     {      
--      boost::shared_ptr<std::vector<boost::shared_ptr<Collision > > > cols = link.getCollisions(col->group_name);  
--      
--      if (!cols)
--      {
--        // group does not exist, create one and add to map
--        cols.reset(new std::vector<boost::shared_ptr<Collision > >);
--        // new group name, create vector, add vector to map and add Collision to the vector
--        link.collision_groups.insert(make_pair(col->group_name,cols));
--        //logDebug("successfully added a new collision group name '%s'",col->group_name.c_str());
--      }
--
--      // group exists, add Collision to the vector in the map
--      cols->push_back(col);
--      //logDebug("successfully added a new collision under group name '%s'",col->group_name.c_str());
-+      link.collision_array.push_back(col);
-     }
-     else
-     {
-@@ -526,29 +476,12 @@
-     }
-   }
-   
--  // Collision (optional)
--  // Assign one single default collision pointer from the collision_groups map
--  link.collision.reset();
--  boost::shared_ptr<std::vector<boost::shared_ptr<Collision > > > default_collision = link.getCollisions("default");
-+  // Collision (optional)  
-+  // Assign the first collision to the .collision ptr, if it exists
-+  if (!link.collision_array.empty())
-+    link.collision = link.collision_array[0];
- 
--  if (!default_collision)
--  {
--    //logDebug("No 'default' collision group for Link '%s'", link.name.c_str());
--  }
--  else if (default_collision->empty())
--  {
--    //logDebug("'default' collision group is empty for Link '%s'", link.name.c_str());
--  }
--  else
--  {
--    if (default_collision->size() > 1)
--    {
--      //logWarn("'default' collision group has %d collisions for Link '%s', taking the first one as default",(int)default_collision->size(), link.name.c_str());
--    }
--    link.collision = (*default_collision->begin());
--  }
--
--  return false;
-+  return true;
- }
- 
- /* exports */
-@@ -689,9 +622,6 @@
-   if (vis.material)
-     exportMaterial(*vis.material, visual_xml);
- 
--  if (!vis.group_name.empty())
--    visual_xml->SetAttribute("group", vis.group_name);
--
-   xml->LinkEndChild(visual_xml);
- 
-   return true;
-@@ -712,9 +642,6 @@
- 
-   exportGeometry(col.geometry, collision_xml);
- 
--  if (!col.group_name.empty())
--    collision_xml->SetAttribute("group", col.group_name);
--
-   xml->LinkEndChild(collision_xml);
- 
-   return true;
-@@ -725,9 +652,12 @@
-   TiXmlElement * link_xml = new TiXmlElement("link");
-   link_xml->SetAttribute("name", link.name);
- 
--  exportInertial(*link.inertial, link_xml);
--  exportVisual(*link.visual, link_xml);
--  exportCollision(*link.collision, link_xml);
-+  if (link.inertial)
-+    exportInertial(*link.inertial, link_xml);
-+  for (std::size_t i = 0 ; i < link.visual_array.size() ; ++i)
-+    exportVisual(*link.visual_array[i], link_xml);
-+  for (std::size_t i = 0 ; i < link.collision_array.size() ; ++i)
-+    exportCollision(*link.collision_array[i], link_xml);
- 
-   xml->LinkEndChild(link_xml);
- 
-diff -r b5ef37039cc7aaf7d3ba69cf30b5be54ec30b8f7 -r 944d3f38d9a4d895996acc45692f05988e58398a src/urdf/urdf_parser/model.cpp
---- a/src/urdf/urdf_parser/model.cpp
-+++ b/src/urdf/urdf_parser/model.cpp
-@@ -38,6 +38,7 @@
- #include <vector>
- #include "urdf_parser/urdf_parser.h"
- // #include <console_bridge/console.h>
-+#include <fstream>
- 
- namespace urdf{
- 
-@@ -45,6 +46,20 @@
- bool parseLink(Link &link, TiXmlElement *config);
- bool parseJoint(Joint &joint, TiXmlElement *config);
- 
-+boost::shared_ptr<ModelInterface>  parseURDFFile(const std::string &path)
-+{
-+    std::ifstream stream( path.c_str() );
-+    if (!stream)
-+    {
-+      //logDebug(("File " + path + " does not exist").c_str());
-+      return boost::shared_ptr<ModelInterface>();
-+    }
-+
-+    std::string xml_str((std::istreambuf_iterator<char>(stream)),
-+	                     std::istreambuf_iterator<char>());
-+    return urdf::parseURDF( xml_str );
-+}
-+
- boost::shared_ptr<ModelInterface>  parseURDF(const std::string &xml_string)
- {
-   boost::shared_ptr<ModelInterface> model(new ModelInterface);
-@@ -52,11 +67,18 @@
- 
-   TiXmlDocument xml_doc;
-   xml_doc.Parse(xml_string.c_str());
-+  if (xml_doc.Error())
-+  {
-+    //logDebug(xml_doc.ErrorDesc());
-+    xml_doc.ClearError();
-+    model.reset();
-+    return model;
-+  }
- 
-   TiXmlElement *robot_xml = xml_doc.FirstChildElement("robot");
-   if (!robot_xml)
-   {
--    //logError("Could not find the 'robot' element in the xml file");
-+    //logDebug("Could not find the 'robot' element in the xml file");
-     model.reset();
-     return model;
-   }
-@@ -65,7 +87,7 @@
-   const char *name = robot_xml->Attribute("name");
-   if (!name)
-   {
--    //logError("No name given for the robot.");
-+    //logDebug("No name given for the robot.");
-     model.reset();
-     return model;
-   }
-@@ -81,7 +103,7 @@
-       parseMaterial(*material, material_xml, false); // material needs to be fully defined here
-       if (model->getMaterial(material->name))
-       {
--        //logError("material '%s' is not unique.", material->name.c_str());
-+        //logDebug("material '%s' is not unique.", material->name.c_str());
-         material.reset();
-         model.reset();
-         return model;
-@@ -89,11 +111,11 @@
-       else
-       {
-         model->materials_.insert(make_pair(material->name,material));
--        //logDebug("successfully added a new material '%s'", material->name.c_str());
-+        //logDebug("urdfdom: successfully added a new material '%s'", material->name.c_str());
-       }
-     }
-     catch (ParseError &e) {
--      //logError("material xml is not initialized correctly");
-+      //logDebug("material xml is not initialized correctly");
-       material.reset();
-       model.reset();
-       return model;
-@@ -110,33 +132,33 @@
-       parseLink(*link, link_xml);
-       if (model->getLink(link->name))
-       {
--        //logError("link '%s' is not unique.", link->name.c_str());
-+        //logDebug("link '%s' is not unique.", link->name.c_str());
-         model.reset();
-         return model;
-       }
-       else
-       {
-         // set link visual material
--        //logDebug("setting link '%s' material", link->name.c_str());
-+        //logDebug("urdfdom: setting link '%s' material", link->name.c_str());
-         if (link->visual)
-         {
-           if (!link->visual->material_name.empty())
-           {
-             if (model->getMaterial(link->visual->material_name))
-             {
--              //logDebug("setting link '%s' material to '%s'", link->name.c_str(),link->visual->material_name.c_str());
-+              //logDebug("urdfdom: setting link '%s' material to '%s'", link->name.c_str(),link->visual->material_name.c_str());
-               link->visual->material = model->getMaterial( link->visual->material_name.c_str() );
-             }
-             else
-             {
-               if (link->visual->material)
-               {
--                //logDebug("link '%s' material '%s' defined in Visual.", link->name.c_str(),link->visual->material_name.c_str());
-+                //logDebug("urdfdom: link '%s' material '%s' defined in Visual.", link->name.c_str(),link->visual->material_name.c_str());
-                 model->materials_.insert(make_pair(link->visual->material->name,link->visual->material));
-               }
-               else
-               {
--                //logError("link '%s' material '%s' undefined.", link->name.c_str(),link->visual->material_name.c_str());
-+                //logDebug("link '%s' material '%s' undefined.", link->name.c_str(),link->visual->material_name.c_str());
-                 model.reset();
-                 return model;
-               }
-@@ -145,17 +167,17 @@
-         }
- 
-         model->links_.insert(make_pair(link->name,link));
--        //logDebug("successfully added a new link '%s'", link->name.c_str());
-+        //logDebug("urdfdom: successfully added a new link '%s'", link->name.c_str());
-       }
-     }
-     catch (ParseError &e) {
--      //logError("link xml is not initialized correctly");
-+      //logDebug("link xml is not initialized correctly");
-       model.reset();
-       return model;
-     }
-   }
-   if (model->links_.empty()){
--    //logError("No link elements found in urdf file");
-+    //logDebug("No link elements found in urdf file");
-     model.reset();
-     return model;
-   }
-@@ -170,19 +192,19 @@
-     {
-       if (model->getJoint(joint->name))
-       {
--        //logError("joint '%s' is not unique.", joint->name.c_str());
-+        //logDebug("joint '%s' is not unique.", joint->name.c_str());
-         model.reset();
-         return model;
-       }
-       else
-       {
-         model->joints_.insert(make_pair(joint->name,joint));
--        //logDebug("successfully added a new joint '%s'", joint->name.c_str());
-+        //logDebug("urdfdom: successfully added a new joint '%s'", joint->name.c_str());
-       }
-     }
-     else
-     {
--      //logError("joint xml is not initialized correctly");
-+      //logDebug("joint xml is not initialized correctly");
-       model.reset();
-       return model;
-     }
-@@ -201,7 +223,7 @@
-   }
-   catch(ParseError &e)
-   {
--    //logError("Failed to build tree: %s", e.what());
-+    //logDebug("Failed to build tree: %s", e.what());
-     model.reset();
-     return model;
-   }
-@@ -213,7 +235,7 @@
-   }
-   catch(ParseError &e)
-   {
--    //logError("Failed to find root link: %s", e.what());
-+    //logDebug("Failed to find root link: %s", e.what());
-     model.reset();
-     return model;
-   }
-@@ -224,25 +246,40 @@
- bool exportMaterial(Material &material, TiXmlElement *config);
- bool exportLink(Link &link, TiXmlElement *config);
- bool exportJoint(Joint &joint, TiXmlElement *config);
--TiXmlDocument*  exportURDF(boost::shared_ptr<ModelInterface> &model)
-+TiXmlDocument*  exportURDF(const ModelInterface &model)
- {
-   TiXmlDocument *doc = new TiXmlDocument();
- 
-   TiXmlElement *robot = new TiXmlElement("robot");
--  robot->SetAttribute("name", model->name_);
-+  robot->SetAttribute("name", model.name_);
-   doc->LinkEndChild(robot);
- 
--  for (std::map<std::string, boost::shared_ptr<Link> >::const_iterator l=model->links_.begin(); l!=model->links_.end(); l++)  
-+
-+  for (std::map<std::string, boost::shared_ptr<Material> >::const_iterator m=model.materials_.begin(); m!=model.materials_.end(); m++)
-+  {
-+    //logDebug("urdfdom: exporting material [%s]\n",m->second->name.c_str());
-+    exportMaterial(*(m->second), robot);
-+  }
-+
-+  for (std::map<std::string, boost::shared_ptr<Link> >::const_iterator l=model.links_.begin(); l!=model.links_.end(); l++)  
-+  {
-+    //logDebug("urdfdom: exporting link [%s]\n",l->second->name.c_str());
-     exportLink(*(l->second), robot);
--
--  for (std::map<std::string, boost::shared_ptr<Joint> >::const_iterator j=model->joints_.begin(); j!=model->joints_.end(); j++)  
-+  }
-+  	
-+  for (std::map<std::string, boost::shared_ptr<Joint> >::const_iterator j=model.joints_.begin(); j!=model.joints_.end(); j++)  
-   {
--    //logDebug("exporting joint [%s]\n",j->second->name.c_str());
-+    //logDebug("urdfdom: exporting joint [%s]\n",j->second->name.c_str());
-     exportJoint(*(j->second), robot);
-   }
- 
-   return doc;
- }
-+    
-+TiXmlDocument*  exportURDF(boost::shared_ptr<ModelInterface> &model)
-+{
-+  return exportURDF(*model);
-+}
- 
- 
- }
-diff -r b5ef37039cc7aaf7d3ba69cf30b5be54ec30b8f7 -r 944d3f38d9a4d895996acc45692f05988e58398a src/urdf/urdf_world/world.h
---- a/src/urdf/urdf_world/world.h
-+++ b/src/urdf/urdf_world/world.h
-@@ -35,7 +35,7 @@
- /* Author: John Hsu */
- 
- /* encapsulates components in a world
--   see http://ros.org/wiki/urml/XML/urdf_world and
-+   see http://ros.org/wiki/usdf/XML/urdf_world
-    for details
- */
- /* example world XML
-diff -r b5ef37039cc7aaf7d3ba69cf30b5be54ec30b8f7 -r 944d3f38d9a4d895996acc45692f05988e58398a test/integration/fixed_joint_reduction.cc
---- a/test/integration/fixed_joint_reduction.cc
-+++ b/test/integration/fixed_joint_reduction.cc
-@@ -27,6 +27,9 @@
- const std::string SDF_TEST_FILE_SIMPLE =
-   std::string(PROJECT_SOURCE_PATH)
-   + "/test/integration/fixed_joint_reduction_simple.urdf";
-+const std::string SDF_TEST_FILE_COLLISION =
-+  std::string(PROJECT_SOURCE_PATH)
-+  + "/test/integration/fixed_joint_reduction_collision.urdf";
- const std::string SDF_TEST_FILE_VISUAL =
-   std::string(PROJECT_SOURCE_PATH)
-   + "/test/integration/fixed_joint_reduction_visual.urdf";
-@@ -51,6 +54,14 @@
- }
- 
- /////////////////////////////////////////////////
-+// This is a copy of the previous test, with visuals replaced
-+// by collisions.
-+TEST(SDFParser, FixedJointReductionCollisionTest)
-+{
-+  FixedJointReductionEquivalence(SDF_TEST_FILE_COLLISION);
-+}
-+
-+/////////////////////////////////////////////////
- void FixedJointReductionEquivalence(const std::string &_file)
- {
-   char *pathCStr = getenv("SDF_PATH");
-diff -r b5ef37039cc7aaf7d3ba69cf30b5be54ec30b8f7 -r 944d3f38d9a4d895996acc45692f05988e58398a test/integration/fixed_joint_reduction_collision.urdf
---- /dev/null
-+++ b/test/integration/fixed_joint_reduction_collision.urdf
-@@ -0,0 +1,151 @@
-+<?xml version="1.0" ?>
-+<robot name="fixed_joint_reduction_test_odel">
-+
-+  <link name="world"/>
-+
-+  <joint name="jointw0" type="continuous">
-+    <origin rpy="0 0 1.57079632679" xyz="0 0 1.0"/>
-+    <axis xyz="1 0 0"/>  <!-- in child (link1) frame -->
-+    <parent link="world"/>
-+    <child link="link0"/>
-+  </joint>
-+
-+  <link name="link0">
-+    <inertial>
-+      <mass value="1000"/>
-+      <origin rpy="0 0 0" xyz="0 0 -0.5"/>
-+      <inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
-+    </inertial>
-+    <collision>
-+      <geometry>
-+        <box size="0.1 0.1 1.0"/>
-+      </geometry>
-+      <origin rpy="0 0 0" xyz="0 0 -0.5"/>
-+    </collision>
-+  </link>
-+
-+  <joint name="joint01" type="continuous">
-+    <origin rpy="0 0 1.57079632679" xyz="0 0 -1"/>
-+    <axis xyz="1 0 0"/>  <!-- in child (link1) frame -->
-+    <parent link="link0"/>
-+    <child link="link1"/>
-+  </joint>
-+
-+  <link name="link1">
-+    <inertial>
-+      <mass value="100"/>
-+      <origin rpy="1 3 4" xyz="0 -1.5 0"/>
-+      <inertia ixx="2" ixy="0" ixz="0" iyy="3" iyz="0" izz="4"/>
-+    </inertial>
-+    <collision>
-+      <geometry>
-+        <box size="0.2 3.0 0.2"/>
-+      </geometry>
-+      <origin rpy="0 0 0" xyz="0 -1.5 0"/>
-+    </collision>
-+  </link>
-+
-+  <joint name="joint12" type="revolute">
-+    <origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 -3.0 0.0"/>
-+    <axis xyz="0 1 0"/>  <!-- in child (link1) frame -->
-+    <limit lower="0" upper="0" velocity="1000" effort="10000"/>
-+    <parent link="link1"/>
-+    <child link="link2"/>
-+  </joint>
-+
-+  <link name="link2">
-+    <inertial>
-+      <mass value="200"/>
-+      <origin rpy="2 -3 -1.57079632679" xyz="0.2 0.4 1.0"/>
-+      <inertia ixx="5" ixy="0" ixz="0" iyy="6" iyz="0" izz="7"/>
-+    </inertial>
-+    <collision>
-+      <geometry>
-+        <box size="0.3 0.3 2.0"/>
-+      </geometry>
-+      <origin rpy="0 0 0" xyz="0 0 1.0"/>
-+    </collision>
-+  </link>
-+
-+  <joint name="joint23" type="revolute">
-+    <origin rpy="-1.57079632679 0 -1.57079632679" xyz="-0.5 0.5 2.5"/>
-+    <axis xyz="0 1 0"/>  <!-- in child (link1) frame -->
-+    <limit lower="0" upper="0" velocity="1000" effort="10000"/>
-+    <parent link="link2"/>
-+    <child link="link3"/>
-+  </joint>
-+
-+  <link name="link3">
-+    <inertial>
-+      <mass value="400"/>
-+      <origin rpy="2 3 4" xyz="0.1 0.2 0.3"/>
-+      <inertia ixx="8" ixy="0" ixz="0" iyy="9" iyz="0" izz="10"/>
-+    </inertial>
-+    <collision>
-+      <geometry>
-+        <box size="0.3 0.4 0.5"/>
-+      </geometry>
-+      <origin rpy="2 3 4" xyz="0.1 0.2 0.3"/>
-+    </collision>
-+  </link>
-+
-+  <joint name="joint01a" type="continuous">
-+    <origin rpy="0 0 1.57079632679" xyz="0 0 -1"/>
-+    <axis xyz="1 0 0"/>  <!-- in child (link1) frame -->
-+    <parent link="link0"/>
-+    <child link="link1a"/>
-+  </joint>
-+
-+  <link name="link1a">
-+    <inertial>
-+      <mass value="100"/>
-+      <origin rpy="1 3 4" xyz="0 -1.5 0"/>
-+      <inertia ixx="2" ixy="0" ixz="0" iyy="3" iyz="0" izz="4"/>
-+    </inertial>
-+  </link>
-+
-+  <joint name="joint12a" type="fixed">
-+    <origin rpy="-1.57079632679 0 -1.57079632679" xyz="0 -3.0 0.0"/>
-+    <axis xyz="0 1 0"/>  <!-- in child (link1) frame -->
-+    <limit lower="0" upper="0" velocity="1000" effort="10000"/>
-+    <parent link="link1a"/>
-+    <child link="link2a"/>
-+  </joint>
-+
-+  <link name="link2a">
-+    <inertial>
-+      <mass value="200"/>
-+      <origin rpy="2 -3 -1.57079632679" xyz="0.2 0.4 1.0"/>
-+      <inertia ixx="5" ixy="0" ixz="0" iyy="6" iyz="0" izz="7"/>
-+    </inertial>
-+    <collision>
-+      <geometry>
-+        <box size="0.3 0.3 2.0"/>
-+      </geometry>
-+      <origin rpy="0 0 0" xyz="0 0 1.0"/>
-+    </collision>
-+  </link>
-+
-+  <joint name="joint23a" type="fixed">
-+    <origin rpy="-1.57079632679 0 -1.57079632679" xyz="-0.5 0.5 2.5"/>
-+    <axis xyz="0 1 0"/>  <!-- in child (link1) frame -->
-+    <limit lower="0" upper="0" velocity="1000" effort="10000"/>
-+    <parent link="link2a"/>
-+    <child link="link3a"/>
-+  </joint>
-+
-+  <link name="link3a">
-+    <inertial>
-+      <mass value="400"/>
-+      <origin rpy="2 3 4" xyz="0.1 0.2 0.3"/>
-+      <inertia ixx="8" ixy="0" ixz="0" iyy="9" iyz="0" izz="10"/>
-+    </inertial>
-+    <collision>
-+      <geometry>
-+        <box size="0.3 0.4 0.5"/>
-+      </geometry>
-+      <origin rpy="2 3 4" xyz="0.1 0.2 0.3"/>
-+    </collision>
-+  </link>
-+
-+</robot>
diff --git a/debian/patches/series b/debian/patches/series
deleted file mode 100644
index da4bff3..0000000
--- a/debian/patches/series
+++ /dev/null
@@ -1 +0,0 @@
-0001-fix-external-urdfdom.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