From c4a3902f1af6e101ebd999869aa53409039b378f Mon Sep 17 00:00:00 2001
From: Mark Moll <mmoll@rice.edu>
Date: Mon, 17 Feb 2014 14:46:06 -0600
Subject: [PATCH] Don't use deprecated API. Fix compiler warnings. Cmake
 cleanup. (Missing changes from 44ea1ea)

---
 CMakeLists.txt                                | 19 +++++++++----------
 include/fcl/math/vec_nf.h                     |  2 +-
 .../broadphase_dynamic_AABB_tree.cpp          |  4 ++--
 .../broadphase_dynamic_AABB_tree_array.cpp    |  4 ++--
 src/collision.cpp                             |  2 +-
 src/continuous_collision.cpp                  |  8 ++++----
 src/distance.cpp                              |  2 +-
 7 files changed, 20 insertions(+), 21 deletions(-)

diff --git a/CMakeLists.txt b/CMakeLists.txt
index cb2d0eee..33a7d34e 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -65,22 +65,21 @@ find_package(flann QUIET)
 if (FLANN_FOUND)
   set(FCL_HAVE_FLANN 1)
   include_directories(${FLANN_INCLUDE_DIRS})
-  link_directories(${FLANN_LIBRARY_DIRS})
   message(STATUS "FCL uses Flann")
 else()
   message(STATUS "FCL does not use Flann")
 endif()
 
 
-find_package(tinyxml QUIET)
-if (TINYXML_FOUND)
-  set(FCL_HAVE_TINYXML 1)
-  include_directories(${TINYXML_INCLUDE_DIRS})
-  link_directories(${TINYXML_LIBRARY_DIRS})
-  message(STATUS "FCL uses tinyxml")
-else()
-  message(STATUS "FCL does not use tinyxml")
-endif()
+# find_package(tinyxml QUIET)
+# if (TINYXML_FOUND)
+#   set(FCL_HAVE_TINYXML 1)
+#   include_directories(${TINYXML_INCLUDE_DIRS})
+#   link_directories(${TINYXML_LIBRARY_DIRS})
+#   message(STATUS "FCL uses tinyxml")
+# else()
+#   message(STATUS "FCL does not use tinyxml")
+# endif()
 
 
 find_package(Boost COMPONENTS thread date_time filesystem system unit_test_framework REQUIRED)
diff --git a/include/fcl/math/vec_nf.h b/include/fcl/math/vec_nf.h
index 5a181a1d..db3d416f 100644
--- a/include/fcl/math/vec_nf.h
+++ b/include/fcl/math/vec_nf.h
@@ -167,7 +167,7 @@ template<typename T1, std::size_t N1,
 void repack(const Vec_n<T1, N1>& input,
             Vec_n<T2, N2>& output)
 {
-  int n = std::min(N1, N2);
+  std::size_t n = std::min(N1, N2);
   for(std::size_t i = 0; i < n; ++i)
     output[i] = input[i];
 }
diff --git a/src/broadphase/broadphase_dynamic_AABB_tree.cpp b/src/broadphase/broadphase_dynamic_AABB_tree.cpp
index e685bdc3..69dc7d79 100644
--- a/src/broadphase/broadphase_dynamic_AABB_tree.cpp
+++ b/src/broadphase/broadphase_dynamic_AABB_tree.cpp
@@ -739,7 +739,7 @@ void DynamicAABBTreeCollisionManager::update(const std::vector<CollisionObject*>
 void DynamicAABBTreeCollisionManager::collide(CollisionObject* obj, void* cdata, CollisionCallBack callback) const
 {
   if(size() == 0) return;
-  switch(obj->getCollisionGeometry()->getNodeType())
+  switch(obj->collisionGeometry()->getNodeType())
   {
 #if FCL_HAVE_OCTOMAP
   case GEOM_OCTREE:
@@ -763,7 +763,7 @@ void DynamicAABBTreeCollisionManager::distance(CollisionObject* obj, void* cdata
 {
   if(size() == 0) return;
   FCL_REAL min_dist = std::numeric_limits<FCL_REAL>::max();
-  switch(obj->getCollisionGeometry()->getNodeType())
+  switch(obj->collisionGeometry()->getNodeType())
   {
 #if FCL_HAVE_OCTOMAP
   case GEOM_OCTREE:
diff --git a/src/broadphase/broadphase_dynamic_AABB_tree_array.cpp b/src/broadphase/broadphase_dynamic_AABB_tree_array.cpp
index 9223c362..c8364517 100644
--- a/src/broadphase/broadphase_dynamic_AABB_tree_array.cpp
+++ b/src/broadphase/broadphase_dynamic_AABB_tree_array.cpp
@@ -764,7 +764,7 @@ void DynamicAABBTreeCollisionManager_Array::update(const std::vector<CollisionOb
 void DynamicAABBTreeCollisionManager_Array::collide(CollisionObject* obj, void* cdata, CollisionCallBack callback) const
 {
   if(size() == 0) return;
-  switch(obj->getCollisionGeometry()->getNodeType())
+  switch(obj->collisionGeometry()->getNodeType())
   {
 #if FCL_HAVE_OCTOMAP
   case GEOM_OCTREE:
@@ -788,7 +788,7 @@ void DynamicAABBTreeCollisionManager_Array::distance(CollisionObject* obj, void*
 {
   if(size() == 0) return;
   FCL_REAL min_dist = std::numeric_limits<FCL_REAL>::max();
-  switch(obj->getCollisionGeometry()->getNodeType())
+  switch(obj->collisionGeometry()->getNodeType())
   {
 #if FCL_HAVE_OCTOMAP
   case GEOM_OCTREE:
diff --git a/src/collision.cpp b/src/collision.cpp
index b481e2d4..d6119d2e 100644
--- a/src/collision.cpp
+++ b/src/collision.cpp
@@ -57,7 +57,7 @@ std::size_t collide(const CollisionObject* o1, const CollisionObject* o2,
                     const CollisionRequest& request,
                     CollisionResult& result)
 {
-  return collide(o1->getCollisionGeometry(), o1->getTransform(), o2->getCollisionGeometry(), o2->getTransform(),
+  return collide(o1->collisionGeometry().get(), o1->getTransform(), o2->collisionGeometry().get(), o2->getTransform(),
                  nsolver, request, result);
 }
 
diff --git a/src/continuous_collision.cpp b/src/continuous_collision.cpp
index 60cb85a2..80818714 100644
--- a/src/continuous_collision.cpp
+++ b/src/continuous_collision.cpp
@@ -316,8 +316,8 @@ FCL_REAL continuousCollide(const CollisionObject* o1, const Transform3f& tf1_end
                            const ContinuousCollisionRequest& request,
                            ContinuousCollisionResult& result)
 {
-  return continuousCollide(o1->getCollisionGeometry(), o1->getTransform(), tf1_end,
-                           o2->getCollisionGeometry(), o2->getTransform(), tf2_end,
+  return continuousCollide(o1->collisionGeometry().get(), o1->getTransform(), tf1_end,
+                           o2->collisionGeometry().get(), o2->getTransform(), tf2_end,
                            request, result);
 }
 
@@ -326,8 +326,8 @@ FCL_REAL collide(const ContinuousCollisionObject* o1, const ContinuousCollisionO
                  const ContinuousCollisionRequest& request,
                  ContinuousCollisionResult& result)
 {
-  return continuousCollide(o1->getCollisionGeometry(), o1->getMotion(),
-                           o2->getCollisionGeometry(), o2->getMotion(),
+  return continuousCollide(o1->collisionGeometry().get(), o1->getMotion(),
+                           o2->collisionGeometry().get(), o2->getMotion(),
                            request, result);
 }
 
diff --git a/src/distance.cpp b/src/distance.cpp
index d20da2f5..a9936b85 100644
--- a/src/distance.cpp
+++ b/src/distance.cpp
@@ -54,7 +54,7 @@ template<typename NarrowPhaseSolver>
 FCL_REAL distance(const CollisionObject* o1, const CollisionObject* o2, const NarrowPhaseSolver* nsolver,
                   const DistanceRequest& request, DistanceResult& result)
 {
-  return distance<NarrowPhaseSolver>(o1->getCollisionGeometry(), o1->getTransform(), o2->getCollisionGeometry(), o2->getTransform(), nsolver,
+  return distance<NarrowPhaseSolver>(o1->collisionGeometry().get(), o1->getTransform(), o2->collisionGeometry().get(), o2->getTransform(), nsolver,
                                      request, result);
 }
 
-- 
GitLab