Skip to content

Commit

Permalink
Drop supporting FCL < 0.5 (#1647)
Browse files Browse the repository at this point in the history
  • Loading branch information
jslee02 authored Jan 14, 2022
1 parent be24fe9 commit 2a158b1
Show file tree
Hide file tree
Showing 14 changed files with 73 additions and 86 deletions.
4 changes: 4 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,10 @@

### [DART 6.13.0 (TBD)](https://github.com/dartsim/dart/milestone/69?closed=1)

* Build

* Dropped supporting FCL < 0.5: [#1647](https://github.com/dartsim/dart/pull/1647)

* Common

* Added Castable class: [#1634](https://github.com/dartsim/dart/pull/1634)
Expand Down
2 changes: 1 addition & 1 deletion cmake/DARTFindBoost.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#
# This file is provided under the "BSD-style" License

set(DART_MIN_BOOST_VERSION 1.58.0 CACHE INTERNAL "Boost min version requirement" FORCE)
set(DART_MIN_BOOST_VERSION 1.65.1 CACHE INTERNAL "Boost min version requirement" FORCE)
if(MSVC)
add_definitions(-DBOOST_ALL_NO_LIB)
endif()
Expand Down
9 changes: 5 additions & 4 deletions cmake/DARTFindassimp.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -10,10 +10,11 @@ find_package(assimp REQUIRED MODULE)

# Manually check version because the upstream version compatibility policy
# doesn't allow different major number while DART is compatible any version
# greater than or equal to 3.2.
if(ASSIMP_VERSION AND ASSIMP_VERSION VERSION_LESS 3.2)
message(SEND_ERROR "Found Assimp ${ASSIMP_VERSION}, but Assimp >= 3.2 is "
"required"
# greater than or equal to 4.1.
set(DART_ASSIMP_VERSION 4.1)
if(ASSIMP_VERSION AND ASSIMP_VERSION VERSION_LESS ${DART_ASSIMP_VERSION})
message(SEND_ERROR "Found Assimp ${ASSIMP_VERSION}, but Assimp >= ${DART_ASSIMP_VERSION}
is required"
)
endif()

Expand Down
2 changes: 1 addition & 1 deletion cmake/DARTFindoctomap.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#
# This file is provided under the "BSD-style" License

find_package(octomap 1.6.8 QUIET CONFIG)
find_package(octomap 1.8.1 QUIET CONFIG)

if(octomap_FOUND AND NOT TARGET octomap)
add_library(octomap INTERFACE IMPORTED)
Expand Down
28 changes: 11 additions & 17 deletions dart/collision/fcl/BackwardCompatibility.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@

#include <Eigen/Dense>

#include "dart/common/Deprecated.hpp"
#include "dart/config.hpp"

// clang-format off
Expand Down Expand Up @@ -88,30 +89,23 @@
#endif // FCL_VERSION_AT_LEAST(0,6,0)
#endif // HAVE_OCTOMAP && FCL_HAVE_OCTOMAP

#if FCL_VERSION_AT_LEAST(0, 5, 0)
#include <memory>
#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>
fcl_shared_ptr<T> fcl_make_shared(Args&&... args)
DART_DEPRECATED(6.13)
std::shared_ptr<T> fcl_make_shared(Args&&... args)
{
return std::make_shared<T>(std::forward<Args>(args)...);
}
#else
#include <boost/make_shared.hpp>
#include <boost/weak_ptr.hpp>
template <class T>
using fcl_shared_ptr = boost::shared_ptr<T>;
template <class T>
using fcl_weak_ptr = boost::weak_ptr<T>;
template <class T, class... Args>
fcl_shared_ptr<T> fcl_make_shared(Args&&... args)
{
return boost::make_shared<T>(std::forward<Args>(args)...);
}
#endif // FCL_VERSION_AT_LEAST(0,5,0)

namespace dart {
namespace collision {
Expand Down Expand Up @@ -169,7 +163,7 @@ using DistanceResult = ::fcl::DistanceResult;
using Contact = ::fcl::Contact;
#endif

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

Expand Down
13 changes: 3 additions & 10 deletions dart/collision/fcl/FCLCollisionDetector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -857,7 +857,7 @@ void FCLCollisionDetector::refreshCollisionObject(CollisionObject* const object)
}

//==============================================================================
fcl_shared_ptr<fcl::CollisionGeometry>
std::shared_ptr<fcl::CollisionGeometry>
FCLCollisionDetector::claimFCLCollisionGeometry(
const dynamics::ConstShapePtr& shape)
{
Expand Down Expand Up @@ -885,7 +885,7 @@ FCLCollisionDetector::claimFCLCollisionGeometry(
}

//==============================================================================
fcl_shared_ptr<fcl::CollisionGeometry>
std::shared_ptr<fcl::CollisionGeometry>
FCLCollisionDetector::createFCLCollisionGeometry(
const dynamics::ConstShapePtr& shape,
FCLCollisionDetector::PrimitiveShape type,
Expand Down Expand Up @@ -942,12 +942,7 @@ FCLCollisionDetector::createFCLCollisionGeometry(

if (FCLCollisionDetector::PRIMITIVE == type)
{
#if FCL_VERSION_AT_LEAST(0, 4, 0)
geom = new fcl::Ellipsoid(FCLTypes::convertVector3(radii));
#else
geom = createEllipsoid<fcl::OBBRSS>(
radii[0] * 2.0, radii[1] * 2.0, radii[2] * 2.0);
#endif
}
else
{
Expand Down Expand Up @@ -1079,7 +1074,7 @@ FCLCollisionDetector::createFCLCollisionGeometry(
geom = createEllipsoid<fcl::OBBRSS>(0.1, 0.1, 0.1);
}

return fcl_shared_ptr<fcl::CollisionGeometry>(geom, deleter);
return std::shared_ptr<fcl::CollisionGeometry>(geom, deleter);
}

//==============================================================================
Expand Down Expand Up @@ -1657,9 +1652,7 @@ void convertOption(
{
request.num_max_contacts = option.maxNumContacts;
request.enable_contact = option.enableContact;
#if FCL_VERSION_AT_LEAST(0, 3, 0)
request.gjk_solver_type = ::fcl::GST_LIBCCD;
#endif
}

//==============================================================================
Expand Down
6 changes: 3 additions & 3 deletions dart/collision/fcl/FCLCollisionDetector.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ class FCLCollisionDetector : public CollisionDetector

/// Return fcl::CollisionGeometry associated with give Shape. New
/// fcl::CollisionGeome will be created if it hasn't created yet.
fcl_shared_ptr<dart::collision::fcl::CollisionGeometry>
std::shared_ptr<dart::collision::fcl::CollisionGeometry>
claimFCLCollisionGeometry(const dynamics::ConstShapePtr& shape);

protected:
Expand Down Expand Up @@ -176,15 +176,15 @@ class FCLCollisionDetector : public CollisionDetector
struct ShapeInfo final
{
/// A weak reference to the shape
fcl_weak_ptr<dart::collision::fcl::CollisionGeometry> mShape;
std::weak_ptr<dart::collision::fcl::CollisionGeometry> mShape;

/// The last version of the shape, as known by this collision detector
std::size_t mLastKnownVersion;
};

/// Create fcl::CollisionGeometry with the custom deleter
/// FCLCollisionGeometryDeleter
fcl_shared_ptr<dart::collision::fcl::CollisionGeometry>
std::shared_ptr<dart::collision::fcl::CollisionGeometry>
createFCLCollisionGeometry(
const dynamics::ConstShapePtr& shape,
FCLCollisionDetector::PrimitiveShape type,
Expand Down
8 changes: 1 addition & 7 deletions dart/collision/fcl/FCLCollisionObject.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ FCLCollisionObject::getFCLCollisionObject() const
FCLCollisionObject::FCLCollisionObject(
CollisionDetector* collisionDetector,
const dynamics::ShapeFrame* shapeFrame,
const fcl_shared_ptr<dart::collision::fcl::CollisionGeometry>& fclCollGeom)
const std::shared_ptr<dart::collision::fcl::CollisionGeometry>& fclCollGeom)
: CollisionObject(collisionDetector, shapeFrame),
mFCLCollisionObject(new dart::collision::fcl::CollisionObject(fclCollGeom))
{
Expand All @@ -83,14 +83,8 @@ void FCLCollisionObject::updateEngineData()
const_cast<SoftMeshShape*>(softMeshShape)->update();
// TODO(JS): update function be called by somewhere out of here.

#if FCL_VERSION_AT_LEAST(0, 3, 0)
auto collGeom = const_cast<dart::collision::fcl::CollisionGeometry*>(
mFCLCollisionObject->collisionGeometry().get());
#else
dart::collision::fcl::CollisionGeometry* collGeom
= const_cast<dart::collision::fcl::CollisionGeometry*>(
mFCLCollisionObject->getCollisionGeometry());
#endif
assert(
dynamic_cast<::fcl::BVHModel<dart::collision::fcl::OBBRSS>*>(collGeom));
auto bvhModel
Expand Down
2 changes: 1 addition & 1 deletion dart/collision/fcl/FCLCollisionObject.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@ class FCLCollisionObject : public CollisionObject
FCLCollisionObject(
CollisionDetector* collisionDetector,
const dynamics::ShapeFrame* shapeFrame,
const fcl_shared_ptr<dart::collision::fcl::CollisionGeometry>&
const std::shared_ptr<dart::collision::fcl::CollisionGeometry>&
fclCollGeom);

// Documentation inherited
Expand Down
2 changes: 1 addition & 1 deletion dart/constraint/ConstraintSolver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -757,7 +757,7 @@ void ConstraintSolver::addContactSurfaceHandler(
if (handler == mContactSurfaceHandler)
{
dterr << "Adding the same contact surface handler for the second time, "
"ignoring." << std::endl;
<< "ignoring.\n";
return;
}
handler->setParent(mContactSurfaceHandler);
Expand Down
4 changes: 2 additions & 2 deletions dart/constraint/ContactSurface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,7 +113,7 @@ class ContactSurfaceHandler
/// when adding a new one. It is suggested to keep this
/// paradigm if used elsewhere.
explicit ContactSurfaceHandler(ContactSurfaceHandlerPtr parent = nullptr);

virtual ~ContactSurfaceHandler() = default;

/// Create parameters of the contact constraint. This method should combine
Expand Down Expand Up @@ -152,7 +152,7 @@ class DefaultContactSurfaceHandler : public ContactSurfaceHandler
{
public:
virtual ~DefaultContactSurfaceHandler() = default;

// Documentation inherited
ContactSurfaceParams createParams(
const collision::Contact& contact,
Expand Down
15 changes: 8 additions & 7 deletions dart/dynamics/VoxelGridShape.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,19 +79,20 @@ octomap::pose6d toPose6d(const Eigen::Isometry3d& frame)
//==============================================================================
VoxelGridShape::VoxelGridShape(double resolution) : Shape()
{
setOctree(fcl_make_shared<octomap::OcTree>(resolution));
setOctree(std::make_shared<octomap::OcTree>(resolution));

mVariance = DYNAMIC_ELEMENTS;
}

//==============================================================================
VoxelGridShape::VoxelGridShape(fcl_shared_ptr<octomap::OcTree> octree) : Shape()
VoxelGridShape::VoxelGridShape(std::shared_ptr<octomap::OcTree> octree)
: Shape()
{
if (!octree)
{
dtwarn << "[VoxelGridShape] Attempting to assign null octree. Creating an "
<< "empty octree with resolution 0.01 instead.\n";
setOctree(fcl_make_shared<octomap::OcTree>(0.01));
setOctree(std::make_shared<octomap::OcTree>(0.01));
return;
}

Expand All @@ -112,7 +113,7 @@ const std::string& VoxelGridShape::getStaticType()
}

//==============================================================================
void VoxelGridShape::setOctree(fcl_shared_ptr<octomap::OcTree> octree)
void VoxelGridShape::setOctree(std::shared_ptr<octomap::OcTree> octree)
{
if (!octree)
{
Expand All @@ -134,13 +135,13 @@ void VoxelGridShape::setOctree(fcl_shared_ptr<octomap::OcTree> octree)
}

//==============================================================================
fcl_shared_ptr<octomap::OcTree> VoxelGridShape::getOctree()
std::shared_ptr<octomap::OcTree> VoxelGridShape::getOctree()
{
return mOctree;
}

//==============================================================================
fcl_shared_ptr<const octomap::OcTree> VoxelGridShape::getOctree() const
std::shared_ptr<const octomap::OcTree> VoxelGridShape::getOctree() const
{
return mOctree;
}
Expand Down Expand Up @@ -220,7 +221,7 @@ void VoxelGridShape::notifyColorUpdated(const Eigen::Vector4d& /*color*/)
ShapePtr VoxelGridShape::clone() const
{
return std::make_shared<VoxelGridShape>(
fcl_make_shared<octomap::OcTree>(*mOctree));
std::make_shared<octomap::OcTree>(*mOctree));
}

//==============================================================================
Expand Down
10 changes: 5 additions & 5 deletions dart/dynamics/VoxelGridShape.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@ class VoxelGridShape : public Shape

/// Constructs from a octomap::OcTree.
/// \param[in] octree Octree.
explicit VoxelGridShape(fcl_shared_ptr<octomap::OcTree> octree);
explicit VoxelGridShape(std::shared_ptr<octomap::OcTree> octree);

/// Destructor.
~VoxelGridShape() override = default;
Expand All @@ -68,13 +68,13 @@ class VoxelGridShape : public Shape
static const std::string& getStaticType();

/// Sets octree.
void setOctree(fcl_shared_ptr<octomap::OcTree> octree);
void setOctree(std::shared_ptr<octomap::OcTree> octree);

/// Returns octree.
fcl_shared_ptr<octomap::OcTree> getOctree();
std::shared_ptr<octomap::OcTree> getOctree();

/// Returns octree.
fcl_shared_ptr<const octomap::OcTree> getOctree() const;
std::shared_ptr<const octomap::OcTree> getOctree() const;

/// Updates the occupancy probability of the voxels where \c point is located.
///
Expand Down Expand Up @@ -158,7 +158,7 @@ class VoxelGridShape : public Shape
void updateVolume() const override;

/// Octree.
fcl_shared_ptr<octomap::OcTree> mOctree;
std::shared_ptr<octomap::OcTree> mOctree;
// TODO(JS): Use std::shared_ptr once we drop supporting FCL (< 0.5)
};

Expand Down
Loading

0 comments on commit 2a158b1

Please sign in to comment.