Fast algorithms to compute an approximation of the minimal volume oriented bounding box of a point cloud in 3D.

Overview

ApproxMVBB

C++ Deps System

Status

Build UnitTests
Build Status Build Status

Homepage


Fast algorithms to compute an approximation of the minimal volume oriented bounding box of a point cloud in 3D.

Computing the minimal volume oriented bounding box for a given point cloud in 3D is a hard problem in computer science. Exact algorithms are known and of cubic order in the number of points in 3D. A faster exact algorithm is currently not know. However, for lots of applications an approximation of the minimum volume oriented bounding box is acceptable and already accurate enough. This project was developed for research in Granular Rigidbody Dynamics. This small standard compliant C++11 library can either be built into a shared object library or directly be included in an existing C++ project.

I am not especially proud of the underlying code as it was written years ago, nevertheless consider PR for refactoring and clean ups are very welcome!

This library includes code for :

  • computing an approximation of an oriented minimal volume box (multithreading support: OpenMP),
  • computing the convex hull of a point cloud in 2d,
  • computing the minimal area rectangle of a 2d point cloud,
  • 2d projections of point clouds,
  • fast building a kD-Tree (n-dimensional, templated) with sophisticated splitting techniques which optimizes a quality criteria during the splitting process,
  • computing the k-nearest neighbors to a given point (kNN search) via kd-Tree.
  • fast statistical outlier filtering of point clouds via (nearest neighbor search, kD-Tree).


Installation & Dependencies

To build the library, the tests and the example you need the build tool cmake. This library has these light-weight required dependencies:

  • Eigen at least version 3.
    • With homebrew or linuxbrew: brew install eigen3
  • meta
    • Install optional: Gets downloaded and used during build.

and theses optional dependecies:

  • pugixml
    • With homebrew or linuxbrew: brew install pugixml
    • install with #define PUGIXML_HAS_LONG_LONG enabled in pugiconfig.hpp.
    • only needed if cmake variable ApproxMVBB_XML_SUPPORT=ON (default=OFF).
  • python3 only needed for visualization purposes.

Download these and install it on your system.

Download the latest ApproxMVBB code:

    git clone https://github.com/gabyx/ApproxMVBB.git ApproxMVBB

Make a build directory and navigate to it:

    mkdir Build
    cd Build

Invoke cmake in the Build directory:

    cmake ../ApproxMVBB

The cmake script tries to find Eigen,meta and pugixml If you installed these in a system wide folder (e.g /usr/local/) this should succeed without any problems. In the CMakeCache.txt file (or over the console by -D<variable>=ON) you can specify what you want to build, the following options are availabe:

  • ApproxMVBB_BUILD_LIBRARY,
  • ApproxMVBB_BUILD_TESTS
  • ApproxMVBB_BUILD_EXAMPLE
  • ApproxMVBB_BUILD_BENCHMARKS
  • etc. See the marked red options after configuring in cmake-gui.

To install the library and the header files at a specific location /usr/local/ run cmake with:

    cmake -DCMAKE_INSTALL_PREFIX="/usr/local/" ../ApproxMVBB

Finally, build and install the project:

    make all
    make install

By default the multithreading support is enabled if OpenMP is found! (see Multithreading Support) To build in parallel use the -jN flag in the make command, where Ndenotes the number of parallel threads to use, or use the Ninja Generator which already uses maximum threads your system offers.

CMake FindScripts The installation installs also scripts approxmvbb-config.cmake and approxmvbb-config-version.cmake into the lib/cmake folder. To include the library in another project the only thing you need to add in your cmake script is

    find_package(ApproxMVBB [version] [COMPONENTS [SUPPORT_KDTREE] [SUPPORT_XML] ] [Required] )

which defines the following targets if ApproxMVBB has been found successfully:

    ApproxMVBB::Core            # Main target to link with!
    ApproxMVBB::KdTreeSupport   # Optional target for KdTree support to link with (only available if installed with this supported!)
    ApproxMVBB::XMLSupport      # Optional target for XML support to link with (only available if installed with this supported!)

The components SUPPORT_KDTREE additionally loads the dependency meta for the KdTree.hpp header and SUPPORT_XML loads pugixml for the KdTreeXml.hpp header.

If you installed the library into non-system generic location you can set the cmake variable $ApproxMVBB_DIR before invoking the find_library command:

    set(ApproxMVBB_DIR "path/to/installation/lib/cmake")
    find_package(ApproxMVBB [version] [Required] )

See the example example/libraryUsage which should be configured as a separate build, and the example example/kdTreeFiltering for more information on how to set up the dependencies!


Supported Platforms

The code has been tested on Linux and OS X with compilers clang and gcc. It should work for Windows as well, but has not been tested properly. Under Visual Studio 15 it seems to build.


Example Usage: Approximation MVBB

Please see the example/approxMVBB/main.cpp in the source directory. Given a point cloud with n=10000 points sampled in the unit cube in 3D we compute an approximation of the minimum volume bounding volume by the following calls:

    #include <iostream>
    #include "ApproxMVBB/ComputeApproxMVBB.hpp"

    int  main(int argc, char** argv)
    {
          ApproxMVBB::Matrix3Dyn points(3,10000);
          points.setRandom();
          ApproxMVBB::OOBB oobb = ApproxMVBB::approximateMVBB(points,0.001,500,5,0,5);
          oobb.expandToMinExtentRelative(0.1);
          return 0;
    }

The returned object oriented bounding box oobb contains the lower oobb.m_minPoint and upper point oobb.m_maxPoint expressed in the coordinate frame K of the bounding box. The bounding box also stores the rotation matrix from the world frame to the object frame K as a quaternion oobb.m_q_KI . The rotation matrix R_KI from frame I to frame K can be obtained by oobb.m_q_KI.matrix() (see Eigen::Quaternion). This rotation matrix R_KI corresponds to a coordinate transformation A_IK which transforms coordinates from frame K to coordinates in frame I. Thereforce, to get the lower point expressed in the coordinate frame I this yields:

    ApproxMVBB::Vector3 p = oobb.m_q_KI * oobb.m_minPoint  // A_IK * oobb.m_minPoint

Degenerate OOBB: The returned bounding box might have a degenerated extent in some axis directions depending on the input points (e.g. 3 points defines a plane which is the minimal oriented bounding box with zero volume). The function oobb.expandToMinExtentRelative(0.1); is a post processing function to enlarge the bounding box by a certain percentage of the largest extent (if existing, otherwise a default value is used).

Points Outside of the final OOBB: Because the algorithm works internally with a sample of the point cloud, the resulting OOBB might not contain all points of the original point cloud! To compensate for this an additional loop is required:

    ApproxMVBB::Matrix33 A_KI = oobb.m_q_KI.matrix().transpose();
    auto size = points.cols();
    for( unsigned int i=0;  i<size; ++i ) {
        oobb.unite(A_KI*points.col(i));
    }

Function Parameters & How It Works: The most important function:

    ApproxMVBB::approximateMVBB(pts,
                                epsilon,
                                pointSamples,
                                gridSize,
                                mvbbDiamOptLoops,
                                mvbbGridSearchOptLoops)

computes an approximation of the minimal volume bounding box in the following steps:

  1. An approximation of the diameter (direction which realizes the diameter: z ) of the points pts is computed. The value epsilon is the absolute tolerance for the approximation of the diameter and has the same units as the points pts (in the example 0.001 meter)
  2. The points are projected into the plane perpendicular to the direction z
  3. An approximation of the diameter of the projected points in 2D is computed (direction x )
  4. The initial approximate bounding box A is computed in the orthogonal frame [x,y,z]
  5. A first optional optimization loop is performed (parameter mvbbDiamOptLoops specifies how many loops) by computing the minimal volume bounding box over a direction t where the direction t is choosen sequentially from the current optimal bounding box solution. The algorithm starts with the directions of the box A. This optimization works with all points in pts and might use a lot of time
  6. The initial bounding box A is used as a tight fit around the points pts to compute a representative sample RS of the point cloud. The value pointSamples defines how many points are used for the exhaustive grid search procedure in the next step
  7. An exhaustive grid search (value gridSize specifies the x,y,z dimension of the grid defined by the bounding box A) is performed. This search is a simple loop over all grid directions (see Gill Barequet, and Sariel Har-Peled [1]) to find a even smaller bounding box. For each grid direction g the minimal bounding box of the projected points in direction g is computed. This consists of finding the minimal rectangle (axis u and v in world frame) of the projected point cloud in the plane perpendicular to direction g. The minimal bounding box G in direction g can be computed from the basis (u,v,g) and is a candidate for the overall minimization problem. Each found bounding box candidate G and its directions (u,v,g) can be used as a starting point for a second optional optimization loop (parameter mvbbGridSearchOptLoops, same algorithm as in step 5 but with less points, namely RS ).
  8. The final approximation for the minimal volume bounding box (minimal volume over all computed candidates) is returned. 💩

Example Usage: Generating a KdTree and Outlier Filtering

The library includes a fast KdTree implementation (which is not claimed to be ultimativly fast and absolutely memory efficient, but was written to fulfill this aspects to a certain level, real benchmarks still need to be done, the implementation can really well compete with famous implementations such as PCL(FLANN),ANN, and CGAL ) The KdTree splitting heuristic implements an extendable sophisticated splitting optimization which in the most elaborate, performance worst case consists of searching for the best split between the splitting heuristics MIDPOINT , MEDIAN and GEOMETRIC_MEAN by evaluating a user-provided quality evaluator. The simple standard quality evaluator is the LinearQualityEvaluator which computes the split quality by a weighted linear combination of the quantities splitRatio , pointRatio, minMaxExtentRatio.

Outlier filtering is done with the k-nearest neighbor search algorithm (similar to the PCL library but faster, and with user defined precision) and works roughly as the following: The algorithm finds for each point p in the point cloud k nearest neighbors and averages their distance (distance functor) to the point p to obtain a mean distance distance for this particular point. All nearest mean distances for all points give a histogram with a sample mean mean and sample standard deviation stdDev. All points which have a mean nearest neighbor distance greater or equal to mean + stdDevMult * stdDev are classified as outlier points.

Look at the examples in examples/kdTreeFiltering which produced the following pictures with the provided visualization notebook examples/kdTreeFiltering/python/VisualizeKdTree.ipynb.

Function Parameters & How It Works To come


Building and Visualizing the Tests

Building and installing the basic tests is done by:

    cd ApproxMVBB
    git submodule init
    git submodule update
    cd ../Build
    make build_and_test

**Note that if the tests fail, submit a new issue and report which test failed. The results can still be visualized and should be correct. **

Note: To run the test in high-performance mode (needs lots of ram), which tests also points clouds of 140 million points and some polygonal statue lucy.txt successfully you need to set the cmake variable ApproxMVBB_TESTS_HIGH_PERFORMANCE to ON and additionally initialize the submodule additional and unzip the files:

     cd ApproxMVBB
     git submodule init
     git submodule update
     cd additional/tests/files; cat Lucy* | tar xz

and rebuild the tests. (this will copy the additional files next to the executable)

Executing the test application cd tests; ./ApproxMVBBTests will then run the following tests:

  1. Testing the ConvexHull2D for several point clouds in 2D
  2. Minimal area rectangle tests for several point clouds in 2D
  3. Testing the diameter computation and calculation of the initial bounding box A (see [section](Function Parameters & How It Works)) for point clouds in 3D
  4. Testing the full optimization pipeline to generate an approximation of the minimal volume bounding box

The output can be visualized with the ipython notebook /tests/python/PlotTestResults.ipynb:

    cd Build/tests
    ipython noteboook


Benchmark

Here are some short benchmarks (single core) from the tests folder:

Point Cloud # Points ~ CPU Time approximateMVBB
Standford Bunny 35'945 0.91 s
Standford Lucy 14'027'872 1.19 s
Unit Cube 140'000'000 7.0 s

approximateMVBB runs approximateMVBBDiam and performs a grid search afterwards (here 5x5x5=25 directions with 5 optimization runs for each) It seems to take a long time for 140 million points. The most inefficient task is to get a good initial bounding box. This takes the most time as diameter computations are performed in 3d and then all points are projected in the found diameter direction in 3d and another diameter in the projected plane in 2d is computed. Afterwards the point cloud is sampled (not just random points, its done with a grid) and convex hull, minimal rectangle computations are performed over the grid directions. These algorithms could be made faster by exploiting the following things:

  • Use an axis aligned bounding box as the initial bounding box for the grid search (not implemented yet)
  • Parallelism for the projection -> (CUDA, threads)

Multithreading Support

You can build the library with OpenMP (by default enabled) You can set the cmake cache variables ApproxMVBB_OPENMP_USE_OPENMP=On which will further enable ApproxMVBB_OPENMP_USE_NTHREADS=On/Off. The variable ApproxMVBB_OPENMP_USE_NTHREADS toogles the number of threads to use. If Off, the number of threads is determined at runtime (default).

If you use clang, make sure you have the OpenMP enabled clang! GCC already supports OpenMP.


References

The main articles this code is based on:

@Article{malandain2002,
Author = {Gr'egoire Malandain and Jean-Daniel Boissonnat},
Journal = {International Journal of Computational Geometry & Applications},
Month = {December},
Number = {6},
Pages = {489 - 510},
Timestamp = {2015.09.02},
Title = {Computing the Diameter of a Point Set},
Volume = {12},
Year = {2002}}

and

@inproceedings{barequet2001,
Author = {Gill Barequet and Sariel Har-peled},
Booktitle = {In Proc. 10th ACM-SIAM Sympos. Discrete Algorithms},
Pages = {38--91},
Timestamp = {2015.09.02},
Title = {Efficiently Approximating the Minimum-Volume Bounding Box of a Point Set in Three Dimensions},
Year = {2001}}

Optimizations for future work:

@Article{chang2011,
Acmid = {2019641},
Address = {New York, NY, USA},
Articleno = {122},
Author = {Chang, Chia-Tche and Gorissen, Bastien and Melchior, Samuel},
Doi = {10.1145/2019627.2019641},
Issn = {0730-0301},
Issue_Date = {October 2011},
Journal = {ACM Trans. Graph.},
Keywords = {Computational geometry, bounding box, manifolds, optimization},
Month = oct,
Number = {5},
Numpages = {16},
Pages = {122:1--122:16},
Publisher = {ACM},
Timestamp = {2015.09.03},
Title = {Fast Oriented Bounding Box Optimization on the Rotation Group {$SO(3,\mathbb{R})$}},
Url = {http://doi.acm.org/10.1145/2019627.2019641},
Volume = {30},
Year = {2011},
Bdsk-Url-1 = {http://doi.acm.org/10.1145/2019627.2019641},
Bdsk-Url-2 = {http://dx.doi.org/10.1145/2019627.2019641}}

Licensing

This source code is released under MPL 2.0.


Author and Acknowledgements

ApproxMVBB was written by Gabriel Nützi, with source code from Grégoire Malandain & Jean-Daniel Boissonnat for the approximation of the diameter of a point cloud. I was inspired by the work and algorithms of Gill Barequet & Sariel Har-Peled for computing a minimal volume bounding box. Additionally, the geometric predicates (orient2d) used in the convex hull algorithm (graham scan) have been taken from the fine work of Jonathan Richard Shewchuk. Special thanks go to my significant other which always had an ear during breakfast for this little project 😘

Comments
  • Unable to build under Windows

    Unable to build under Windows

    Unfortunately, I am unable to build the library under Windows 10 using Visual Studio 2013 (for x64). CMake runs fine: I manually specified the path to eigen and I have manually compiled pugixml and have specified its library file and include directory. I've never used meta and I have no idea what it does. But I suspect meta is the culprit here. I can see that sine meta is not detected on my machine, the build script would use git to clone the latest version and then halts!

    Here's what VS2013 output gives me:

    1>------ Build started: Project: ZERO_CHECK, Configuration: Debug x64 ------
    2>------ Build started: Project: ApproxMVBB_PredInitGenInternal, Configuration: Debug x64 ------
    3>------ Build started: Project: meta, Configuration: Debug x64 ------
    2>cl : Command line warning D9002: ignoring unknown option '/EH;'
    2>cl : Command line warning D9002: ignoring unknown option '/EH/'
    2>cl : Command line warning D9002: ignoring unknown option '/EHM'
    2>cl : Command line warning D9002: ignoring unknown option '/EHP'
    2>  PredicatesInit.cpp
    2>C:\Users\magho_000\Desktop\ApproxMVBB\external\GeometryPredicates\src\PredicatesInit.cpp(70): warning C4996: 'fopen': This function or variable may be unsafe. Consider using fopen_s instead. To disable deprecation, use _CRT_SECURE_NO_WARNINGS. See online help for details.
    2>          C:\Program Files (x86)\Microsoft Visual Studio 12.0\VC\include\stdio.h(211) : see declaration of 'fopen'
    3>  Creating directories for 'meta'
    3>  Performing download step (git clone) for 'meta'
    3>  Cloning into 'meta'...
    3>  Already on 'master'
    3>  Your branch is up-to-date with 'origin/master'.
    3>  Submodule 'doc/gh-pages' (https://github.com/ericniebler/meta.git) registered for path 'doc/gh-pages'
    3>  Cloning into 'doc/gh-pages'...
    3>  Submodule path 'doc/gh-pages': checked out '23d49cfb19b58a13089fb12e6ac65465e254eeb2'
    3>  Performing update step for 'meta'
    3>  Current branch master is up to date.
    3>  No patch step for 'meta'
    3>  Performing configure step for 'meta'
    3>  -- The CXX compiler identification is MSVC 18.0.21005.1
    3>  -- Check for working CXX compiler using: Visual Studio 12 2013 Win64
    3>  -- Check for working CXX compiler using: Visual Studio 12 2013 Win64 -- works
    3>  -- Detecting CXX compiler ABI info
    3>  -- Detecting CXX compiler ABI info - done
    3>  -- Detecting CXX compile features
    3>  -- Detecting CXX compile features - done
    3>  CMake Warning (dev) at CMakeLists.txt:16 (if):
    3>    Policy CMP0054 is not set: Only interpret if() arguments as variables or
    3>    keywords when unquoted.  Run "cmake --help-policy CMP0054" for policy
    3>    details.  Use the cmake_policy command to set the policy and suppress this
    3>    warning.
    3>  
    3>    Quoted variables like "MSVC" will no longer be dereferenced when the policy
    3>    is set to NEW.  Since the policy is not set the OLD behavior will be used.
    3>  This warning is for project developers.  Use -Wno-dev to suppress it.
    3>  
    3>  -- Could NOT find Doxygen (missing:  DOXYGEN_EXECUTABLE) 
    3>  -- Found Git: C:/Program Files (x86)/Git/cmd/git.exe (found version "1.9.5.msysgit.1") 
    3>  -- Doxygen not found; the 'doc' and 'gh-pages.{clean,copy,update}' targets will be unavailable.
    3>  -- Configuring done
    3>  -- Generating done
    3>  -- Build files have been written to: C:/Users/magho_000/Desktop/Build/src/meta-build
    3>  No build step for 'meta'
    3>  No install step for 'meta'
    3>  Completed 'meta'
    

    At this point, the build process halts (as if trapped in a deadlock) and there's nothing I can do other than force close MSBuild process. Any help is greatly appreciated :)

    opened by Maghoumi 102
  • Cmake fails on Windows 10 with VS2017 (64-bit)

    Cmake fails on Windows 10 with VS2017 (64-bit)

    I get the following error when I try and use cmake (3.10.2) to setup the project for VS2017,

    CMake Error at cmake/SetTargetCompileOptions.cmake:47 (message): Could not set compile flags for compiler id: MSVC Call Stack (most recent call first): lib/CMakeLists.txt:14 (setTargetCompileOptions) lib/CMakeLists.txt:40 (add_approxmvbb_lib)

    opened by adam-hartshorne 23
  • Stable min/max points ?

    Stable min/max points ?

    Hi gabyx, first of all thanks for your amazing work about this libraries :) . For second: i'm trying to compile your libraries for windows using vs2017 but i have a lot of compiling errors that i think are due to the compiler but i don't know how to manage it. Can you help me?

    i have attached logs both from cmake-gui and from vs2017, i'm using windows 10 64bit.

    The most important i think is "error MSB6006: "CL.exe" exited with code 2."

    Thank you for you reply

    Federica

    opened by federicatrozzi 10
  • Initial Matrix3Dyn from data

    Initial Matrix3Dyn from data

    Hey Gabyx,

    I was trying to use your library to process some data in my research project, but I'm not very familiar with C++.

    I'm trying to initial Matrix3Dyn from my 3D data points, but I'm not sure how to add point one by one. I searched your code base finding that Matrix3Dyn is a data structure wrapper of Eigen::Matrix from Eigen library (?). And I'm still confused how to use it after checking docs on Eigen.

    Wonder if you could give some code fragments on this kind of usage? Thanks.

    Tim

    question 
    opened by pcpLiu 9
  • Make issue -

    Make issue -

    I seem to get the following issue:

    http://pastebin.com/inuaFYFC

    The error appears to be on the example/kdTreeFiltering:

    /home/raaj/ApproxMVBB/include/ApproxMVBB/KdTree.hpp: In member function ‘void ApproxMVBB::KdTree::TreeStatistics::appendToXML(ApproxMVBB::KdTree::TreeStatistics::XMLNodeType&)’: /home/raaj/ApproxMVBB/include/ApproxMVBB/KdTree.hpp:1721:109: error: call of overloaded ‘set_value(long long unsigned int)’ is ambiguous stat.append_attribute("m_minLeafDataSize").set_value( (long long unsigned int)m_minLeafDataSize );

    opened by soulslicer 9
  • MVBB too large

    MVBB too large

    Hey, I am currently trying to calculate the MVBB for each link of a robotic arm. For most of the links, the output is OK, but some inputs produce degenerate boxes like this:

    screenshot_endeffector_box

    The potential MVBB is the big grey box, the actual link is displayed inside the red rectangle. I read the points of the link directly from the STL file, which I checked, does not contain any unwanted points that could cause this problem. Generally, I just use the same approach as in the example

        // Read the points into m_points
        // [...]
    
        m_oobb = ApproxMVBB::approximateMVBB(m_points,0.001,500,5,0,5);
    
        // Make sure all points are inside oobb
        ApproxMVBB::Matrix33 A_KI = m_oobb.m_q_KI.matrix().transpose();
        auto size = m_points.cols();
        for( unsigned int i=0;  i<size; ++i ) {
            m_oobb.unite(A_KI*m_points.col(i));
        }
    
        // [...]
        m_box_center = m_oobb.center();
        m_box_size = m_oobb.extent();
    
        // [...]
        m_box_center = (m_oobb.m_q_KI * m_box_center).eval();
        m_box_size = (m_oobb.m_q_KI * m_box_size).eval();
    

    I've also tried with different parametrizations of the algorithm by, e.g. taking 0.8 of the points as samples, or increasing number of grid-search runs.

    Additionally, it does not seem to fit the link correctly, as shown in the below image, although I explicitly united all points with the oobb. screenshot_endeffector_box_front

    The thing that bugs me the most is, that it works for many links, but for some it just produces boxes that are way too large. I already tried to wrap my head around this problem, but failed to come up with a cause that makes only a part of the links fail. Do you have any idea what might be causing this problem? I have the feeling I am missing something obvious.

    Best regards, André

    opened by abranden 5
  • macos cmake fpu_control problem

    macos cmake fpu_control problem

    My system is macOS 10.13.3. When I execute cmake .. in folder ApproxMVBB/Build It generated two errors and I paste them below. I searched google found that fpu_control.h is not a macOS header. So how do I build it? Thank you!

    image

    image

    image

    opened by wheelBL 5
  • Fix broken Visual Studio build

    Fix broken Visual Studio build

    Hello Gabriel, it's me again : ) When I tried building with VS 2015, I noticed there were a couple of minor issues preventing the build. This PR fixes those issues. I can confirm that the project builds fine under VS 2015 and the example works. Similar to before, the tests don't build under VS.

    Hope this helps. Cheers

    opened by Maghoumi 5
  • ApproxMVBB library version could not be determined!,GIT-NOTFOUND

    ApproxMVBB library version could not be determined!,GIT-NOTFOUND

    Hello, I have read the ApproxMVBB library version could not be determined!, HEAD-HASH-NOTFOUND. Gabyx says get the repository with clone and not from .zip. I have done that and I still get this error (used Git Desktop). Is there any solution to this ? image

    opened by NikLasov 4
  • openmp issue

    openmp issue

    hello

    there's something strange...

    i'm discovering your library and test your example with the simple code of the readme: ApproxMVBB::Matrix3Dyn points(3,3000); points.setRandom(); ApproxMVBB::OOBB oobb = ApproxMVBB::approximateMVBB(points,0.001,1000,5,0,5); oobb.expandToMinExtentRelative(0.2);

    if openmp is not activated... no problem.

    if openmp is activated then i've this error, following...

    error: no member named 'approximateMVBB' in namespace 'ApproxMVBB'

    i think i missed the compilation somewhere

    opened by jean59 4
  • example error

    example error

    when i run example/ApproxMVBBExample-MVBB i got this

    ==29054==ASan runtime does not come first in initial library list; you should either link runtime to your application or manually preload it with LD_PRELOAD.
    

    i have to run export LD_PRELOAD=$LD_PRELOAD:/usr/lib/x86_64-linux-gnu/libasan.so.2 every time before running the example to make it correct. ubuntu 16.04 gcc5.4

    opened by RaymondZuo301 4
  • Problem with compilation

    Problem with compilation

    Hi, after building and install the project by make all make install

    I directly went into "example/approxMVBB/" and ran "g++ main.cpp", and I got error like:

    /tmp/ccsedFcN.o: In function main': main.cpp:(.text+0x304): undefined reference toApproxMVBB::OOBB::expandToMinExtentAbsolute(double)' /tmp/ccsedFcN.o: In function ApproxMVBB::OOBB::setZAxisLongest()': main.cpp:(.text._ZN10ApproxMVBB4OOBB15setZAxisLongestEv[_ZN10ApproxMVBB4OOBB15setZAxisLongestEv]+0x48): undefined reference toApproxMVBB::OOBB::switchZAxis(unsigned int)' /tmp/ccsedFcN.o: In function ApproxMVBB::OOBB ApproxMVBB::approximateMVBBDiam<Eigen::Matrix<double, 3, -1, 0, 3, -1> >(Eigen::MatrixBase<Eigen::Matrix<double, 3, -1, 0, 3, -1> > const&, double, unsigned int, unsigned long)': main.cpp:(.text._ZN10ApproxMVBB19approximateMVBBDiamIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EEdjm[_ZN10ApproxMVBB19approximateMVBBDiamIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EEdjm]+0x233): undefined reference toApproxMVBB::ProjectedPointSet::ProjectedPointSet()' main.cpp:(.text._ZN10ApproxMVBB19approximateMVBBDiamIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EEdjm[_ZN10ApproxMVBB19approximateMVBBDiamIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EEdjm]+0x2fd): undefined reference to ApproxMVBB::ProjectedPointSet::~ProjectedPointSet()' main.cpp:(.text._ZN10ApproxMVBB19approximateMVBBDiamIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EEdjm[_ZN10ApproxMVBB19approximateMVBBDiamIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EEdjm]+0x328): undefined reference toApproxMVBB::ProjectedPointSet::~ProjectedPointSet()' /tmp/ccsedFcN.o: In function ApproxMVBB::OOBB ApproxMVBB::approximateMVBBGridSearch<Eigen::Matrix<double, 3, -1, 0, 3, -1> >(Eigen::MatrixBase<Eigen::Matrix<double, 3, -1, 0, 3, -1> > const&, ApproxMVBB::OOBB, double, unsigned int, unsigned int, double, double)': main.cpp:(.text._ZN10ApproxMVBB25approximateMVBBGridSearchIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EES4_djjdd[_ZN10ApproxMVBB25approximateMVBBGridSearchIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EES4_djjdd]+0x76): undefined reference toApproxMVBB::OOBB::expandToMinExtentAbsolute(double)' main.cpp:(.text._ZN10ApproxMVBB25approximateMVBBGridSearchIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EES4_djjdd[_ZN10ApproxMVBB25approximateMVBBGridSearchIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EES4_djjdd]+0xdf): undefined reference to ApproxMVBB::ProjectedPointSet::ProjectedPointSet()' main.cpp:(.text._ZN10ApproxMVBB25approximateMVBBGridSearchIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EES4_djjdd[_ZN10ApproxMVBB25approximateMVBBGridSearchIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EES4_djjdd]+0x2bd): undefined reference toApproxMVBB::OOBB::expandToMinExtentAbsolute(double)' main.cpp:(.text._ZN10ApproxMVBB25approximateMVBBGridSearchIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EES4_djjdd[_ZN10ApproxMVBB25approximateMVBBGridSearchIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EES4_djjdd]+0x4c0): undefined reference to ApproxMVBB::ProjectedPointSet::~ProjectedPointSet()' main.cpp:(.text._ZN10ApproxMVBB25approximateMVBBGridSearchIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EES4_djjdd[_ZN10ApproxMVBB25approximateMVBBGridSearchIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EES4_djjdd]+0x4f0): undefined reference toApproxMVBB::ProjectedPointSet::~ProjectedPointSet()' /tmp/ccsedFcN.o: In function std::pair<Eigen::Matrix<double, 3u, 1, ((Eigen::StorageOptions)0)|((((3u)==(1))&&((1)!=(1)))?((Eigen::StorageOptions)1) : ((((1)==(1))&&((3u)!=(1)))?((Eigen::StorageOptions)0) : ((Eigen::StorageOptions)0))), 3u, 1>, Eigen::Matrix<double, 3u, 1, ((Eigen::StorageOptions)0)|((((3u)==(1))&&((1)!=(1)))?((Eigen::StorageOptions)1) : ((((1)==(1))&&((3u)!=(1)))?((Eigen::StorageOptions)0) : ((Eigen::StorageOptions)0))), 3u, 1> > ApproxMVBB::PointFunctions::estimateDiameter<3u, Eigen::Matrix<double, 3, -1, 0, 3, -1> >(Eigen::MatrixBase<Eigen::Matrix<double, 3, -1, 0, 3, -1> > const&, double, unsigned long)': main.cpp:(.text._ZN10ApproxMVBB14PointFunctions16estimateDiameterILj3EN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEESt4pairINS3_IdXT_ELi1EXorLNS2_14StorageOptionsE0EquaaeqT_Li1EneLi1ELi1ELS6_1EquaaeqLi1ELi1EneT_Li1ELS6_0ELS6_0EEXT_ELi1EEES7_ERKNS2_10MatrixBaseIT0_EEdm[_ZN10ApproxMVBB14PointFunctions16estimateDiameterILj3EN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEESt4pairINS3_IdXT_ELi1EXorLNS2_14StorageOptionsE0EquaaeqT_Li1EneLi1ELi1ELS6_1EquaaeqLi1ELi1EneT_Li1ELS6_0ELS6_0EEXT_ELi1EEES7_ERKNS2_10MatrixBaseIT0_EEdm]+0x142): undefined reference toApproxMVBB::DiameterEstimator::estimateDiameter(ApproxMVBB::Diameter::TypeSegment*, double const**, int, int, int, double)' /tmp/ccsedFcN.o: In function ApproxMVBB::OOBB ApproxMVBB::ProjectedPointSet::computeMVBBApprox<Eigen::Matrix<double, 3, -1, 0, 3, -1> >(Eigen::Matrix<double, 3, 1, 0, 3, 1> const&, Eigen::MatrixBase<Eigen::Matrix<double, 3, -1, 0, 3, -1> > const&, double)': main.cpp:(.text._ZN10ApproxMVBB17ProjectedPointSet17computeMVBBApproxIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS3_IdLi3ELi1ELi0ELi3ELi1EEERKNS2_10MatrixBaseIT_EEd[_ZN10ApproxMVBB17ProjectedPointSet17computeMVBBApproxIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS3_IdLi3ELi1ELi0ELi3ELi1EEERKNS2_10MatrixBaseIT_EEd]+0x554): undefined reference toApproxMVBB::OOBB::OOBB(Eigen::Matrix<double, 3, 1, 0, 3, 1> const&, Eigen::Matrix<double, 3, 1, 0, 3, 1> const&, Eigen::Matrix<double, 3, 3, 0, 3, 3> const&)' /tmp/ccsedFcN.o: In function ApproxMVBB::OOBB ApproxMVBB::optimizeMVBB<Eigen::Matrix<double, 3, -1, 0, 3, -1> >(Eigen::MatrixBase<Eigen::Matrix<double, 3, -1, 0, 3, -1> > const&, ApproxMVBB::OOBB, unsigned int, double, double)': main.cpp:(.text._ZN10ApproxMVBB12optimizeMVBBIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EES4_jdd[_ZN10ApproxMVBB12optimizeMVBBIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EES4_jdd]+0xfa): undefined reference toApproxMVBB::ProjectedPointSet::ProjectedPointSet()' main.cpp:(.text._ZN10ApproxMVBB12optimizeMVBBIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EES4_jdd[_ZN10ApproxMVBB12optimizeMVBBIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EES4_jdd]+0x2d0): undefined reference to ApproxMVBB::OOBB::expandToMinExtentAbsolute(double)' main.cpp:(.text._ZN10ApproxMVBB12optimizeMVBBIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EES4_jdd[_ZN10ApproxMVBB12optimizeMVBBIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EES4_jdd]+0x377): undefined reference toApproxMVBB::ProjectedPointSet::~ProjectedPointSet()' main.cpp:(.text._ZN10ApproxMVBB12optimizeMVBBIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EES4_jdd[_ZN10ApproxMVBB12optimizeMVBBIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS1_10MatrixBaseIT_EES4_jdd]+0x38b): undefined reference to ApproxMVBB::ProjectedPointSet::~ProjectedPointSet()' /tmp/ccsedFcN.o: In functionApproxMVBB::OOBB ApproxMVBB::ProjectedPointSet::computeMVBB<Eigen::Matrix<double, 3, -1, 0, 3, -1> >(Eigen::Matrix<double, 3, 1, 0, 3, 1> const&, Eigen::MatrixBase<Eigen::Matrix<double, 3, -1, 0, 3, -1> > const&)': main.cpp:(.text._ZN10ApproxMVBB17ProjectedPointSet11computeMVBBIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS3_IdLi3ELi1ELi0ELi3ELi1EEERKNS2_10MatrixBaseIT_EE[_ZN10ApproxMVBB17ProjectedPointSet11computeMVBBIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS3_IdLi3ELi1ELi0ELi3ELi1EEERKNS2_10MatrixBaseIT_EE]+0x91): undefined reference to ApproxMVBB::MinAreaRectangle::compute()' main.cpp:(.text._ZN10ApproxMVBB17ProjectedPointSet11computeMVBBIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS3_IdLi3ELi1ELi0ELi3ELi1EEERKNS2_10MatrixBaseIT_EE[_ZN10ApproxMVBB17ProjectedPointSet11computeMVBBIN5Eigen6MatrixIdLi3ELin1ELi0ELi3ELin1EEEEENS_4OOBBERKNS3_IdLi3ELi1ELi0ELi3ELi1EEERKNS2_10MatrixBaseIT_EE]+0x36e): undefined reference toApproxMVBB::OOBB::OOBB(Eigen::Matrix<double, 3, 1, 0, 3, 1> const&, Eigen::Matrix<double, 3, 1, 0, 3, 1> const&, Eigen::Matrix<double, 3, 3, 0, 3, 3> const&)' /tmp/ccsedFcN.o: In function std::pair<Eigen::Matrix<double, 2u, 1, ((Eigen::StorageOptions)0)|((((2u)==(1))&&((1)!=(1)))?((Eigen::StorageOptions)1) : ((((1)==(1))&&((2u)!=(1)))?((Eigen::StorageOptions)0) : ((Eigen::StorageOptions)0))), 2u, 1>, Eigen::Matrix<double, 2u, 1, ((Eigen::StorageOptions)0)|((((2u)==(1))&&((1)!=(1)))?((Eigen::StorageOptions)1) : ((((1)==(1))&&((2u)!=(1)))?((Eigen::StorageOptions)0) : ((Eigen::StorageOptions)0))), 2u, 1> > ApproxMVBB::PointFunctions::estimateDiameter<2u, Eigen::Matrix<double, 2, -1, 0, 2, -1> >(Eigen::MatrixBase<Eigen::Matrix<double, 2, -1, 0, 2, -1> > const&, double, unsigned long)': main.cpp:(.text._ZN10ApproxMVBB14PointFunctions16estimateDiameterILj2EN5Eigen6MatrixIdLi2ELin1ELi0ELi2ELin1EEEEESt4pairINS3_IdXT_ELi1EXorLNS2_14StorageOptionsE0EquaaeqT_Li1EneLi1ELi1ELS6_1EquaaeqLi1ELi1EneT_Li1ELS6_0ELS6_0EEXT_ELi1EEES7_ERKNS2_10MatrixBaseIT0_EEdm[_ZN10ApproxMVBB14PointFunctions16estimateDiameterILj2EN5Eigen6MatrixIdLi2ELin1ELi0ELi2ELin1EEEEESt4pairINS3_IdXT_ELi1EXorLNS2_14StorageOptionsE0EquaaeqT_Li1EneLi1ELi1ELS6_1EquaaeqLi1ELi1EneT_Li1ELS6_0ELS6_0EEXT_ELi1EEES7_ERKNS2_10MatrixBaseIT0_EEdm]+0x142): undefined reference toApproxMVBB::DiameterEstimator::estimateDiameter(ApproxMVBB::Diameter::TypeSegment*, double const**, int, int, int, double)' collect2: error: ld returned 1 exit status

    Does it matter if I ignore the "CMake FindScripts" step ? Cause this is the only different between my implementation and your official guidance.

    help wanted 
    opened by Zerg-Overmind 11
  • VS2017 - definition of dllimport function not allowed errors

    VS2017 - definition of dllimport function not allowed errors

    When building the library and various projects, I receive a number of #C2491 errors e.g. error C2491: 'ApproxMVBB::approximateMVBBGridSearch': definition of dllimport function not allowed

    I believe it is this problem which is specific to Visual Studio compiler,

    https://msdn.microsoft.com/en-us/library/62688esh.aspx

    https://docs.microsoft.com/en-us/cpp/cpp/using-dllimport-and-dllexport-in-cpp-classes

    opened by adam-hartshorne 4
  • reference and parallelization

    reference and parallelization

    Hi gabyx. Thanks for offering your work. It is valuable for me. Can you offer the reference paper of your implementation? I think it would be helpful to understand your code by my own. Question 2 is - do you think ApproxMVBB is easy to parallelization by means of OpenMP/MPI etc. ? In my experiment, the speed using ApproxMVBB almostly equals to the speed of rotating calipers method with parallelization.

    enhancement 
    opened by chenming-wu 12
  • a conda build and cmake problem

    a conda build and cmake problem

    Hi, I've created a conda build for ApproxMVBB, see https://anaconda.org/lorinma/mvbb

    After install the libs through conda, I was trying to test the example code from https://github.com/gabyx/ApproxMVBB/blob/master/example/approxMVBB/src/main.cpp

    with a simple CMakeLists.txt It passed the cmake process, but then I get a series errors for 'xxx was not declared in this scope' when I build it

    But, if I run cmake twice: $cmake .. $cmake .. Then I can build it smoothly and get the right result when run the binary

    I'm working on Cloud9 (Ubuntu linux-64)

    Any idea?

    Thanks!

    help wanted 
    opened by lorinma 6
Owner
Gabriel Nützi
with a degree in permanent-head-damage (phd)
Gabriel Nützi
Point Cloud Denoising input segmentation output raw point-cloud valid/clear fog rain de-noised Abstract Lidar sensors are frequently used in environme

Point Cloud Denoising input segmentation output raw point-cloud valid/clear fog rain de-noised Abstract Lidar sensors are frequently used in environme

null 75 Nov 24, 2022
Gesture-Volume-Control - This Python program can adjust the system's volume by using hand gestures

Gesture-Volume-Control This Python program can adjust the system's volume by usi

VatsalAryanBhatanagar 1 Dec 30, 2021
Hand Gesture Volume Control is AIML based project which uses image processing to control the volume of your Computer.

Hand Gesture Volume Control Modules There are basically three modules Handtracking Program Handtracking Module Volume Control Program Handtracking Pro

VITTAL 1 Jan 12, 2022
This code finds bounding box of a single human mouth.

This code finds bounding box of a single human mouth. In comparison to other face segmentation methods, it is relatively insusceptible to open mouth conditions, e.g., yawning, surgical robots, etc. The mouth coordinates are found in a more certified way using two independent algorithms. Therefore, the algorithm can be used in more sensitive applications.

iThermAI 4 Nov 27, 2022
Alpha-IoU: A Family of Power Intersection over Union Losses for Bounding Box Regression

Alpha-IoU: A Family of Power Intersection over Union Losses for Bounding Box Regression YOLOv5 with alpha-IoU losses implemented in PyTorch. Example r

Jacobi(Jiabo He) 147 Dec 5, 2022
Tools to create pixel-wise object masks, bounding box labels (2D and 3D) and 3D object model (PLY triangle mesh) for object sequences filmed with an RGB-D camera.

Tools to create pixel-wise object masks, bounding box labels (2D and 3D) and 3D object model (PLY triangle mesh) for object sequences filmed with an RGB-D camera. This project prepares training and testing data for various deep learning projects such as 6D object pose estimation projects singleshotpose, as well as object detection and instance segmentation projects.

null 305 Dec 16, 2022
Improving Object Detection by Estimating Bounding Box Quality Accurately

Improving Object Detection by Estimating Bounding Box Quality Accurately Abstrac

null 2 Apr 14, 2022
LQM - Improving Object Detection by Estimating Bounding Box Quality Accurately

Improving Object Detection by Estimating Bounding Box Quality Accurately Abstract Object detection aims to locate and classify object instances in ima

IM Lab., POSTECH 0 Sep 28, 2022
Rendering Point Clouds with Compute Shaders

Compute Shader Based Point Cloud Rendering This repository contains the source code to our techreport: Rendering Point Clouds with Compute Shaders and

Markus Schütz 460 Jan 5, 2023
Style-based Point Generator with Adversarial Rendering for Point Cloud Completion (CVPR 2021)

Style-based Point Generator with Adversarial Rendering for Point Cloud Completion (CVPR 2021) An efficient PyTorch library for Point Cloud Completion.

Microsoft 119 Jan 2, 2023
Implementation of the "PSTNet: Point Spatio-Temporal Convolution on Point Cloud Sequences" paper.

PSTNet: Point Spatio-Temporal Convolution on Point Cloud Sequences Introduction Point cloud sequences are irregular and unordered in the spatial dimen

Hehe Fan 63 Dec 9, 2022
Implementation of the "Point 4D Transformer Networks for Spatio-Temporal Modeling in Point Cloud Videos" paper.

Point 4D Transformer Networks for Spatio-Temporal Modeling in Point Cloud Videos Introduction Point cloud videos exhibit irregularities and lack of or

Hehe Fan 101 Dec 29, 2022
Synthetic LiDAR sequential point cloud dataset with point-wise annotations

SynLiDAR dataset: Learning From Synthetic LiDAR Sequential Point Cloud This is official repository of the SynLiDAR dataset. For technical details, ple

null 78 Dec 27, 2022
[ICCV 2021 Oral] SnowflakeNet: Point Cloud Completion by Snowflake Point Deconvolution with Skip-Transformer

This repository contains the source code for the paper SnowflakeNet: Point Cloud Completion by Snowflake Point Deconvolution with Skip-Transformer (ICCV 2021 Oral). The project page is here.

AllenXiang 65 Dec 26, 2022
A fast model to compute optical flow between two input images.

DCVNet: Dilated Cost Volumes for Fast Optical Flow This repository contains our implementation of the paper: @InProceedings{jiang2021dcvnet, title={

Huaizu Jiang 8 Sep 27, 2021
Black-Box-Tuning - Black-Box Tuning for Language-Model-as-a-Service

Black-Box-Tuning Source code for paper "Black-Box Tuning for Language-Model-as-a

Tianxiang Sun 149 Jan 4, 2023
Minimal diffusion models - Minimal code and simple experiments to play with Denoising Diffusion Probabilistic Models (DDPMs)

Minimal code and simple experiments to play with Denoising Diffusion Probabilist

Rithesh Kumar 16 Oct 6, 2022
GndNet: Fast ground plane estimation and point cloud segmentation for autonomous vehicles using deep neural networks.

GndNet: Fast Ground plane Estimation and Point Cloud Segmentation for Autonomous Vehicles. Authors: Anshul Paigwar, Ozgur Erkent, David Sierra Gonzale

Anshul Paigwar 114 Dec 29, 2022
Cascading Feature Extraction for Fast Point Cloud Registration (BMVC 2021)

Cascading Feature Extraction for Fast Point Cloud Registration This repository contains the source code for the paper [Arxive link comming soon]. Meth

null 7 May 26, 2022