Giter Site home page Giter Site logo

hpp-fcl's Introduction

HPP-FCL — An extension of the Flexible Collision Library

Pipeline status Documentation Coverage report Conda Downloads Conda Version PyPI version black ruff

FCL was forked in 2015. Since then, a large part of the code has been rewritten or removed (for the unused and untested part). The broad phase was reintroduced by Justin Carpentier in 2022 based on the FCL version 0.7.0.

If you use HPP-FCL in your projects and research papers, we would appreciate it if you'd cite it.

New features

Compared to the original FCL library, the main new features are:

  • a dedicated and efficient implementation of the GJK algorithm (we do not rely anymore on libccd)
  • the support of safety margins for collision detection
  • an accelerated version of collision detection à la Nesterov, which leads to increased performances (up to a factor of 2). More details are available in this paper
  • the computation of a lower bound of the distance between two objects when collision checking is performed, and no collision is found
  • the implementation of Python bindings for easy code prototyping
  • the support of new geometries such as height fields, capsules, ellipsoids, etc.
  • enhance reliability with the fix of a myriad of bugs
  • efficient computation of contact points and contact patches between objects
  • full support of object serialization via Boost.Serialization

This project is now used in many robotics frameworks such as Pinocchio, an open-source software that implements efficient and versatile rigid body dynamics algorithms, the Humanoid Path Planner, an open-source software for Motion and Manipulation Planning. HPP-FCL has also been recently used to develop Simple, a new (differentiable) and efficient simulator for robotics and beyond.

A high-performance library

Unlike the original FCL library, HPP-FCL implements the well-established GJK algorithm and its variants for collision detection and distance computation. These implementations lead to state-of-the-art performances, as depicted by the figures below.

On the one hand, we have benchmarked HPP-FCL against major software alternatives of the state of the art:

  1. the Bullet simulator,
  2. the original FCL library (used in the Drake framework),
  3. the libccd library (used in MuJoCo).

The results are depicted in the following figure, which notably shows that the accelerated variants of GJK largely outperform by a large margin (from 5x up to 15x times faster). Please notice that the y-axis is in log scale.

HPP-FCL vs the rest of the world

On the other hand, why do we care about dedicated collision detection solvers like GJK for the narrow phase? Why can't we simply formulate the collision detection problem as a quadratic problem and call an off-the-shelf optimization solver like ProxQP)? Here is why.

HPP-FCL vs generic QP solvers

One can observe that GJK-based approaches largely outperform solutions based on classic optimization solvers (e.g., QP solver like ProxQP), notably for large geometries composed of tens or hundreds of vertices.

Open-source projects relying on Pinocchio

  • Pinocchio A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives.
  • IfcOpenShell Open source IFC library and geometry engine.
  • Crocoddyl A software to realize model predictive control for complex robotics platforms.
  • TSID A software that implements a Task Space Inverse Dynamics QP.
  • HPP A SDK that implements motion planners for humanoids and other robots.
  • Jiminy A simulator based on Pinocchio.
  • ocs2 A toolbox for Optimal Control for Switched Systems (OCS2)

C++ example

Both the C++ library and the python bindings can be installed as simply as conda -c conda-forge install hpp-fcl. The .so library, include files and python bindings will then be installed under $CONDA_PREFIX/lib, $CONDA_PREFIX/include and $CONDA_PREFIX/lib/python3.XX/site-packages.

Here is an example of using HPP-FCL in C++:

#include "hpp/fcl/math/transform.h"
#include "hpp/fcl/mesh_loader/loader.h"
#include "hpp/fcl/BVH/BVH_model.h"
#include "hpp/fcl/collision.h"
#include "hpp/fcl/collision_data.h"
#include <iostream>
#include <memory>

// Function to load a convex mesh from a `.obj`, `.stl` or `.dae` file.
//
// This function imports the object inside the file as a BVHModel, i.e. a point cloud
// which is hierarchically transformed into a tree of bounding volumes.
// The leaves of this tree are the individual points of the point cloud
// stored in the `.obj` file.
// This BVH can then be used for collision detection.
//
// For better computational efficiency, we sometimes prefer to work with
// the convex hull of the point cloud. This insures that the underlying object
// is convex and thus very fast collision detection algorithms such as
// GJK or EPA can be called with this object.
// Consequently, after creating the BVH structure from the point cloud, this function
// also computes its convex hull.
std::shared_ptr<hpp::fcl::ConvexBase> loadConvexMesh(const std::string& file_name) {
  hpp::fcl::NODE_TYPE bv_type = hpp::fcl::BV_AABB;
  hpp::fcl::MeshLoader loader(bv_type);
  hpp::fcl::BVHModelPtr_t bvh = loader.load(file_name);
  bvh->buildConvexHull(true, "Qt");
  return bvh->convex;
}

int main() {
  // Create the hppfcl shapes.
  // Hppfcl supports many primitive shapes: boxes, spheres, capsules, cylinders, ellipsoids, cones, planes,
  // halfspace and convex meshes (i.e. convex hulls of clouds of points).
  // It also supports BVHs (bounding volumes hierarchies), height-fields and octrees.
  std::shared_ptr<hpp::fcl::Ellipsoid> shape1 = std::make_shared<hpp::fcl::Ellipsoid>(0.7, 1.0, 0.8);
  std::shared_ptr<hpp::fcl::ConvexBase> shape2 = loadConvexMesh("../path/to/mesh/file.obj");

  // Define the shapes' placement in 3D space
  hpp::fcl::Transform3f T1;
  T1.setQuatRotation(hpp::fcl::Quaternion3f::UnitRandom());
  T1.setTranslation(hpp::fcl::Vec3f::Random());
  hpp::fcl::Transform3f T2 = hpp::fcl::Transform3f::Identity();
  T2.setQuatRotation(hpp::fcl::Quaternion3f::UnitRandom());
  T2.setTranslation(hpp::fcl::Vec3f::Random());

  // Define collision requests and results.
  //
  // The collision request allows to set parameters for the collision pair.
  // For example, we can set a positive or negative security margin.
  // If the distance between the shapes is less than the security margin, the shapes
  // will be considered in collision.
  // Setting a positive security margin can be usefull in motion planning,
  // i.e to prevent shapes from getting too close to one another.
  // In physics simulation, allowing a negative security margin may be usefull to stabilize the simulation.
  hpp::fcl::CollisionRequest col_req;
  col_req.security_margin = 1e-1;
  // A collision result stores the result of the collision test (signed distance between the shapes,
  // witness points location, normal etc.)
  hpp::fcl::CollisionResult col_res;

  // Collision call
  hpp::fcl::collide(shape1.get(), T1, shape2.get(), T2, col_req, col_res);

  // We can access the collision result once it has been populated
  std::cout << "Collision? " << col_res.isCollision() << "\n";
  if (col_res.isCollision()) {
    hpp::fcl::Contact contact = col_res.getContact(0);
    // The penetration depth does **not** take into account the security margin.
    // Consequently, the penetration depth is the true signed distance which separates the shapes.
    // To have the distance which takes into account the security margin, we can simply add the two together.
    std::cout << "Penetration depth: " << contact.penetration_depth << "\n";
    std::cout << "Distance between the shapes including the security margin: " << contact.penetration_depth + col_req.security_margin << "\n";
    std::cout << "Witness point on shape1: " << contact.nearest_points[0].transpose() << "\n";
    std::cout << "Witness point on shape2: " << contact.nearest_points[1].transpose() << "\n";
    std::cout << "Normal: " << contact.normal.transpose() << "\n";
  }

  // Before calling another collision test, it is important to clear the previous results stored in the collision result.
  col_res.clear();

  return 0;
}

Python example

Here is the C++ example from above translated in python using HPP-FCL's python bindings:

import numpy as np
import hppfcl
# Optional:
# The Pinocchio library is a rigid body algorithms library and has a handy SE3 module.
# It can be installed as simply as `conda -c conda-forge install pinocchio`.
# Installing pinocchio also installs hpp-fcl.
import pinocchio as pin

def loadConvexMesh(file_name: str):
    loader = hppfcl.MeshLoader()
    bvh: hppfcl.BVHModelBase = loader.load(file_name)
    bvh.buildConvexHull(True, "Qt")
    return bvh.convex

if __name__ == "__main__":
    # Create hppfcl shapes
    shape1 = hppfcl.Ellipsoid(0.7, 1.0, 0.8)
    shape2 = loadConvexMesh("../path/to/mesh/file.obj")

    # Define the shapes' placement in 3D space
    T1 = hppfcl.Transform3f()
    T1.setTranslation(pin.SE3.Random().translation)
    T1.setRotation(pin.SE3.Random().rotation)
    T2 = hppfcl.Transform3f();
    # Using np arrays also works
    T1.setTranslation(np.random.rand(3))
    T2.setRotation(pin.SE3.Random().rotation)

    # Define collision requests and results
    col_req = hppfcl.CollisionRequest()
    col_res = hppfcl.CollisionResult()

    # Collision call
    hppfcl.collide(shape1, T1, shape2, T2, col_req, col_res)

    # Accessing the collision result once it has been populated
    print("Is collision? ", {col_res.isCollision()})
    if col_res.isCollision():
        contact: hppfcl.Contact = col_res.getContact(0)
        print("Penetration depth: ", contact.penetration_depth)
        print("Distance between the shapes including the security margin: ", contact.penetration_depth + col_req.security_margin)
        print("Witness point shape1: ", contact.getNearestPoint1())
        print("Witness point shape2: ", contact.getNearestPoint2())
        print("Normal: ", contact.normal)

    # Before running another collision call, it is important to clear the old one
    col_res.clear()

Acknowledgments

The development of HPP-FCL is actively supported by the Gepetto team @LAAS-CNRS, the Willow team @INRIA and, to some extend, Eureka Robotics.

hpp-fcl's People

Contributors

aorthey avatar edsterg avatar florent-lamiraux avatar fvalenza avatar gabrielebndn avatar gauthamm avatar isucan avatar jcarpent avatar jiayuan-gu avatar jmirabel avatar jorisv avatar jslee02 avatar jvgomez avatar lmontaut avatar lucileremigy avatar mamoll avatar manifoldfr avatar maximiliennaveau avatar mfelis avatar nim65s avatar panjia1983 avatar pantor avatar pfernbach avatar pre-commit-ci[bot] avatar remod avatar rstrudel avatar scpeters avatar stephane-caron avatar tobiaskunz avatar wxmerkt avatar

Stargazers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

Watchers

 avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar  avatar

hpp-fcl's Issues

Latest release on robotpkg apt repository

Would it be possible to "upload" the latest release 1.5.3 on robotpkg repository (compatible with the latest Pinocchio release) ? It seems many changes have been introduced since the latest available one 1.4.5.

Are the changes to assimp public?

Is the source repository for robotpkg-assimp public, and if so, what is the URL? I noticed issues with libassimp-dev on Bionic (wrong include directory) and am wondering what changes and potential fixes are in robotpkg-assimp

Merging the refactoring branch to devel

I am writing this issue to keep track of what is missing for the refactoring branch to be mature enough for a release.
So far, I can identify:

  • Handle redundancy between lz and HalfLength in Cylinder, Capsule and Cone. This can be done by either removing lz or by making the variables private and providing appropriate getter/setter methods which ensure consistency between the two values
  • Fix the CI failure in unit test frontlist. As far as I have understood, the buggy feature could be removed altogether
  • Expand the Python bindings so that they cover at least all classes and methods currently exposed in Pinocchio and the most important core algorithms
  • Verify the Python bindings through appropriate unit tests
  • Install internal headers.
  • Run integration test for known dependencies (pinocchio and HPP)

@jmirabel, I know you have something to add to the list. Feel free to edit this post
@nmansard, could you provide feedback of what you need to be exposed for your tutorials?

Suspect bug in collide function on master and devel branches

Hi,
while testing pinocchio on Ubuntu 19.04 I found that a unit test was not passing, and I suspect the root cause is in hpp-fcl.

So, in Pinocchio, I saw test unittest/geom was not passing. This is the error I get:

/home/gabriele/devel/pinocchio/unittest/geom.cpp(100): error: in "geomTest/simple_boxes": check computeCollision(geomModel,geomData,0) == true has failed
/home/gabriele/devel/pinocchio/unittest/geom.cpp(112): error: in "geomTest/simple_boxes": check computeCollision(geomModel,geomData,0) == true has failed

*** 2 failures are detected in the test module "geomTest"

After struggling to understand why the github CI was passing, I realised I was not on the latest release, but on branch master, which is forward with respect to it. I can confirm the unit test passes on v1.3.0.

I suspect this is a bug in hpp-fcl, or that at least this is due to a non-backward-compatible change in hpp-fcl. What reinforces the suspect is that I sometimes don't get the same errors, suggesting an issue with uninitialized variables.

I investigated the Pinocchio unit test with valgrind, and indeed I found

Conditional jump or move depends on uninitialised value(s)

More precicely, after commenting everything but the first check:

==24940== Conditional jump or move depends on uninitialised value(s)
==24940==    at 0x4D154E5: hpp::fcl::DistanceResult::update(double, hpp::fcl::CollisionGeometry const*, hpp::fcl::CollisionGeometry const*, int, int, Eigen::Matrix<double, 3, 1, 0, 3, 1> const&, Eigen::Matrix<double, 3, 1, 0, 3, 1> const&, Eigen::Matrix<double, 3, 1, 0, 3, 1> const&) (collision_data.h:388)
==24940==    by 0x4D529A6: hpp::fcl::ShapeDistanceTraversalNode<hpp::fcl::Box, hpp::fcl::Box>::leafComputeDistance(int, int) const (traversal_node_shapes.h:150)
==24940==    by 0x4E5A110: hpp::fcl::distanceRecurse(hpp::fcl::DistanceTraversalNodeBase*, int, int, std::__cxx11::list<hpp::fcl::BVHFrontNode, std::allocator<hpp::fcl::BVHFrontNode> >*) (traversal_recurse.cpp:172)
==24940==    by 0x4D88CD5: hpp::fcl::distance(hpp::fcl::DistanceTraversalNodeBase*, std::__cxx11::list<hpp::fcl::BVHFrontNode, std::allocator<hpp::fcl::BVHFrontNode> >*, int) (collision_node.cpp:72)
==24940==    by 0x4D17C16: double hpp::fcl::ShapeShapeDistance<hpp::fcl::Box, hpp::fcl::Box>(hpp::fcl::CollisionGeometry const*, hpp::fcl::Transform3f const&, hpp::fcl::CollisionGeometry const*, hpp::fcl::Transform3f const&, hpp::fcl::GJKSolver const*, hpp::fcl::DistanceRequest const&, hpp::fcl::DistanceResult&) (distance_func_matrix.cpp:79)
==24940==    by 0x4EB9740: unsigned long hpp::fcl::ShapeShapeCollide<hpp::fcl::Box, hpp::fcl::Box>(hpp::fcl::CollisionGeometry const*, hpp::fcl::Transform3f const&, hpp::fcl::CollisionGeometry const*, hpp::fcl::Transform3f const&, hpp::fcl::GJKSolver const*, hpp::fcl::CollisionRequest const&, hpp::fcl::CollisionResult&) (collision_func_matrix.cpp:83)
==24940==    by 0x4D1296F: hpp::fcl::collide(hpp::fcl::CollisionGeometry const*, hpp::fcl::Transform3f const&, hpp::fcl::CollisionGeometry const*, hpp::fcl::Transform3f const&, hpp::fcl::CollisionRequest const&, hpp::fcl::CollisionResult&) (collision.cpp:127)
==24940==    by 0x4D125B6: hpp::fcl::collide(hpp::fcl::CollisionObject const*, hpp::fcl::CollisionObject const*, hpp::fcl::CollisionRequest const&, hpp::fcl::CollisionResult&) (collision.cpp:76)
==24940==    by 0x5760DC: pinocchio::computeCollision(pinocchio::GeometryModel const&, pinocchio::GeometryData&, unsigned long const&) (geometry.hxx:66)
==24940==    by 0x570B0F: geomTest::simple_boxes::test_method() (geom.cpp:100)
==24940==    by 0x56F027: geomTest::simple_boxes_invoker() (geom.cpp:33)
==24940==    by 0x596C53: boost::detail::function::void_function_invoker0<void (*)(), void>::invoke(boost::detail::function::function_buffer&) (function_template.hpp:118)
==24940== 
==24940== Conditional jump or move depends on uninitialised value(s)
==24940==    at 0x4EB975D: unsigned long hpp::fcl::ShapeShapeCollide<hpp::fcl::Box, hpp::fcl::Box>(hpp::fcl::CollisionGeometry const*, hpp::fcl::Transform3f const&, hpp::fcl::CollisionGeometry const*, hpp::fcl::Transform3f const&, hpp::fcl::GJKSolver const*, hpp::fcl::CollisionRequest const&, hpp::fcl::CollisionResult&) (collision_func_matrix.cpp:85)
==24940==    by 0x4D1296F: hpp::fcl::collide(hpp::fcl::CollisionGeometry const*, hpp::fcl::Transform3f const&, hpp::fcl::CollisionGeometry const*, hpp::fcl::Transform3f const&, hpp::fcl::CollisionRequest const&, hpp::fcl::CollisionResult&) (collision.cpp:127)
==24940==    by 0x4D125B6: hpp::fcl::collide(hpp::fcl::CollisionObject const*, hpp::fcl::CollisionObject const*, hpp::fcl::CollisionRequest const&, hpp::fcl::CollisionResult&) (collision.cpp:76)
==24940==    by 0x5760DC: pinocchio::computeCollision(pinocchio::GeometryModel const&, pinocchio::GeometryData&, unsigned long const&) (geometry.hxx:66)
==24940==    by 0x570B0F: geomTest::simple_boxes::test_method() (geom.cpp:100)
==24940==    by 0x56F027: geomTest::simple_boxes_invoker() (geom.cpp:33)
==24940==    by 0x596C53: boost::detail::function::void_function_invoker0<void (*)(), void>::invoke(boost::detail::function::function_buffer&) (function_template.hpp:118)
==24940==    by 0x5182A4D: boost::detail::function::function_obj_invoker0<boost::detail::forward, int>::invoke(boost::detail::function::function_buffer&) (in /usr/lib/x86_64-linux-gnu/libboost_unit_test_framework.so.1.67.0)
==24940==    by 0x5182634: boost::execution_monitor::catch_signals(boost::function<int ()> const&) (in /usr/lib/x86_64-linux-gnu/libboost_unit_test_framework.so.1.67.0)
==24940==    by 0x5182700: boost::execution_monitor::execute(boost::function<int ()> const&) (in /usr/lib/x86_64-linux-gnu/libboost_unit_test_framework.so.1.67.0)
==24940==    by 0x51827CC: boost::execution_monitor::vexecute(boost::function<void ()> const&) (in /usr/lib/x86_64-linux-gnu/libboost_unit_test_framework.so.1.67.0)
==24940==    by 0x51AA1C8: boost::unit_test::unit_test_monitor_t::execute_and_translate(boost::function<void ()> const&, unsigned int) (in /usr/lib/x86_64-linux-gnu/libboost_unit_test_framework.so.1.67.0)

Where the second issue seems to be a consequence of the first one.
Then I dug into the code. It seems that the most likely explanation is that when this method is called:

/// @brief Distance testing between leaves (two shapes)
void leafComputeDistance(int, int) const
{
FCL_REAL distance;
Vec3f closest_p1, closest_p2, normal;
nsolver->shapeDistance(*model1, tf1, *model2, tf2, distance, closest_p1,
closest_p2, normal);
result->update(distance, model1, model2, DistanceResult::NONE,
DistanceResult::NONE, closest_p1, closest_p2, normal);
}

shapeDistance leaves variable distance unininitialized. So, I examined shapeDistance. I found that indeed, during the unit test, the execution path arrives here:

if(epa_status & details::EPA::Valid
|| epa_status == details::EPA::OutOfFaces // Warnings
|| epa_status == details::EPA::OutOfVertices // Warnings
)
{
Vec3f w0, w1;
epa.getClosestPoints (shape, w0, w1);
assert (epa.depth >= -eps);
distance = std::min (0., -epa.depth);
// TODO should be
// normal = tf1.getRotation() * epa.normal;
normal = tf2.getRotation() * epa.normal;
p1 = p2 = tf1.transform(w0 - epa.normal*(epa.depth *0.5));
}

but the if fails, leaving distance uninitialized.
This function was heavily modified with commit 741f38b. I suspect this is the root cause. Before this commit, it seems all execution paths left the variable distance initialized.
At this point, I stop. I pushed the analysis as deep as I could, but I do not know how to go forward.

@jmirabel, can you check this? Why was the Pinocchio unit test working well with HPP-FCL 1.3.0, but it does not with the devel branch? Is this a newly-introduced bug in HPP-FCL, or is it just a backward-incompatible change? Is the identified execution path the one you would expect? What does oit mean? Regardless, I think it is not nice that undercertain circumstances one output of shapeDistance is left untouched

Documentation of Python bindings

I have tried the Python bindings, it seems to work well on my computer.
I did not try yet with Pinocchio, but I may give it a try next week.

In the meantime, I think it should be nice to provide the documentation with the main FCL geometries. @jmirabel Have you tried your script to automatize the documentation?

test & folder both named "benchmark"

Hi,

in the test dir, there is a benchmark cmake target and a benchmark folder, which leads to the following error in case we run cmake . in the main directory:

/usr/bin/ccache  g++   -pedantic -Wno-long-long -Wall -Wextra -Wcast-align -Wcast-qual -Wformat -Wwrite-strings -Wconversion    CMakeFiles/benchmark.dir/benchmark.cpp.o CMakeFiles/benchmark.dir/test_fcl_utility.cpp.o  -o benchmark  -L/opt/openrobots/lib -rdynamic ../src/libhpp-fcl.so -lboost_thread -lboost_date_time -lboost_filesystem -lboost_system -lboost_unit_test_framework -lboost_chrono -lboost_atomic -lpthread -lassimp -L/opt/openrobots/lib -loctomap -loctomath -Wl,-rpath,/local/users/gsaurel/humanoid-path-planner/hpp-fcl/src:/opt/openrobots/lib 
/usr/bin/ld : ne peut ouvrir le fichier de sortie benchmark : est un dossier
collect2: error: ld returned 1 exit status
test/CMakeFiles/benchmark.dir/build.make:132 : la recette pour la cible « test/benchmark » a échouée

Is one of those required for hpp_benchmark ?
Otherwise, I suggest to rename one or the other.

Namespace change

For external use of hpp-fcl, it might be a good idea to change the namespace.

Currently, an application which would load both libfcl.so and libhpp-fcl.so (even indirectly) will likely crash because of functions have the same prototype.

Supporting Windows

In order to allow the full support of Pinocchio on Windows system, I would like to make this package compliant with Windows too, knowing that EigenPy is already working on Windows.

The main requested feature required is the export of all the functions and classes located in the shared library. This is not very complicated to do, so I was wondering who is willing to handle this task?

Moving to `std::shared_ptr`

Hi,

The HPP framework is now using C++11, and is therefore going move to std::shared_ptr instead of boostones.

Keeping boost::shared_ptr in hpp-fcl would be a pain, and this might not be totally necessary.

I suggest to move hpp-fcl to C++11 and std::shared_ptr, and to release a new major version for this change.

For pinocchio, and other third-parties that rely on hpp-fcl, this might lead to something like:
https://github.com/stack-of-tasks/pinocchio/blob/master/src/CMakeLists.txt#L51-L54

Obviously, I can handle this work, and the related updates in the HPP, SoT, loco-3d & gepetto projects, but is there any objection for this ?

My main motivation is that the current version of hpp-pinocchio is not compatible with pinocchio v2.6.0, so I can't publish pinocchio v2.6.0 on robotpkg until a new HPP release is done, and the switch to std::shared_ptr is already on-going on this new HPP release.

Test mesh loader

I encountered some issues with current version of HPP-FCL with assimp on robotpkg because for some ASSIMP version, C_Str for aiString are missing.
I suggest to add missing unit tests concerning mesh loading.

Invalid distance_lower_bound

For simple geometries, like Box and Sphere collision pairs, the distance_lower_bound is not updated even when there is a contact.

Collision with volume / closed-shape object

Hello,
I know that this is old news and we already talked about but it was never solved and became relevant again in some of my new use cases.

FCL do not have any notion of "volume" or closed-shape object, it only test collision between the surfaces of the pair of object. If one of the object in entirely inside the other, it doesn't detect the collision.

Is there any ongoing development to change this ?

Manager and self-collision check

Hi!

I did some test with hpp::fcl::collide and seems it performs better than my current library. Additionally, I need support for PointCloud and a safety margin.

So now, as the base fcl has a BroadPhaseManagers, I would ask if here I can find any support to check collision for multiple objects? - As I understand it should be not a big deal for me to adapt it to fcl::BroadPhaseManagers, cuz anyway improvements and safety margin are in hpp::fcl::collide?

Depending on an answer to the previous question, I have also something like AllowedCollisionMatrix or Collision Pairs, between which I either want or not to check the collision. So in fcl I would do this with Callbacks and UserData. What about the hpp::fcl ?

The fact of a manager, I guess is the least invasive way for me to use the library right now.
Of course, I can do a vector of objects and check one against another, but the question is if there is any other way to check collision for multiple objects and self-collision.

Do you have any sample code? - in the test folder I only see the very old ones.

I consider both discrete and continuous collision checking.

BVH construction

At the moment, the BVH is built using a top-down method. Bottom-up methods are generally harder to implement but generate better BVH, resulting in cheaper collision test. We may want to implement the agglomerative clustering algorithm from this article

GKJ abort

I encountered the following abort:

The GJK inputs are:

  • Triangle 1 at
  a = Eigen::Matrix<double,3,1,ColMajor> (data ptr: 0x7ffff13e0f38) = {
    [0] = 0.063996093749999997,
    [1] = -0.15320971679687501,
    [2] = -0.42799999999999999
  }, 
  b = Eigen::Matrix<double,3,1,ColMajor> (data ptr: 0x7ffff13e0f50) = {
    [0] = 0.069105957031249998,
    [1] = -0.150722900390625,
    [2] = -0.42999999999999999
  }, 
  c = Eigen::Matrix<double,3,1,ColMajor> (data ptr: 0x7ffff13e0f68) = {
    [0] = 0.063996093749999997,
    [1] = -0.15320971679687501,
    [2] = -0.42999999999999999
  }

at

  T = Eigen::Matrix<double,3,1,ColMajor> (data ptr: 0x7ffff13e20e8) = {
    [0] = -12.824601270753471,
    [1] = -1.6840516940066426,
    [2] = 3.8914453043793844
  }, 
  q = Eigen::Quaternion<double> (data ptr: 0x7ffff13e2100) = {
    [x] = -0.26862477561450587,
    [y] = -0.46249645019513175,
    [z] = 0.73064726592483387,
    [w] = -0.42437287410898855
  }
  • Triangle 2:
  a = Eigen::Matrix<double,3,1,ColMajor> (data ptr: 0x7ffff13e0ff8) = {
    [0] = -25.655000000000001,
    [1] = -1.2858199462890625,
    [2] = 3.7249809570312502
  }, 
  b = Eigen::Matrix<double,3,1,ColMajor> (data ptr: 0x7ffff13e1010) = {
    [0] = -10.926,
    [1] = -1.284259033203125,
    [2] = 3.7281499023437501
  }, 
  c = Eigen::Matrix<double,3,1,ColMajor> (data ptr: 0x7ffff13e1028) = {
    [0] = -10.926,
    [1] = -1.2866180419921875,
    [2] = 3.72335400390625
  }

at

  T = Eigen::Matrix<double,3,1,ColMajor> (data ptr: 0x7ffff13e2198) = {
    [0] = 0,
    [1] = 0,
    [2] = 0
  }, 
  q = Eigen::Quaternion<double> (data ptr: 0x7ffff13e21b0) = {
    [x] = 0,
    [y] = 0,
    [z] = 0,
    [w] = 1
  }

Package not distributed with qhull on robotpkg

Hi,

I just noticed that hpp-fcl is not distributed with qhull on robotpkg apt-repository, at least for the latest release available. Is it intended ? Personnally, I rely on qhull for computing convex hulls and it would be helpful to get it directly without building hpp-fcl from source.

Best regards,
Alexis Duburcq

Installation make error

Hi there,

There is an error during the installation process after a successful cmake .. . My OS is Ubunbu 14.04 and the output of the cmake is

shihao@shihao-OptiPlex-7040:~/hpp-fcl/build$ cmake ..
-- The C compiler identification is GNU 4.8.4
-- The CXX compiler identification is GNU 4.8.4
-- Check for working C compiler: /usr/bin/cc
-- Check for working C compiler: /usr/bin/cc -- works
-- Detecting C compiler ABI info
-- Detecting C compiler ABI info - done
-- Check for working CXX compiler: /usr/bin/c++
-- Check for working CXX compiler: /usr/bin/c++ -- works
-- Detecting CXX compiler ABI info
-- Detecting CXX compiler ABI info - done
-- Found PkgConfig: /usr/bin/pkg-config (found version "0.26") 
-- Performing Test R-pedantic
-- Performing Test R-pedantic - Success
-- Performing Test R-Wno-long-long
-- Performing Test R-Wno-long-long - Success
-- Performing Test R-Wall
-- Performing Test R-Wall - Success
-- Performing Test R-Wextra
-- Performing Test R-Wextra - Success
-- Performing Test R-Wcast-align
-- Performing Test R-Wcast-align - Success
-- Performing Test R-Wcast-qual
-- Performing Test R-Wcast-qual - Success
-- Performing Test R-Wformat
-- Performing Test R-Wformat - Success
-- Performing Test R-Wwrite-strings
-- Performing Test R-Wwrite-strings - Success
-- Performing Test R-Wconversion
-- Performing Test R-Wconversion - Success
-- Found Doxygen: /usr/bin/doxygen (found version "1.8.6") 
-- eigen3 >= 3.0.0 is required.
-- checking for module 'eigen3 >= 3.0.0'
--   found eigen3 , version 3.2.0
-- Pkg-config module eigen3 v3.2.0 has been detected with success.
-- Boost version: 1.54.0
-- Boost version: 1.54.0
-- Found the following Boost libraries:
--   thread
--   date_time
--   filesystem
--   system
--   unit_test_framework
-- octomap >= 1.6 is optional.
-- checking for module 'octomap >= 1.6'
--   found octomap , version 1.9.0
-- Pkg-config module octomap v1.9.0 has been detected with success.
-- FCL uses Octomap
-- assimp >= 2.0 is required.
-- checking for module 'assimp >= 2.0'
--   found assimp , version 3.0.1264
-- Pkg-config module assimp v3.0.1264 has been detected with success.
-- Assimp version has unified headers
-- Failed to find latex/dvips/gs, will use MathJax backend.
-- Doxygen rendering: using MathJax backend
-- Configuring done
-- Generating done
-- Build files have been written to: /home/shihao/hpp-fcl/build

After I type the make -j8 to proceed the installation, two errors have been reported.
1.

/usr/include/eigen3/Eigen/src/Core/../plugins/MatrixCwiseBinaryOps.h:110:72: error: could not convert ‘Eigen::MatrixBase<Derived>::cwiseMax(const Eigen::MatrixBase<OtherDerived>&) const [with OtherDerived = Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 3, 1> >; Derived = Eigen::CwiseBinaryOp<Eigen::internal::scalar_difference_op<double>, const Eigen::Matrix<double, 3, 1>, const Eigen::Matrix<double, 3, 1> >; typename Eigen::internal::traits<T>::Scalar = double]((*(const Eigen::MatrixBase<Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 3, 1> > >*)(& Eigen::DenseBase<Derived>::Constant(Eigen::DenseBase<Derived>::Index, Eigen::DenseBase<Derived>::Index, const Scalar&) [with Derived = Eigen::Matrix<double, 3, 1>; Eigen::DenseBase<Derived>::ConstantReturnType = Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 3, 1> >; typename Eigen::internal::traits<T>::Scalar = double; Eigen::DenseBase<Derived>::Index = long int; Eigen::DenseBase<Derived>::Scalar = double](((const Eigen::EigenBase<Eigen::CwiseBinaryOp<Eigen::internal::scalar_difference_op<double>, const Eigen::Matrix<double, 3, 1>, const Eigen::Matrix<double, 3, 1> > >*)this)->Eigen::EigenBase<Derived>::cols<Eigen::CwiseBinaryOp<Eigen::internal::scalar_difference_op<double>, const Eigen::Matrix<double, 3, 1>, const Eigen::Matrix<double, 3, 1> > >(), (* & other)))))’ from ‘const Eigen::CwiseBinaryOp<Eigen::internal::scalar_max_op<double>, const Eigen::CwiseBinaryOp<Eigen::internal::scalar_difference_op<double>, const Eigen::Matrix<double, 3, 1>, const Eigen::Matrix<double, 3, 1> >, const Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 3, 1> > >’ to ‘const Eigen::CwiseBinaryOp<Eigen::internal::scalar_max_op<double>, const Eigen::CwiseBinaryOp<Eigen::internal::scalar_difference_op<double>, const Eigen::Matrix<double, 3, 1>, const Eigen::Matrix<double, 3, 1> >, const Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::CwiseBinaryOp<Eigen::internal::scalar_difference_op<double>, const Eigen::Matrix<double, 3, 1>, const Eigen::Matrix<double, 3, 1> > > >’
/home/shihao/hpp-fcl/src/distance_sphere_sphere.cpp:75:58: error: operands to ?: have different types ‘const Eigen::CwiseUnaryOp<Eigen::internal::scalar_quotient1_op<double>, const Eigen::Matrix<double, 3, 1> >’ and ‘fcl::Vec3f {aka Eigen::Matrix<double, 3, 1>}’
     Vec3f unit (dist > epsilon ? c1c2/dist : Vec3f (0,0,0));
                                                          ^
/home/shihao/hpp-fcl/src/distance_sphere_sphere.cpp: In function ‘std::size_t fcl::ShapeShapeCollide(const fcl::CollisionGeometry*, const fcl::Transform3f&, const fcl::CollisionGeometry*, const fcl::Transform3f&, const NarrowPhaseSolver*, const fcl::CollisionRequest&, fcl::CollisionResult&) [with T_SH1 = fcl::Sphere; T_SH2 = fcl::Sphere; NarrowPhaseSolver = fcl::GJKSolver_indep; std::size_t = long unsigned int]’:
/home/shihao/hpp-fcl/src/distance_sphere_sphere.cpp:115:58: error: operands to ?: have different types ‘const Eigen::CwiseUnaryOp<Eigen::internal::scalar_quotient1_op<double>, const Eigen::Matrix<double, 3, 1> >’ and ‘fcl::Vec3f {aka Eigen::Matrix<double, 3, 1>}’
     Vec3f unit (dist > epsilon ? c1c2/dist : Vec3f (0,0,0));

It seems to me that the error results from the Eigen3 library but I am not quite sure about what I should do with this problem. Can you help me with it?

Confusing tag v4.4.0-rc

Hi all,
while downloading and building from source, in search for the latest stable release, I noticed a very confusing tag v4.4.0-rc: https://github.com/humanoid-path-planner/hpp-fcl/tree/v4.4.0-rc.

What makes it confusing is that it the latest release is 1.3.0, and also v4.4.0-rc seems to be very old, from 26/02/2019. It was probably a mistake.

Should it be deleted? I am not sure whether I have access rights to do it, and even if I did I do not dare to delete it before being 100% sure it is the right thing to do.

[refactoring] Bindings do not work on Mac

The hppfcl module does not show up on my Mac after installation.
I use a fairly old OS (10.11, El Capitan), but it will likely be the same on newer versions, as far as I understand.
Apparently, there is a problem with the .dylib extension. It should be .so, even for Mac.

I followed this post:
https://stackoverflow.com/questions/2488016/how-to-make-python-load-dylib-on-osx

For me, it was enough to do mv hppfcl.dylib hppfcl.so inside lib/python2.7/site-packages and the problem was solved. This should be handled in the CMakeLists.txt

Few unittests fails with `-march=native`

This is the list of unittest that are failing:

The following tests FAILED:
	  2 - collision (Failed)
	  3 - distance (Failed)
	  4 - distance_lower_bound (Failed)
	  5 - geometric_shapes (Failed)
	  6 - frontlist (Failed)
	 14 - bvh_models (Failed)
	 15 - profiling (SEGFAULT)
	 17 - octree (Failed)

Is this library supporting data alignment?

C++17 vs register keyword

hpp-fcl currently does not build in workspaces that are set to use CMAKE_CXX_STANDARD=17 since the register keyword is no longer supported. It is e.g. used here:

register FCL_REAL t, s;

To fix it, we could either (a) fix the code or (b) check that if a standard >14 is requested raise a CMake warning and force a maximum of C++14 for the project.

What are your thoughts on removing the register keyword? Would you consider a PR for that?

Compilation error on distance_sphere_sphere.cpp

For some reason, on my ubuntu 16.04 compiler, the code does not compile here

Vec3f unit (dist > epsilon ? c1c2/dist : Vec3f (0,0,0));

I get the follwing error:
operands to ?: have different types ‘const Eigen::CwiseUnaryOp<Eigen::internal::scalar_quotient1_op, const Eigen::Matrix<double, 3, 1> >’ and ‘fcl::Vec3f {aka Eigen::Matrix<double, 3, 1>}’
Vec3f unit (dist > epsilon ? c1c2/dist : Vec3f (0,0,0));

I understand that normalized is not called to avoid computing the norm twice, still I wonder whether just calling the eigen method would not simplify the code (and selfishly answer my compilation issue).

I propose this modification here, let me know if you disagree, in which case we need to extend the code by computing the quotient outside of the ? operator

stonneau@0fd383e

Provide operator == to class CollisionResult

In Pinocchio, i need to perform the comparison operation between two fcl::CollisionResult Objects.

As this struct contains vector of Contact and vector of CostSource, the naive approach consisting of thinking default operators will be defined doesn't work ( I get compiling errors stating that the operator == is invalind between two const fcl::CollisionResult ).
Two ways are then possible :
1/ Perform in Pinocchio in a raw way this comparison, iterating through vectors etc
2/ Provide such operator in fcl::CollisionResult, thus also in Contact and CostSource

Area of contact between 2 meshes

Goal: Quantify the area between meshes in contact

Hopefully your expert opinion can provide some insight on how this can be achieved using this library.
If 2 meshes are in contact, is there a simple way to compute the contact area?

Intersection volume of 2 meshes

Goal: retrieve the intersection volume of 2 meshes if collisionResult.isCollision() returns true.

I have found the boolean capacity of whether meshes are colliding and also the computeDistances function where the distance between the 2 closest points can be queried.

Is there also provided api for the intersection volume or some way of quantifying the magnitude of 2 meshes intersecting?

I've found that the computeDistances function will always return a negative value close to 0 when 2 meshes partially intersect. This makes sense as the distance is only between the closest vertices on the meshes.

Impossible to compute collision between convex and halfspace

  • Trying to compute the collision between a convex geometry and an halfspace primitive through an exception
  • The normal of the contact between a convex geometry and a box is always the one of the box, never the one of the convex geometry, no matter of their order in the collision pair. I'm not sure if it is intended and how to get the normal wrt the convex geometry.

NB: In Python, trying to access o1 from a CollisionResult raises an exception on my setup:
No to_python (by-value) converter found for C++ type: hpp::fcl::CollisionGeometry const*

Add testing of Python bindings

To enforce coverage of this package, it would be nice to also test the Python bindings. Unfortunately I don’t have time to do it. @nim65s Would you be available to do this task?

huge test resources

Hi,

test/fcl_resources is 55.4 Mo.
Are these files really required ?

If so, tar --zstd -cvf fcl_resources.tar.zst fcl_resources/ is 6.9 Mo, and would reduce the release tarball from 11Mo to 7.5Mo, so maybe we should consider compressing those.

(we could also decide to use zstd for our release tarballs instead of gz, but it will not be compatible with older systems)

Octomap version is not handled internally

To cope with the change of API in octomap 1.8 with respect to previous version,

a routine OCTOMAP_VERSION_AT_LEAST has been implemented ( http://cpc.cx/mCk )
However this routine uses variables defined in the CMakeLists.txt (http://cpc.cx/mCl),
and thus not defined in depending subprojects.

I suggest putting the implementation of the methods using OCTOMAP_VERSION_AT_LEAST in corresponding cpp files to hide their use

Method impossible to call from Python

Hi,

AFAIK, CollisionObject is not exposed in Python, so it is impossible to call this method:

doxygen::def ("distance", static_cast< FCL_REAL (*)(const CollisionObject*, const CollisionObject*,

If I'm right, I suggest either to expose CollisionObject or to remove it ? The same goes for collisions.

Best

GJK::evaluate does not converge

Since commits 0f95151 and aadec3c, method GJK::evaluate in src/narrowphase/gjk.cpp sometimes fails to converge to a solution (status = Valid of status = Inside) and reaches the maximal number if iterations. Since commit 9c98029, if the method returns "Failed" and the distance between object is small enough, GJKSolver_indep::shapeDistance returns collision with pentration distance equal to 0.

https://github.com/florent-lamiraux/hpp-fcl/blob/7c65d1ef1a369b4b80d598cfd1a837f96d948efc/test/test_fcl_geometric_shapes.cpp#L253 provides a test where a cylinder is in collision with a box and the method does not converge.

Flag not found on Mac

I installed Pinocchio on Mac. When I try to import Pinocchio in the python2, I met the following error:

ImportError: dlopen(/usr/local/lib/python2.7/site-packages/pinocchio/libpinocchio_pywrap.so, 2): Symbol not found: __ZN5boost6system16generic_categoryEv
Referenced from: /usr/local/lib/libhpp-fcl.dylib
Expected in: /usr/local/opt/boost/lib/libboost_system-mt.dylib
in /usr/local/lib/libhpp-fcl.dylib

I guess this is caused by the library of hpp-fcl or the boost, though I have tried many times to install these two packages with latest home-brew. Can you help me out?

Python bindings issue

The unit test added by commit 394ecbb does not pass. The error is:

Traceback (most recent call last):
  File "hpp-fcl/test/python_unit/api.py", line 17, in test_collision
    self.assertTrue(not hppfcl.collide(capsule, M1, capsule, M2, req, res))
Boost.Python.ArgumentError: Python argument types in
    hppfcl.hppfcl.collide(Capsule, Transform3f, Capsule, Transform3f, CollisionRequest, CollisionResult)
did not match C++ signature:
    collide(hpp::fcl::CollisionGeometry const*, hpp::fcl::Transform3f, hpp::fcl::CollisionGeometry const*, hpp::fcl::Transform3f, hpp::fcl::CollisionRequest, hpp::fcl::CollisionResult {lvalue})
    collide(hpp::fcl::CollisionObject const*, hpp::fcl::CollisionObject const*, hpp::fcl::CollisionRequest, hpp::fcl::CollisionResult {lvalue})

I do not understand the issue. Function distance has almost the same prototype and has no issue...

additional constructor for collisionrequest is a bad idea

6732f69

Because of the default parameter signature in the other constructor, and
because bool and size_t can be used indifferently, the constructor called is undefined
depending on the parameters given. As a matter of fact, the constructor called
in CollisionValidation is not the one you think. This leads to a bug where max_num_contacts parameter
is in fact set to 0. I am creating a pull request to fix this in hpp-core, but the ambiguity should be removed

Build failure when building doxygen

I am building the latest devel of hpp-fcl and get the following error:

Traceback (most recent call last):
  File "/home/wxm/dev/install_ws/src/hpp-fcl/doc/python/doxygen_xml_parser.py", line 688, in <module>
    output = OutputStreams (args.output_directory, sys.stdout, sys.stderr))
  File "/home/wxm/dev/install_ws/src/hpp-fcl/doc/python/doxygen_xml_parser.py", line 531, in __init__
    self.tree = etree.parse (input)
  File "src/lxml/etree.pyx", line 3519, in lxml.etree.parse
  File "src/lxml/parser.pxi", line 1839, in lxml.etree._parseDocument
  File "src/lxml/parser.pxi", line 1865, in lxml.etree._parseDocumentFromURL
  File "src/lxml/parser.pxi", line 1769, in lxml.etree._parseDocFromFile
  File "src/lxml/parser.pxi", line 1163, in lxml.etree._BaseParser._parseDocFromFile
  File "src/lxml/parser.pxi", line 601, in lxml.etree._ParserContext._handleParseResultDoc
  File "src/lxml/parser.pxi", line 711, in lxml.etree._handleParseResult
  File "src/lxml/parser.pxi", line 638, in lxml.etree._raiseParseError
IOError: Error reading file '/home/wxm/dev/install_ws/build/hpp-fcl/doc/doxygen-xml/index.xml': failed to load external entity "/home/wxm/dev/install_ws/build/hpp-fcl/doc/doxygen-xml/index.xml"
make[2]: *** [python/CMakeFiles/generate_doxygen_cpp_doc] Error 1
make[1]: *** [python/CMakeFiles/generate_doxygen_cpp_doc.dir/all] Error 2
make: *** [all] Error 2

The system is Ubuntu 18.04. Have you seen this before?

/home/wxm/dev/install_ws/build/hpp-fcl/doc/doxygen-xml/index.xml does not exist

Double FCL_HAVE_OCTOMAP

Small question: is normal to have both FCL_HAVE_OCTOMAPand HPP_FCL_HAVE_OCTOMAP?

"-DHPP_FCL_HAVE_OCTOMAP -DFCL_HAVE_OCTOMAP -DOCTOMAP_MAJOR_VERSION=${OCTOMAP_MAJOR_VERSION} -DOCTOMAP_MINOR_VERSION=${OCTOMAP_MINOR_VERSION} -DOCTOMAP_PATCH_VERSION=${OCTOMAP_PATCH_VERSION}")

Documentation generation issues in Python 3

Hi,

On my computer, in python 3, headers inbuild/python/doxygen_autodoc/ are filled with ill-generated strings, eg.:


inline const char* member_func_doc ( hpp::fcl::ConvexBase * (*function_ptr) (const hpp::fcl::Vec3f *, int, bool, const char *))
{
  if (function_ptr == static_cast< hpp::fcl::ConvexBase * (*) (const hpp::fcl::Vec3f *, int, bool, const char *)>(&hpp::fcl::ConvexBase::convexHull))
    return "b'Build a convex hull based on Qhull library and store the vertices and optionally the triangles. \\n"\n"\\n"\n"\\n"\n"Param\\n"\n"  - points, num_points the points whose convex hull should be computed. \\n"\n"  - keepTriangles if true, returns a Convex<Triangle> object which contains the triangle of the shape. \\n"\n"  - qhullCommand the command sent to qhull.\\n"\n"- if keepTriangles is true, this parameter should include \\"Qt\\". If NULL, \\"Qt\\" is passed to Qhull.\\n"\n"- if keepTriangles is false, an empty string is passed to Qhull. \\n"\n"\\n"\n"\\n"\n"\\n"\n"Note: hpp-fcl must have been compiled with option HPP_FCL_HAS_QHULL set to ON. '";
  return "";
}

(please note the \\n"\n"\\n"\n"\\n"\n"\\n"\n" chains, which are generating compilation errors)
In python 2, the generated files look good.

This commit fix the build for me in python 3 while not breaking python 2: nim65s@86e0391

The CI looks good: https://gitlab.laas.fr/humanoid-path-planner/hpp-fcl/pipelines/9761
But I suspect that this is because the CI doesn't have lxml, so this is generation is turned off in the CMake.

What should we do about that ? Apply this commit ? (I need to redo it without my autoformatting changes) Maybe this .decode() should be apply before, and we shouldn't have had those bytes strings in the first place ?

For me, this is blocking the next release.

Issue with CwiseBinaryOp on 14.04

#45 raised the following error on 14.04, with gcc:

[ 16%] Building CXX object src/CMakeFiles/hpp-fcl.dir/shape/geometric_shapes.cpp.o
cd /home/travis/build/nim65s/hpp-fcl/build/src && /usr/bin/g++  -DFCL_HAVE_OCTOMAP -DFCL_USE_ASSIMP_UNIFIED_HEADER_NAMES -DOCTOMAP_MAJOR_VERSION=1 -DOCTOMAP_MINOR_VERSION=8 -DOCTOMAP_PATCH_VERSION=0 -Dhpp_fcl_EXPORTS -I/home/travis/build/nim65s/hpp-fcl/build -I/home/travis/build/nim65s/hpp-fcl/build/include -I/home/travis/build/nim65s/hpp-fcl/include -I/usr/include/eigen3 -isystem /usr/local/include -isystem /usr/include/assimp  -pedantic -Wno-long-long -Wall -Wextra -Wcast-align -Wcast-qual -Wformat -Wwrite-strings -Wconversion -w -g -fPIC   -o CMakeFiles/hpp-fcl.dir/shape/geometric_shapes.cpp.o -c /home/travis/build/nim65s/hpp-fcl/src/shape/geometric_shapes.cpp
In file included from /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:139:0,
                 from /usr/include/eigen3/Eigen/Core:279,
                 from /home/travis/build/nim65s/hpp-fcl/include/hpp/fcl/math/vec_3f.h:43,
                 from /home/travis/build/nim65s/hpp-fcl/include/hpp/fcl/BV/OBB.h:42,
                 from /home/travis/build/nim65s/hpp-fcl/src/BV/OBB.cpp:38:
/usr/include/eigen3/Eigen/src/Core/../plugins/MatrixCwiseBinaryOps.h: In instantiation of ‘const Eigen::CwiseBinaryOp<Eigen::internal::scalar_max_op<typename Eigen::internal::traits<T>::Scalar>, const Derived, const Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<typename Eigen::internal::traits<T>::Scalar>, Derived> > Eigen::MatrixBase<Derived>::cwiseMax(const Scalar&) const [with Derived = Eigen::CwiseBinaryOp<Eigen::internal::scalar_difference_op<double>, const Eigen::Matrix<double, 3, 1>, const Eigen::Matrix<double, 3, 1> >; typename Eigen::internal::traits<T>::Scalar = double; Eigen::MatrixBase<Derived>::Scalar = double]’:
/home/travis/build/nim65s/hpp-fcl/src/BV/OBB.cpp:317:60:   required from here
/usr/include/eigen3/Eigen/src/Core/../plugins/MatrixCwiseBinaryOps.h:110:72: error: could not convert ‘Eigen::MatrixBase<Derived>::cwiseMax(const Eigen::MatrixBase<OtherDerived>&) const [with OtherDerived = Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 3, 1> >; Derived = Eigen::CwiseBinaryOp<Eigen::internal::scalar_difference_op<double>, const Eigen::Matrix<double, 3, 1>, const Eigen::Matrix<double, 3, 1> >; typename Eigen::internal::traits<T>::Scalar = double]((*(const Eigen::MatrixBase<Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 3, 1> > >*)(& Eigen::DenseBase<Derived>::Constant(Eigen::DenseBase<Derived>::Index, Eigen::DenseBase<Derived>::Index, const Scalar&) [with Derived = Eigen::Matrix<double, 3, 1>; Eigen::DenseBase<Derived>::ConstantReturnType = Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 3, 1> >; typename Eigen::internal::traits<T>::Scalar = double; Eigen::DenseBase<Derived>::Index = long int; Eigen::DenseBase<Derived>::Scalar = double](((const Eigen::EigenBase<Eigen::CwiseBinaryOp<Eigen::internal::scalar_difference_op<double>, const Eigen::Matrix<double, 3, 1>, const Eigen::Matrix<double, 3, 1> > >*)this)->Eigen::EigenBase<Derived>::cols<Eigen::CwiseBinaryOp<Eigen::internal::scalar_difference_op<double>, const Eigen::Matrix<double, 3, 1>, const Eigen::Matrix<double, 3, 1> > >(), (* & other)))))’ from ‘const Eigen::CwiseBinaryOp<Eigen::internal::scalar_max_op<double>, const Eigen::CwiseBinaryOp<Eigen::internal::scalar_difference_op<double>, const Eigen::Matrix<double, 3, 1>, const Eigen::Matrix<double, 3, 1> >, const Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::Matrix<double, 3, 1> > >’ to ‘const Eigen::CwiseBinaryOp<Eigen::internal::scalar_max_op<double>, const Eigen::CwiseBinaryOp<Eigen::internal::scalar_difference_op<double>, const Eigen::Matrix<double, 3, 1>, const Eigen::Matrix<double, 3, 1> >, const Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>, Eigen::CwiseBinaryOp<Eigen::internal::scalar_difference_op<double>, const Eigen::Matrix<double, 3, 1>, const Eigen::Matrix<double, 3, 1> > > >’
   return cwiseMax(Derived::PlainObject::Constant(rows(), cols(), other));

and clang:

[ 16%] Building CXX object src/CMakeFiles/hpp-fcl.dir/shape/geometric_shapes.cpp.o
cd /home/travis/build/nim65s/hpp-fcl/build/src && /usr/local/clang-5.0.0/bin/clang++  -DFCL_HAVE_OCTOMAP -DFCL_USE_ASSIMP_UNIFIED_HEADER_NAMES -DOCTOMAP_MAJOR_VERSION=1 -DOCTOMAP_MINOR_VERSION=8 -DOCTOMAP_PATCH_VERSION=0 -Dhpp_fcl_EXPORTS -I/home/travis/build/nim65s/hpp-fcl/build -I/home/travis/build/nim65s/hpp-fcl/build/include -I/home/travis/build/nim65s/hpp-fcl/include -I/usr/include/eigen3 -isystem /usr/local/include -isystem /usr/include/assimp  -pedantic -Wno-long-long -Wall -Wextra -Wcast-align -Wcast-qual -Wformat -Wwrite-strings -Wconversion -w -g -fPIC   -o CMakeFiles/hpp-fcl.dir/shape/geometric_shapes.cpp.o -c /home/travis/build/nim65s/hpp-fcl/src/shape/geometric_shapes.cpp
In file included from /home/travis/build/nim65s/hpp-fcl/src/BV/OBB.cpp:38:
In file included from /home/travis/build/nim65s/hpp-fcl/include/hpp/fcl/BV/OBB.h:42:
In file included from /home/travis/build/nim65s/hpp-fcl/include/hpp/fcl/math/vec_3f.h:43:
In file included from /usr/include/eigen3/Eigen/Core:279:
In file included from /usr/include/eigen3/Eigen/src/Core/MatrixBase.h:139:
/usr/include/eigen3/Eigen/src/Core/../plugins/MatrixCwiseBinaryOps.h:110:10: error: 
      no viable conversion from returned value of type 'const CwiseBinaryOp<[2 *
      ...], const CwiseNullaryOp<[...], Eigen::Matrix<double, 3, 1, 0, 3,
      1>>>' to function return type 'const CwiseBinaryOp<[2 * ...], const
      CwiseNullaryOp<[...],
      Eigen::CwiseBinaryOp<Eigen::internal::scalar_difference_op<double>, const
      Eigen::Matrix<double, 3, 1, 0, 3, 1>, const Eigen::Matrix<double, 3, 1, 0,
      3, 1> >>>'
  return cwiseMax(Derived::PlainObject::Constant(rows(), cols(), other));
         ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
/home/travis/build/nim65s/hpp-fcl/src/BV/OBB.cpp:317:49: note: in instantiation
      of member function
      'Eigen::MatrixBase<Eigen::CwiseBinaryOp<Eigen::internal::scalar_difference_op<double>,
      const Eigen::Matrix<double, 3, 1, 0, 3, 1>, const Eigen::Matrix<double, 3,
      1, 0, 3, 1> > >::cwiseMax' requested here
  squaredLowerBoundDistance = (AABB_corner - a).cwiseMax (0).squaredNorm ();
                                                ^
/usr/include/eigen3/Eigen/src/Core/util/ForwardDeclarations.h:89:65: note: 
      candidate constructor (the implicit copy constructor) not viable: no known
      conversion from 'const CwiseBinaryOp<internal::scalar_max_op<Scalar>,
      const Eigen::CwiseBinaryOp<Eigen::internal::scalar_difference_op<double>,
      const Eigen::Matrix<double, 3, 1, 0, 3, 1>, const Eigen::Matrix<double, 3,
      1, 0, 3, 1> >, const
      Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>,
      Eigen::Matrix<double, 3, 1, 0, 3, 1> > >' (aka 'const
      CwiseBinaryOp<scalar_max_op<double>, const
      Eigen::CwiseBinaryOp<Eigen::internal::scalar_difference_op<double>, const
      Eigen::Matrix<double, 3, 1, 0, 3, 1>, const Eigen::Matrix<double, 3, 1, 0,
      3, 1> >, const
      Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>,
      Eigen::Matrix<double, 3, 1, 0, 3, 1> > >') to 'const
      Eigen::CwiseBinaryOp<Eigen::internal::scalar_max_op<double>, const
      Eigen::CwiseBinaryOp<Eigen::internal::scalar_difference_op<double>, const
      Eigen::Matrix<double, 3, 1, 0, 3, 1>, const Eigen::Matrix<double, 3, 1, 0,
      3, 1> >, const
      Eigen::CwiseNullaryOp<Eigen::internal::scalar_constant_op<double>,
      Eigen::CwiseBinaryOp<Eigen::internal::scalar_difference_op<double>, const
      Eigen::Matrix<double, 3, 1, 0, 3, 1>, const Eigen::Matrix<double, 3, 1, 0,
      3, 1> > > > &' for 1st argument
template<typename BinaryOp,  typename Lhs, typename Rhs>  class CwiseBinaryOp;
                                                                ^

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    🖖 Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. 📊📈🎉

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google ❤️ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.