Skip to content

Commit

Permalink
[build] Require FCL >= 0.7.0
Browse files Browse the repository at this point in the history
  • Loading branch information
jslee02 committed Mar 22, 2024
1 parent 786c242 commit c508317
Show file tree
Hide file tree
Showing 7 changed files with 21 additions and 172 deletions.
4 changes: 2 additions & 2 deletions cmake/DARTFindfcl.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,9 @@
#
# This file is provided under the "BSD-style" License

find_package(fcl 0.5.0 CONFIG)
find_package(fcl 0.7.0 CONFIG)
if(NOT FCL_FOUND AND NOT fcl_FOUND)
find_package(fcl 0.5.0 REQUIRED MODULE)
find_package(fcl 0.7.0 REQUIRED MODULE)
endif()

# Set target fcl if not set
Expand Down
32 changes: 0 additions & 32 deletions dart/collision/fcl/BackwardCompatibility.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,65 +39,41 @@ namespace fcl {
//==============================================================================
double length(const dart::collision::fcl::Vector3& t)
{
#if FCL_VERSION_AT_LEAST(0, 6, 0)
return t.norm();
#else
return t.length();
#endif
}

//==============================================================================
double length2(const dart::collision::fcl::Vector3& t)
{
#if FCL_VERSION_AT_LEAST(0, 6, 0)
return t.squaredNorm();
#else
return t.sqrLength();
#endif
}

//==============================================================================
dart::collision::fcl::Vector3 getTranslation(
const dart::collision::fcl::Transform3& T)
{
#if FCL_VERSION_AT_LEAST(0, 6, 0)
return T.translation();
#else
return T.getTranslation();
#endif
}

//==============================================================================
void setTranslation(
dart::collision::fcl::Transform3& T, const dart::collision::fcl::Vector3& t)
{
#if FCL_VERSION_AT_LEAST(0, 6, 0)
T.translation() = t;
#else
T.setTranslation(t);
#endif
}

//==============================================================================
dart::collision::fcl::Matrix3 getRotation(
const dart::collision::fcl::Transform3& T)
{
#if FCL_VERSION_AT_LEAST(0, 6, 0)
return T.linear();
#else
return T.getRotation();
#endif
}

//==============================================================================
void setRotation(
dart::collision::fcl::Transform3& T, const dart::collision::fcl::Matrix3& R)
{
#if FCL_VERSION_AT_LEAST(0, 6, 0)
T.linear() = R;
#else
T.setRotation(R);
#endif
}

//==============================================================================
Expand All @@ -107,7 +83,6 @@ void setEulerZYX(
double eulerY,
double eulerZ)
{
#if FCL_VERSION_AT_LEAST(0, 6, 0)
double ci(cos(eulerX));
double cj(cos(eulerY));
double ch(cos(eulerZ));
Expand All @@ -124,21 +99,14 @@ void setEulerZYX(
cj * sh, sj * ss + cc, sj * cs - sc,
-sj, cj * si, cj * ci;
// clang-format on
#else
rot.setEulerZYX(eulerX, eulerY, eulerZ);
#endif
}

//==============================================================================
dart::collision::fcl::Vector3 transform(
const dart::collision::fcl::Transform3& t,
const dart::collision::fcl::Vector3& v)
{
#if FCL_VERSION_AT_LEAST(0, 6, 0)
return t * v;
#else
return t.transform(v);
#endif
}

} // namespace fcl
Expand Down
99 changes: 13 additions & 86 deletions dart/collision/fcl/BackwardCompatibility.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,67 +50,27 @@
(FCL_MINOR_VERSION < y || (FCL_MINOR_VERSION <= y))))
// clang-format on

#include <fcl/config.h>

#if FCL_VERSION_AT_LEAST(0, 6, 0)

#include <fcl/geometry/bvh/BVH_model.h>
#include <fcl/geometry/geometric_shape_to_BVH_model.h>
#include <fcl/math/bv/OBBRSS.h>
#include <fcl/math/bv/utility.h>
#include <fcl/math/geometry.h>
#include <fcl/narrowphase/collision.h>
#include <fcl/narrowphase/collision_object.h>
#include <fcl/narrowphase/distance.h>

#else

#include <fcl/BV/OBBRSS.h>
#include <fcl/BVH/BVH_model.h>
#include <fcl/collision.h>
#include <fcl/collision_data.h>
#include <fcl/collision_object.h>
#include <fcl/distance.h>
#include <fcl/math/matrix_3f.h>
#include <fcl/math/transform.h>
#include <fcl/math/vec_3f.h>
#include <fcl/shape/geometric_shape_to_BVH_model.h>

#endif // FCL_VERSION_AT_LEAST(0,6,0)

#include <fcl/broadphase/broadphase_dynamic_AABB_tree.h>
#include <fcl/config.h>
#include <fcl/geometry/bvh/BVH_model.h>
#include <fcl/geometry/geometric_shape_to_BVH_model.h>
#include <fcl/math/bv/OBBRSS.h>
#include <fcl/math/bv/utility.h>
#include <fcl/math/geometry.h>
#include <fcl/narrowphase/collision.h>
#include <fcl/narrowphase/collision_object.h>
#include <fcl/narrowphase/distance.h>

#if HAVE_OCTOMAP && FCL_HAVE_OCTOMAP
#if FCL_VERSION_AT_LEAST(0, 6, 0)
#include <fcl/geometry/octree/octree.h>
#else
#include <fcl/octree.h>
#endif // FCL_VERSION_AT_LEAST(0,6,0)
#endif // HAVE_OCTOMAP && FCL_HAVE_OCTOMAP
#include <fcl/geometry/octree/octree.h>
#endif // HAVE_OCTOMAP && FCL_HAVE_OCTOMAP

#include <memory>

/// \deprecated Use std::shared_ptr() instead
template <class T>
using fcl_shared_ptr = std::shared_ptr<T>;

/// \deprecated Use std::weak_ptr() instead
template <class T>
using fcl_weak_ptr = std::weak_ptr<T>;

/// \deprecated Use std::make_shared() instead
template <class T, class... Args>
DART_DEPRECATED(6.13)
std::shared_ptr<T> fcl_make_shared(Args&&... args)
{
return std::make_shared<T>(std::forward<Args>(args)...);
}

namespace dart {
namespace collision {
namespace fcl {

#if FCL_VERSION_AT_LEAST(0, 6, 0)
// Geometric fundamentals
using Vector3 = ::fcl::Vector3<double>;
using Matrix3 = ::fcl::Matrix3<double>;
Expand All @@ -122,9 +82,9 @@ using Cone = ::fcl::Cone<double>;
using Ellipsoid = ::fcl::Ellipsoid<double>;
using Halfspace = ::fcl::Halfspace<double>;
using Sphere = ::fcl::Sphere<double>;
#if HAVE_OCTOMAP && FCL_HAVE_OCTOMAP
#if HAVE_OCTOMAP && FCL_HAVE_OCTOMAP
using OcTree = ::fcl::OcTree<double>;
#endif // HAVE_OCTOMAP && FCL_HAVE_OCTOMAP
#endif // HAVE_OCTOMAP && FCL_HAVE_OCTOMAP
// Collision objects
using CollisionObject = ::fcl::CollisionObject<double>;
using CollisionGeometry = ::fcl::CollisionGeometry<double>;
Expand All @@ -136,35 +96,6 @@ using CollisionResult = ::fcl::CollisionResult<double>;
using DistanceRequest = ::fcl::DistanceRequest<double>;
using DistanceResult = ::fcl::DistanceResult<double>;
using Contact = ::fcl::Contact<double>;
#else
// Geometric fundamentals
using Vector3 = ::fcl::Vec3f;
using Matrix3 = ::fcl::Matrix3f;
using Transform3 = ::fcl::Transform3f;
// Geometric primitives
using Box = ::fcl::Box;
using Cylinder = ::fcl::Cylinder;
using Cone = ::fcl::Cone;
using Halfspace = ::fcl::Halfspace;
using Sphere = ::fcl::Sphere;
#if HAVE_OCTOMAP && FCL_HAVE_OCTOMAP
using OcTree = ::fcl::OcTree;
#endif // HAVE_OCTOMAP && FCL_HAVE_OCTOMAP
// Collision objects
using CollisionObject = ::fcl::CollisionObject;
using CollisionGeometry = ::fcl::CollisionGeometry;
using DynamicAABBTreeCollisionManager = ::fcl::DynamicAABBTreeCollisionManager;
using OBBRSS = ::fcl::OBBRSS;
using CollisionRequest = ::fcl::CollisionRequest;
using CollisionResult = ::fcl::CollisionResult;
using DistanceRequest = ::fcl::DistanceRequest;
using DistanceResult = ::fcl::DistanceResult;
using Contact = ::fcl::Contact;
#endif

#if !FCL_VERSION_AT_LEAST(0, 6, 0)
using Ellipsoid = ::fcl::Ellipsoid;
#endif

/// Returns norm of a 3-dim vector
double length(const dart::collision::fcl::Vector3& t);
Expand All @@ -174,11 +105,7 @@ double length2(const dart::collision::fcl::Vector3& t);

[[nodiscard]] inline dart::collision::fcl::Transform3 getTransform3Identity()
{
#if FCL_VERSION_AT_LEAST(0, 6, 0)
return dart::collision::fcl::Transform3::Identity();
#else
return dart::collision::fcl::Transform3();
#endif
}

/// Returns translation component of a transform
Expand Down
12 changes: 0 additions & 12 deletions dart/collision/fcl/FCLCollisionDetector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -503,19 +503,11 @@ ::fcl::BVHModel<BV>* createPyramid(
const double front = -d / 2;
const double back = d / 2;

#if FCL_VERSION_AT_LEAST(0, 6, 0)
points[0] << 0, 0, hTop;
points[1] << right, back, hBottom;
points[2] << left, back, hBottom;
points[3] << left, front, hBottom;
points[4] << right, front, hBottom;
#else
points[0].setValue(0, 0, hTop);
points[1].setValue(right, back, hBottom);
points[2].setValue(left, back, hBottom);
points[3].setValue(left, front, hBottom);
points[4].setValue(right, front, hBottom);
#endif

faces[0].set(0, 1, 2);
faces[1].set(0, 2, 3);
Expand All @@ -525,11 +517,7 @@ ::fcl::BVHModel<BV>* createPyramid(
faces[5].set(1, 4, 3);

for (unsigned int i = 0; i < points.size(); ++i) {
#if FCL_VERSION_AT_LEAST(0, 6, 0)
points[i] = pose * points[i];
#else
points[i] = pose.transform(points[i]);
#endif
}

model->beginModel();
Expand Down
35 changes: 0 additions & 35 deletions dart/collision/fcl/FCLTypes.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,60 +35,25 @@
namespace dart {
namespace collision {

#if !FCL_VERSION_AT_LEAST(0, 6, 0)
//==============================================================================
dart::collision::fcl::Vector3 FCLTypes::convertVector3(
const Eigen::Vector3d& _vec)
{
return dart::collision::fcl::Vector3(_vec[0], _vec[1], _vec[2]);
}
#endif

//==============================================================================
Eigen::Vector3d FCLTypes::convertVector3(
const dart::collision::fcl::Vector3& _vec)
{
#if FCL_VERSION_AT_LEAST(0, 6, 0)
return _vec;
#else
return Eigen::Vector3d(_vec[0], _vec[1], _vec[2]);
#endif
}

//==============================================================================
dart::collision::fcl::Matrix3 FCLTypes::convertMatrix3x3(
const Eigen::Matrix3d& _R)
{
#if FCL_VERSION_AT_LEAST(0, 6, 0)
return _R;
#else
return dart::collision::fcl::Matrix3(
_R(0, 0),
_R(0, 1),
_R(0, 2),
_R(1, 0),
_R(1, 1),
_R(1, 2),
_R(2, 0),
_R(2, 1),
_R(2, 2));
#endif
}

//==============================================================================
dart::collision::fcl::Transform3 FCLTypes::convertTransform(
const Eigen::Isometry3d& _T)
{
#if FCL_VERSION_AT_LEAST(0, 6, 0)
return _T;
#else
dart::collision::fcl::Transform3 trans;

trans.setTranslation(convertVector3(_T.translation()));
trans.setRotation(convertMatrix3x3(_T.linear()));

return trans;
#endif
}

} // namespace collision
Expand Down
5 changes: 0 additions & 5 deletions dart/collision/fcl/FCLTypes.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,11 +43,6 @@ namespace collision {
class FCLTypes
{
public:
#if !FCL_VERSION_AT_LEAST(0, 6, 0)
/// Convert Eigen vector3 type to FCL vector3 type
static dart::collision::fcl::Vector3 convertVector3(
const Eigen::Vector3d& _vec);
#endif
/// Convert FCL vector3 type to Eigen vector3 type
static Eigen::Vector3d convertVector3(
const dart::collision::fcl::Vector3& _vec);
Expand Down
6 changes: 6 additions & 0 deletions docs/readthedocs/developer_guide/build.rst
Original file line number Diff line number Diff line change
Expand Up @@ -143,8 +143,14 @@ Here's a summary of the dependencies required to build DART (WIP):
+------------+----------+---------+--------------+-------+
| Eigen | Yes | Runtime | 3.4.0 | |
+------------+----------+---------+--------------+-------+
| FCL | Yes | Runtime | 0.7.0 | |
+------------+----------+---------+--------------+-------+
| fmt | Yes | Runtime | 8.1.1 | |
+------------+----------+---------+--------------+-------+
| Bullet | No | Runtime | 3.06 | |
+------------+----------+---------+--------------+-------+
| Ipopt | No | Runtime | 3.11.9 | |
+------------+----------+---------+--------------+-------+

Clone the DART Repository
~~~~~~~~~~~~~~~~~~~~~~~~~
Expand Down

0 comments on commit c508317

Please sign in to comment.