Skip to content
Snippets Groups Projects
Commit 6a67e242 authored by Joseph Mirabel's avatar Joseph Mirabel Committed by Joseph Mirabel
Browse files

Update to last changes in hpp-fcl

* hpp-fcl uses only Eigen types in future version.
* The FCL_HAVE_EIGEN makes it compatible with older version of hpp-fcl.
* See comment in src/spatial/fcl-pinocchio-conversions.hpp
* for more details.
parent f7a67855
No related branches found
No related tags found
No related merge requests found
......@@ -24,6 +24,18 @@
namespace se3
{
#if FCL_HAVE_EIGEN
// TODO When not supporting the version of hpp-fcl (v0.5) not using plain eigen types
// the following functions can be removed because
// - fcl::Matrix3f = Eigen::Matrix3d
// - fcl::Vec3f = Eigen::Vector3d
// Currently, they are mandatory to support both v0.5 with FCL_HAVE_EIGEN and
// future version
inline fcl::Matrix3f toFclMatrix3f (Eigen::Matrix3d const & mat) { return mat; }
inline Eigen::Matrix3d toMatrix3d (fcl::Matrix3f const & mat) { return mat; }
inline fcl::Vec3f toFclVec3f (Eigen::Vector3d const & vec) { return vec; }
inline Eigen::Vector3d toVector3d (fcl::Vec3f const & vec) { return vec; }
#else // FCL_HAVE_EIGEN
inline fcl::Matrix3f toFclMatrix3f(const Eigen::Matrix3d & mat)
{
return fcl::Matrix3f( mat(0,0),mat(0,1), mat(0,2),
......@@ -50,6 +62,7 @@ namespace se3
{
return Eigen::Vector3d(vec[0],vec[1],vec[2]);
}
#endif // FCL_HAVE_EIGEN
inline fcl::Transform3f toFclTransform3f(const SE3 & m)
{
......
......@@ -156,13 +156,13 @@ BOOST_AUTO_TEST_CASE ( simple_boxes )
model.appendBodyToJoint(idx,Inertia::Random(),SE3::Identity());
model.addBodyFrame("planar2_body", idx, SE3::Identity());
boost::shared_ptr<fcl::Box> sample(new fcl::Box(1));
boost::shared_ptr<fcl::Box> sample(new fcl::Box(1, 1, 1));
geomModel.addGeometryObject(GeometryObject("ff1_collision_object",
model.getBodyId("planar1_body"),0,
sample,SE3::Identity(), "", Eigen::Vector3d::Ones()),
model,true);
boost::shared_ptr<fcl::Box> sample2(new fcl::Box(1));
boost::shared_ptr<fcl::Box> sample2(new fcl::Box(1, 1, 1));
geomModel.addGeometryObject(GeometryObject("ff2_collision_object",
model.getBodyId("planar2_body"),0,
sample2,SE3::Identity(), "", Eigen::Vector3d::Ones()),
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment