diff --git a/CMakeLists.txt b/CMakeLists.txt index cb2d0eee3382b2b9882548df18b5caf5f47edd7b..33a7d34e6125d0b8c278889c02e2d2069c9216de 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 5a181a1d37e50cd7e31fd3f17a07adeada193de6..db3d416fa7839d8374e3a511b30c017b4778f540 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 e685bdc374e63a1a296f2c4259bcf41300f8e362..69dc7d798e459f3814b49d3395c24997d650163a 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 9223c362899d9dcda8e0f66c141ef352d7ce7b04..c8364517058f98e750fda35fabb9c8f696067c04 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 b481e2d45eae823a19f7a946e359fe888b6af4a4..d6119d2e55c19e1bb7951a316f55b906812cb137 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 60cb85a230946f48e9efeb2989c0f5f85e6a5bf0..80818714109f5eacc178669406e0ef6307032d5e 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 d20da2f59182e612224807a120209de3bfd039e0..a9936b858c00307bf3a72bfdc6ff8e1613d1bc2f 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); }