[sdformat] Update to release 2.0.1

rmattes rmattes at fedoraproject.org
Sat Aug 23 18:44:20 UTC 2014


commit 5958d7a5c4c7a9acd9a4aac0ccd62f07b2ea5b1d
Author: Rich Mattes <richmattes at gmail.com>
Date:   Sat Aug 23 14:43:48 2014 -0400

    Update to release 2.0.1
    
    - Apply upstream patch for urdfdom 0.3 support

 .gitignore                   |    1 +
 sdformat-2.0.1-urdf3.patch   |  443 ++++++++++++++++++++++++++++++++++++++++++
 sdformat-2.0.1-urdfdom.patch |   44 ++++
 sdformat.spec                |   23 ++-
 sources                      |    2 +-
 5 files changed, 506 insertions(+), 7 deletions(-)
---
diff --git a/.gitignore b/.gitignore
index 8131b80..e2e5e72 100644
--- a/.gitignore
+++ b/.gitignore
@@ -1,3 +1,4 @@
 /sdformat_1.4.10.tar.bz2
 /sdformat_1.4.11.tar.bz2
 /sdformat_2.0.0.tar.bz2
+/sdformat2_2.0.1.tar.bz2
diff --git a/sdformat-2.0.1-urdf3.patch b/sdformat-2.0.1-urdf3.patch
new file mode 100644
index 0000000..c3b993c
--- /dev/null
+++ b/sdformat-2.0.1-urdf3.patch
@@ -0,0 +1,443 @@
+diff -r d79259b26096 src/parser_urdf.cc
+--- a/src/parser_urdf.cc	Mon Aug 04 13:07:16 2014 -0700
++++ b/src/parser_urdf.cc	Sat Aug 23 14:30:18 2014 -0400
+@@ -297,85 +297,15 @@
+ }
+ 
+ ////////////////////////////////////////////////////////////////////////////////
+-void ReduceCollisionToParent(UrdfLinkPtr _link,
+-    const std::string &_groupName, UrdfCollisionPtr _collision)
++void ReduceCollisionToParent(UrdfLinkPtr _link, UrdfCollisionPtr _collision)
+ {
+-  boost::shared_ptr<std::vector<UrdfCollisionPtr> > cols;
+-#if USE_EXTERNAL_URDF && defined(URDF_GE_0P3)
+-  if (_link->collision)
+-  {
+-    cols.reset(new std::vector<UrdfCollisionPtr>);
+-    cols->push_back(_link->collision);
+-  }
+-  else
+-  {
+-    cols = boost::shared_ptr<std::vector<UrdfCollisionPtr> >(
+-            &_link->collision_array);
+-  }
+-#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);
+-  if (colIt != cols->end())
+-    sdfwarn << "attempted to add collision to link ["
+-      << _link->name
+-      << "], but it already exists under group ["
+-      << _groupName << "]\n";
+-  else
+-    cols->push_back(_collision);
++  _link->collision_array.push_back(_collision);
+ }
+ 
+ ////////////////////////////////////////////////////////////////////////////////
+-void ReduceVisualToParent(UrdfLinkPtr _link,
+-    const std::string &_groupName, UrdfVisualPtr _visual)
++void ReduceVisualToParent(UrdfLinkPtr _link, UrdfVisualPtr _visual)
+ {
+-  boost::shared_ptr<std::vector<UrdfVisualPtr> > viss;
+-#if USE_EXTERNAL_URDF && defined(URDF_GE_0P3)
+-  if (_link->visual)
+-  {
+-    viss.reset(new std::vector<UrdfVisualPtr>);
+-    viss->push_back(_link->visual);
+-  }
+-  else
+-  {
+-    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
+-    _link->visual_groups.insert(make_pair(_groupName, viss));
+-    sdfdbg << "successfully added a new visual group name ["
+-          << _groupName << "]\n";
+-  }
+-
+-  // group exists, add Visual to the vector in the map if it's not there
+-  std::vector<UrdfVisualPtr>::iterator visIt
+-    = find(viss->begin(), viss->end(), _visual);
+-  if (visIt != viss->end())
+-    sdfwarn << "attempted to add visual to link ["
+-      << _link->name
+-      << "], but it already exists under group ["
+-      << _groupName << "]\n";
+-  else
+-    viss->push_back(_visual);
++  _link->visual_array.push_back(_visual);
+ }
+ 
+ ////////////////////////////////////////////////////////////////////////////////
+@@ -839,54 +769,17 @@
+ /// reduce fixed joints:  lump visuals to parent link
+ void ReduceVisualsToParent(UrdfLinkPtr _link)
+ {
+-  // lump visual to parent
+-  // lump all visual to parent, assign group name
+-  // "lump::"+group name+"::'+_link name
+-  // lump but keep the _link name in(/as) the group name,
+-  // so we can correlate visuals to visuals somehow.
+-  for (std::map<std::string,
+-      boost::shared_ptr<std::vector<UrdfVisualPtr> > >::iterator
+-      visualsIt = _link->visual_groups.begin();
+-      visualsIt != _link->visual_groups.end(); ++visualsIt)
++  for (std::vector<UrdfVisualPtr>::iterator
++      visualIt = _link->visual_array.begin();
++      visualIt != _link->visual_array.end(); ++visualIt)
+   {
+-    if (visualsIt->first.find(std::string("lump::")) == 0)
+-    {
+-      // it's a previously lumped mesh, re-lump under same _groupName
+-      std::string lumpGroupName = visualsIt->first;
+-      sdfdbg << "re-lumping group name [" << lumpGroupName
+-             << "] to link [" << _link->getParent()->name << "]\n";
+-      for (std::vector<UrdfVisualPtr>::iterator
+-          visualIt = visualsIt->second->begin();
+-          visualIt != visualsIt->second->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);
+-      }
+-    }
+-    else
+-    {
+-      // default and any other groups meshes
+-      std::string lumpGroupName = std::string("lump::")+_link->name;
+-      sdfdbg << "adding modified lump group name [" << lumpGroupName
+-             << "] to link [" << _link->getParent()->name << "].\n";
+-      for (std::vector<UrdfVisualPtr>::iterator
+-          visualIt = visualsIt->second->begin();
+-          visualIt != visualsIt->second->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);
+-      }
+-    }
++    // 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(), *visualIt);
++    _link->getParent()->visual_array.push_back(*visualIt);
+   }
+ }
+ 
+@@ -894,63 +787,19 @@
+ /// reduce fixed joints:  lump collisions to parent link
+ void ReduceCollisionsToParent(UrdfLinkPtr _link)
+ {
+-  // lump collision parent
+-  // lump all collision to parent, assign group name
+-  // "lump::"+group name+"::'+_link name
+-  // lump but keep the _link name in(/as) the group name,
+-  // so we can correlate visuals to collisions somehow.
+-  for (std::map<std::string,
+-      boost::shared_ptr<std::vector<UrdfCollisionPtr> > >::iterator
+-      collisionsIt = _link->collision_groups.begin();
+-      collisionsIt != _link->collision_groups.end(); ++collisionsIt)
++  for (std::vector<UrdfCollisionPtr>::iterator
++      collisionIt = _link->collision_array.begin();
++      collisionIt != _link->collision_array.end(); ++collisionIt)
+   {
+-    if (collisionsIt->first.find(std::string("lump::")) == 0)
+-    {
+-      // if it's a previously lumped mesh, relump under same _groupName
+-      std::string lumpGroupName = collisionsIt->first;
+-      sdfdbg << "re-lumping collision [" << collisionsIt->first
+-             << "] for link [" << _link->name
+-             << "] to parent [" << _link->getParent()->name
+-             << "] with group name [" << lumpGroupName << "]\n";
+-      for (std::vector<UrdfCollisionPtr>::iterator
+-          collisionIt = collisionsIt->second->begin();
+-          collisionIt != collisionsIt->second->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);
+-      }
+-    }
+-    else
+-    {
+-      // default and any other group meshes
+-      std::string lumpGroupName = std::string("lump::")+_link->name;
+-      sdfdbg << "lumping collision [" << collisionsIt->first
+-             << "] for link [" << _link->name
+-             << "] to parent [" << _link->getParent()->name
+-             << "] with group name [" << lumpGroupName << "]\n";
+-      for (std::vector<UrdfCollisionPtr>::iterator
+-          collisionIt = collisionsIt->second->begin();
+-          collisionIt != collisionsIt->second->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);
+-      }
+-    }
++    // 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(), *collisionIt);
++    _link->getParent()->collision_array.push_back(*collisionIt);
+   }
+-  // this->PrintCollisionGroups(_link->getParent());
+ }
+ 
+ /////////////////////////////////////////////////
+@@ -1827,17 +1676,8 @@
+ void PrintCollisionGroups(UrdfLinkPtr _link)
+ {
+   sdfdbg << "COLLISION LUMPING: link: [" << _link->name << "] contains ["
+-    << static_cast<int>(_link->collision_groups.size())
++    << static_cast<int>(_link->collision_array.size())
+     << "] collisions.\n";
+-  for (std::map<std::string,
+-      boost::shared_ptr<std::vector<UrdfCollisionPtr > > >::iterator
+-      colsIt = _link->collision_groups.begin();
+-      colsIt != _link->collision_groups.end(); ++colsIt)
+-  {
+-    sdfdbg << "    collision_groups: [" << colsIt->first << "] has ["
+-      << static_cast<int>(colsIt->second->size())
+-      << "] Collision objects\n";
+-  }
+ }
+ 
+ ////////////////////////////////////////////////////////////////////////////////
+@@ -2206,86 +2046,21 @@
+ }
+ 
+ ////////////////////////////////////////////////////////////////////////////////
+-void CreateCollisions(TiXmlElement* _elem,
+-    ConstUrdfLinkPtr _link)
++void CreateCollisions(TiXmlElement* _elem, ConstUrdfLinkPtr _link)
+ {
+-  // loop through all collision groups. as well as additional collision from
+-  //   lumped meshes (fixed joint reduction)
+-  for (std::map<std::string,
+-      boost::shared_ptr<std::vector<UrdfCollisionPtr> > >::const_iterator
+-      collisionsIt = _link->collision_groups.begin();
+-      collisionsIt != _link->collision_groups.end(); ++collisionsIt)
++  // loop through collisions
++  for (std::vector<UrdfCollisionPtr>::const_iterator
++      collision =  _link->collision_array.begin();
++      collision != _link->collision_array.end();
++      ++collision)
+   {
+-    unsigned int defaultMeshCount = 0;
+-    unsigned int groupMeshCount = 0;
+-    unsigned int lumpMeshCount = 0;
+-    // loop through collisions in each group
+-    for (std::vector<UrdfCollisionPtr>::iterator
+-        collision = collisionsIt->second->begin();
+-        collision != collisionsIt->second->end();
+-        ++collision)
+-    {
+-      if (collisionsIt->first == "default")
+-      {
+-        sdfdbg << "creating default collision for link [" << _link->name
+-               << "]";
++    sdfdbg << "creating default collision for link [" << _link->name
++           << "]";
+ 
+-        std::string collisionPrefix = _link->name;
++    std::string collisionPrefix = _link->name + (*collision)->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;
+-      }
+-      else if (collisionsIt->first.find(std::string("lump::")) == 0)
+-      {
+-        // if collision name starts with "lump::", pass through
+-        //   original parent link name
+-        sdfdbg << "creating lump collision [" << collisionsIt->first
+-               << "] for link [" << _link->name << "].\n";
+-        /// collisionPrefix is the original name before lumping
+-        std::string collisionPrefix = collisionsIt->first.substr(6);
+-
+-        if (lumpMeshCount > 0)
+-        {
+-          // append _[meshCount] to link name for additional collisions
+-          std::ostringstream collisionNameStream;
+-          collisionNameStream << collisionPrefix << "_" << lumpMeshCount;
+-          collisionPrefix = collisionNameStream.str();
+-        }
+-
+-        CreateCollision(_elem, _link, *collision, collisionPrefix);
+-        ++lumpMeshCount;
+-      }
+-      else
+-      {
+-        sdfdbg << "adding collisions from collision group ["
+-              << collisionsIt->first << "]\n";
+-
+-        std::string collisionPrefix = _link->name + std::string("_") +
+-          collisionsIt->first;
+-
+-        if (groupMeshCount > 0)
+-        {
+-          // append _[meshCount] to _link name for additional collisions
+-          std::ostringstream collisionNameStream;
+-          collisionNameStream << collisionPrefix << "_" << groupMeshCount;
+-          collisionPrefix = collisionNameStream.str();
+-        }
+-
+-        CreateCollision(_elem, _link, *collision, collisionPrefix);
+-        ++groupMeshCount;
+-      }
+-    }
++    /* make a <collision> block */
++    CreateCollision(_elem, _link, *collision, collisionPrefix);
+   }
+ }
+ 
+@@ -2293,83 +2068,18 @@
+ void CreateVisuals(TiXmlElement* _elem,
+     ConstUrdfLinkPtr _link)
+ {
+-  // loop through all visual groups. as well as additional visuals from
+-  //   lumped meshes (fixed joint reduction)
+-  for (std::map<std::string,
+-      boost::shared_ptr<std::vector<UrdfVisualPtr> > >::const_iterator
+-      visualsIt = _link->visual_groups.begin();
+-      visualsIt != _link->visual_groups.end(); ++visualsIt)
++  // loop through visuals
++  for (std::vector<UrdfVisualPtr>::const_iterator
++      visual = _link->visual_array.begin();
++      visual != _link->visual_array.end(); ++visual)
+   {
+-    unsigned int defaultMeshCount = 0;
+-    unsigned int groupMeshCount = 0;
+-    unsigned int lumpMeshCount = 0;
+-    // loop through all visuals in this group
+-    for (std::vector<UrdfVisualPtr>::iterator
+-        visual = visualsIt->second->begin();
+-        visual != visualsIt->second->end();
+-        ++visual)
+-    {
+-      if (visualsIt->first == "default")
+-      {
+-        sdfdbg << "creating default visual for link [" << _link->name
+-               << "]";
++    sdfdbg << "creating default visual for link [" << _link->name
++           << "]";
+ 
+-        std::string visualPrefix = _link->name;
++    std::string visualPrefix = _link->name + (*visual)->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;
+-      }
+-      else if (visualsIt->first.find(std::string("lump::")) == 0)
+-      {
+-        // if visual name starts with "lump::", pass through
+-        //   original parent link name
+-        sdfdbg << "creating lump visual [" << visualsIt->first
+-               << "] for link [" << _link->name << "].\n";
+-        /// visualPrefix is the original name before lumping
+-        std::string visualPrefix = visualsIt->first.substr(6);
+-
+-        if (lumpMeshCount > 0)
+-        {
+-          // append _[meshCount] to _link name for additional visuals
+-          std::ostringstream visualNameStream;
+-          visualNameStream << visualPrefix << "_" << lumpMeshCount;
+-          visualPrefix = visualNameStream.str();
+-        }
+-
+-        CreateVisual(_elem, _link, *visual, visualPrefix);
+-        ++lumpMeshCount;
+-      }
+-      else
+-      {
+-        sdfdbg << "adding visuals from visual group ["
+-              << visualsIt->first << "]\n";
+-
+-        std::string visualPrefix = _link->name + std::string("_") +
+-          visualsIt->first;
+-
+-        if (groupMeshCount > 0)
+-        {
+-          // append _[meshCount] to _link name for additional visuals
+-          std::ostringstream visualNameStream;
+-          visualNameStream << visualPrefix << "_" << groupMeshCount;
+-          visualPrefix = visualNameStream.str();
+-        }
+-
+-        CreateVisual(_elem, _link, *visual, visualPrefix);
+-        ++groupMeshCount;
+-      }
+-    }
++    // create a <visual> block
++    CreateVisual(_elem, _link, *visual, visualPrefix);
+   }
+ }
+ 
diff --git a/sdformat-2.0.1-urdfdom.patch b/sdformat-2.0.1-urdfdom.patch
new file mode 100644
index 0000000..9af36d9
--- /dev/null
+++ b/sdformat-2.0.1-urdfdom.patch
@@ -0,0 +1,44 @@
+diff -up ./cmake/sdf_config.h.in.urdfdom ./cmake/sdf_config.h.in
+--- ./cmake/sdf_config.h.in.urdfdom	2014-08-22 21:07:12.473338538 -0400
++++ ./cmake/sdf_config.h.in	2014-08-22 21:07:34.382208622 -0400
+@@ -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 -up ./cmake/SearchForStuff.cmake.urdfdom ./cmake/SearchForStuff.cmake
+--- ./cmake/SearchForStuff.cmake.urdfdom	2014-07-11 13:50:35.000000000 -0400
++++ ./cmake/SearchForStuff.cmake	2014-08-22 20:59:39.239507142 -0400
+@@ -62,12 +62,25 @@ if (USE_EXTERNAL_URDF)
+       set (URDF_GE_0P3 TRUE)
+     endif()
+ 
+-    # what am I doing here? pkg-config and cmake
+-    set(URDF_INCLUDE_DIRS ${URDF_INCLUDEDIR})
+-    set(URDF_LIBRARY_DIRS ${URDF_LIBDIR})
+   endif()
+ endif()
+ 
++################################################
++# Find gtest
++find_package(GTest)
++if (USE_EXTERNAL_GTEST AND GTEST_FOUND)
++  set(GTEST_LIBRARY ${GTEST_LIBRARIES})
++  set(GTEST_MAIN_LIBRARY ${GTEST_MAIN_LIBRARIES})
++  set(GTEST_INCLUDE_DIR ${GTEST_INCLUDE_DIRS})
++else()
++  add_library(gtest STATIC "${PROJECT_SOURCE_DIR}/test/gtest/src/gtest-all.cc")
++  add_library(gtest_main STATIC "${PROJECT_SOURCE_DIR}/test/gtest/src/gtest_main.cc")
++  target_link_libraries(gtest_main gtest)
++  set(GTEST_LIBRARY "${PROJECT_BINARY_DIR}/test/libgtest.a")
++  set(GTEST_MAIN_LIBRARY "${PROJECT_BINARY_DIR}/test/libgtest_main.a")
++  set(GTEST_INCLUDE_DIR "${PROJECT_SOURCE_DIR}/test/gtest/include")
++endif()
++
+ #################################################
+ # Macro to check for visibility capability in compiler
+ # Original idea from: https://gitorious.org/ferric-cmake-stuff/ 
diff --git a/sdformat.spec b/sdformat.spec
index ab1cc65..6da3e2f 100644
--- a/sdformat.spec
+++ b/sdformat.spec
@@ -11,11 +11,12 @@ URL:		http://gazebosim.org/sdf.html
 Source0:	https://bitbucket.org/osrf/%{name}/get/%{name}2_%{version}.tar.bz2
 # Unbundle urdfdom and urdfdom-headers from sdformat, build against system versions.
 # Work progressing upstream
-Patch0:		sdformat-2.0.0-urdfdom.patch
+Patch0:		sdformat-2.0.1-urdfdom.patch
 # Automatically discovers and uses system gtest if available.
 # Not yet submitted upstream
 Patch1:		sdformat-1.4.10-gtest.patch
-Patch2:         sdformat-2.0.0-urdf3.patch
+# Changes from the upstream "update_urdf_3.0" branch to parser_urdf.cc
+Patch2:		sdformat-2.0.1-urdf3.patch
 BuildRequires:	boost-devel
 BuildRequires:	cmake
 BuildRequires:	doxygen-latex
@@ -25,6 +26,9 @@ BuildRequires:	texlive-refman
 BuildRequires:	tinyxml-devel
 BuildRequires:	urdfdom-devel
 
+#Test dependencies
+BuildRequires:  python
+
 %description
 The Simulation Description Format (SDF) is an XML file format used to 
 describe all the elements in a software simulation environment. Originally
@@ -52,15 +56,18 @@ The %{name}-doc package contains development documentation for
 %setup -q -n osrf-%{name}-%{hghash}
 %patch0 -p0 -b .urdfdom
 %patch1 -p0 -b .gtest
-#%patch2 -p0 -b .urdf3
+%patch2 -p1 -b .urdf3
 # Remove bundled urdf components
 rm -rf src/urdf
 rm -rf test/gtest
 
 %build
-mkdir build; pushd build
-%cmake .. -DCMAKE_BUILD_TYPE=None -DCMAKE_CXX_FLAGS_NONE="%{optflags}" -DLIB_INSTALL_DIR:STRING=%{_lib} -DUSE_EXTERNAL_URDF=ON
+mkdir build
+pushd build
+%cmake -DCMAKE_BUILD_TYPE=None -DCMAKE_CXX_FLAGS_NONE="%{optflags}" -DLIB_INSTALL_DIR:STRING=%{_lib} -DUSE_EXTERNAL_URDF=ON -DUSE_EXTERNAL_GTEST=ON  ..
+
 popd
+cat  build/sdf/sdf_config.h
 make -C build %{?_smp_mflags}
 make -C build doc
 
@@ -68,7 +75,7 @@ make -C build doc
 make -C build install DESTDIR=%{buildroot}
 
 %check
-make -C build test || exit 0
+make -C build test || cat build/Testing/Temporary/LastTest.log
 
 %post -p /sbin/ldconfig
 
@@ -90,6 +97,10 @@ make -C build test || exit 0
 %doc build/doxygen/html
 
 %changelog
+* Sat Aug 23 2014 Rich Mattes <richmattes at gmail.com> - 2.0.1-1
+- Update to release 2.0.1
+- Apply upstream patch for urdfdom 0.3 support
+
 * Mon Aug 18 2014 Fedora Release Engineering <rel-eng at lists.fedoraproject.org> - 2.0.0-5
 - Rebuilt for https://fedoraproject.org/wiki/Fedora_21_22_Mass_Rebuild
 
diff --git a/sources b/sources
index fcc3342..606f037 100644
--- a/sources
+++ b/sources
@@ -1 +1 @@
-d3b98b2296f3f234019c551af6a27bf9  sdformat_2.0.0.tar.bz2
+82f7f6479ae3cb4e095cf7c3210678e0  sdformat2_2.0.1.tar.bz2


More information about the scm-commits mailing list