Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Update API to support fcl 0.5 and tinyxml2 4.0 #749

Merged
merged 5 commits into from
Jul 21, 2016
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

* Collision detection

* Added support of FCL 0.5 and tinyxml2 4.0: [#749](https://github.com/dartsim/dart/pull/749)
* Added warnings for unsupported shape pairs of DARTCollisionDetector: [#722](https://github.com/dartsim/dart/pull/722)

* Misc improvements and bug fixes
Expand Down
12 changes: 4 additions & 8 deletions dart/collision/fcl/FCLCollisionDetector.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -431,8 +431,6 @@ fcl::BVHModel<BV>* createEllipsoid(float _sizeX, float _sizeY, float _sizeZ)
return model;
}

#if FCL_MAJOR_MINOR_VERSION_AT_MOST(0,4)

//==============================================================================
template<class BV>
fcl::BVHModel<BV>* createCylinder(double _baseRadius, double _topRadius,
Expand Down Expand Up @@ -536,8 +534,6 @@ fcl::BVHModel<BV>* createCylinder(double _baseRadius, double _topRadius,
return model;
}

#endif

//==============================================================================
template<class BV>
fcl::BVHModel<BV>* createMesh(float _scaleX, float _scaleY, float _scaleZ,
Expand Down Expand Up @@ -782,7 +778,7 @@ std::unique_ptr<CollisionObject> FCLCollisionDetector::createCollisionObject(
}

//==============================================================================
boost::shared_ptr<fcl::CollisionGeometry>
fcl_shared_ptr<fcl::CollisionGeometry>
FCLCollisionDetector::claimFCLCollisionGeometry(
const dynamics::ConstShapePtr& shape)
{
Expand All @@ -805,7 +801,7 @@ FCLCollisionDetector::claimFCLCollisionGeometry(
}

//==============================================================================
boost::shared_ptr<fcl::CollisionGeometry>
fcl_shared_ptr<fcl::CollisionGeometry>
FCLCollisionDetector::createFCLCollisionGeometry(
const dynamics::ConstShapePtr& shape,
FCLCollisionDetector::PrimitiveShape type,
Expand Down Expand Up @@ -943,9 +939,9 @@ FCLCollisionDetector::createFCLCollisionGeometry(
}

if (geom)
return boost::shared_ptr<fcl::CollisionGeometry>(geom, deleter);
return fcl_shared_ptr<fcl::CollisionGeometry>(geom, deleter);
else
return boost::shared_ptr<fcl::CollisionGeometry>();
return fcl_shared_ptr<fcl::CollisionGeometry>();
}

//==============================================================================
Expand Down
7 changes: 4 additions & 3 deletions dart/collision/fcl/FCLCollisionDetector.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
#include <fcl/collision_object.h>
#include <boost/weak_ptr.hpp> // This should be removed once we migrate to fcl 0.5
#include "dart/collision/CollisionDetector.hpp"
#include "dart/collision/fcl/FCLTypes.hpp"

namespace dart {
namespace collision {
Expand Down Expand Up @@ -130,7 +131,7 @@ class FCLCollisionDetector : public CollisionDetector

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

protected:
Expand Down Expand Up @@ -162,15 +163,15 @@ class FCLCollisionDetector : public CollisionDetector

/// Create fcl::CollisionGeometry with the custom deleter
/// FCLCollisionGeometryDeleter
boost::shared_ptr<fcl::CollisionGeometry> createFCLCollisionGeometry(
fcl_shared_ptr<fcl::CollisionGeometry> createFCLCollisionGeometry(
const dynamics::ConstShapePtr& shape,
FCLCollisionDetector::PrimitiveShape type,
const FCLCollisionGeometryDeleter& deleter);

private:

using ShapeMap = std::map<dynamics::ConstShapePtr,
boost::weak_ptr<fcl::CollisionGeometry>>;
fcl_weak_ptr<fcl::CollisionGeometry>>;
// TODO(JS): FCL replaced all the use of boost in version 0.5. Once we migrate
// to 0.5 or greater, this also should be changed to
// std::weak_ptr<fcl::CollisionGeometry>
Expand Down
2 changes: 1 addition & 1 deletion dart/collision/fcl/FCLCollisionObject.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -63,7 +63,7 @@ const fcl::CollisionObject* FCLCollisionObject::getFCLCollisionObject() const
FCLCollisionObject::FCLCollisionObject(
CollisionDetector* collisionDetector,
const dynamics::ShapeFrame* shapeFrame,
const boost::shared_ptr<fcl::CollisionGeometry>& fclCollGeom)
const fcl_shared_ptr<fcl::CollisionGeometry>& fclCollGeom)
: CollisionObject(collisionDetector, shapeFrame),
mFCLCollisionObjectUserData(new UserData(this)),
mFCLCollisionObject(new fcl::CollisionObject(fclCollGeom))
Expand Down
3 changes: 2 additions & 1 deletion dart/collision/fcl/FCLCollisionObject.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@

#include <fcl/collision_object.h>
#include "dart/collision/CollisionObject.hpp"
#include "dart/collision/fcl/FCLTypes.hpp"

namespace dart {
namespace collision {
Expand Down Expand Up @@ -64,7 +65,7 @@ class FCLCollisionObject : public CollisionObject
/// Constructor
FCLCollisionObject(CollisionDetector* collisionDetector,
const dynamics::ShapeFrame* shapeFrame,
const boost::shared_ptr<fcl::CollisionGeometry>& fclCollGeom);
const fcl_shared_ptr<fcl::CollisionGeometry>& fclCollGeom);

// Documentation inherited
void updateEngineData() override;
Expand Down
8 changes: 8 additions & 0 deletions dart/collision/fcl/FCLTypes.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,14 @@
(FCL_MAJOR_VERSION < x || (FCL_MAJOR_VERSION <= x && \
(FCL_MINOR_VERSION < y || (FCL_MINOR_VERSION <= y))))

#if FCL_VERSION_AT_LEAST(0,5,0)
template <class T> using fcl_shared_ptr = std::shared_ptr<T>;
template <class T> using fcl_weak_ptr = std::weak_ptr<T>;
#else
template <class T> using fcl_shared_ptr = boost::shared_ptr<T>;
template <class T> using fcl_weak_ptr = boost::weak_ptr<T>;
#endif

namespace dart {
namespace collision {

Expand Down
10 changes: 5 additions & 5 deletions dart/utils/XmlHelpers.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -726,7 +726,7 @@ bool getAttributeBool(const tinyxml2::XMLElement* element,
const int result = element->QueryBoolAttribute(attributeName.c_str(),
&val);

if (result != tinyxml2::XML_NO_ERROR)
if (result != tinyxml2::XML_SUCCESS)
{
dtwarn << "[getAttribute] Error in parsing bool type attribute ["
<< attributeName << "] of an element [" << element->Name()
Expand All @@ -744,7 +744,7 @@ int getAttributeInt(const tinyxml2::XMLElement* element,
int val = 0;
const int result = element->QueryIntAttribute(attributeName.c_str(), &val);

if (result != tinyxml2::XML_NO_ERROR)
if (result != tinyxml2::XML_SUCCESS)
{
dtwarn << "[getAttribute] Error in parsing int type attribute ["
<< attributeName << "] of an element [" << element->Name()
Expand All @@ -763,7 +763,7 @@ unsigned int getAttributeUInt(const tinyxml2::XMLElement* element,
const int result = element->QueryUnsignedAttribute(attributeName.c_str(),
&val);

if (result != tinyxml2::XML_NO_ERROR)
if (result != tinyxml2::XML_SUCCESS)
{
dtwarn << "[getAttribute] Error in parsing unsiged int type attribute ["
<< attributeName << "] of an element [" << element->Name()
Expand All @@ -782,7 +782,7 @@ float getAttributeFloat(const tinyxml2::XMLElement* element,
const int result = element->QueryFloatAttribute(attributeName.c_str(),
&val);

if (result != tinyxml2::XML_NO_ERROR)
if (result != tinyxml2::XML_SUCCESS)
{
dtwarn << "[getAttribute] Error in parsing float type attribute ["
<< attributeName << "] of an element [" << element->Name()
Expand All @@ -801,7 +801,7 @@ double getAttributeDouble(const tinyxml2::XMLElement* element,
const int result = element->QueryDoubleAttribute(attributeName.c_str(),
&val);

if (result != tinyxml2::XML_NO_ERROR)
if (result != tinyxml2::XML_SUCCESS)
{
dtwarn << "[getAttribute] Error in parsing double type attribute ["
<< attributeName << "] of an element [" << element->Name()
Expand Down