Git Product home page Git Product logo

vdbfusion's Introduction

VDBFusion: Flexible and Efficient TSDF Integration

C++ Python Linux PyPI version shields.io PRs Welcome Paper MIT license Open In Colab

example

This is a small utility library that implements the VDBFusion algorithm, similar to TSDF-based reconstruction pipelines but using a different data-structure (VDB).

Installation

Take a seat and relax, you only need to:

pip install vdbfusion

If you plan to use our C++ API then you should build this project from source. More details in the Installation instructions.

The ROS-1 C++ wrapper for this library is available at https://github.com/PRBonn/vdbfusion_ros

Usage

The code shown below is not intended to be copy pasted but rather be a spiritual guide for developers. If you really want to give this library a try you should consider checking the standalone Python, Notebooks, and C++ examples.

Data loading

NOTE: This step is not mandatory. Our API only expects points and poses but this is the easiest way to deal with 3D data.

Python C++
class Dataset:
    def __init__(self, *args, **kwargs):
        # Initialize your dataset here ..

    def __len__(self) -> int:
        return len(self.n_scans)

    def __getitem__(self, idx: int):
        # Returns a PointCloud(np.array(N, 3))
        # and sensor origin(Eigen::Vector3d)
        # in the global coordinate frame.
        return points, origin
class Dataset {
  // Initialize your dataset here ..
  Dataset(...);

  // Return length of the dataset
  std::size_t size() const { return n_scans_; }

  // Returns a Cloud(std::vector<Eigen::Vector3d>)
  // and the sensor origin(Eigen::Vector3d) in the
  // global coordinate frame.
  std::tuple<Cloud, Point> operator[](int idx) const;
};

TSDF Fusion pipeline

Python C++
import vdbfusion

vdb_volume = vdbfusion.VDBVolume(voxel_size,
                                 sdf_trunc,
                                 space_carving
dataset = Dataset(...)

for scan, origin in dataset:
    vdb_volume.integrate(scan, origin)
#include "vdbfusion/VDBVolume.h"

vdb_fusion::VDBVolume vdb_volume(voxel_size,
                                 sdf_trunc,
                                 space_carving);
const auto dataset = Dataset(...);

for (const auto& [scan, origin] : iterable(dataset)) {
  vdb_volume.Integrate(scan, origin);
}

Visualization

For visualization you can use any 3D library you like. For this example we are going to be using Open3D. If you are using the Python API make sure to pip install open3d before trying this snippet.

Python C++
import open3d as o3d

# Extract triangle mesh (numpy arrays)
vert, tri = vdb_volume.extract_triangle_mesh()

# Visualize the results
mesh = o3d.geometry.TriangleMesh(
    o3d.utility.Vector3dVector(vert),
    o3d.utility.Vector3iVector(tri),
)

mesh.compute_vertex_normals()
o3d.visualization.draw_geometries([mesh])
#include <open3d/Open3D.h>

// Extract triangle mesh (Eigen).
auto [verts, tris] = vdb_volume.ExtractTriangleMesh();

// Visualize the results
auto mesh = o3d::geometry::TriangleMesh(
    verts,
    tris,
)

mesh.ComputeVertexNormals()
o3d::visualization::DrawGeometries({&mesh})

LICENSE

The LICENSE can be found at the root of this repository. It only applies to the code of VDBFusion but not to its 3rdparty dependencies. Please make sure to check the licenses in there before using any form of this code.

Credits

I would like to thank the Open3D and OpenVDB authors and contributors for making their implementations open source which inspired, helped and guided the implementation of the VDBFusion library.

Citation

If you use this library for any academic work, please cite the original paper.

@article{vizzo2022sensors,
  author         = {Vizzo, Ignacio and Guadagnino, Tiziano and Behley, Jens and Stachniss, Cyrill},
  title          = {VDBFusion: Flexible and Efficient TSDF Integration of Range Sensor Data},
  journal        = {Sensors},
  volume         = {22},
  year           = {2022},
  number         = {3},
  article-number = {1296},
  url            = {https://www.mdpi.com/1424-8220/22/3/1296},
  issn           = {1424-8220},
  doi            = {10.3390/s22031296}
}

vdbfusion's People

Contributors

benemer avatar luarzou avatar nachovizzo avatar saurabh1002 avatar sumanthrao1997 avatar swarmt avatar willyzw 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

vdbfusion's Issues

Does VDBFusion support pcd with colors as input?

Great Work, and Easy to Use.

I wanna to reconstruction with mesh, and I have the pointcloud with colors and normals.

If the API support the pcd with colors as input. If supported, how can I call the interface methods? if not, any other texture mapping methods recommended based on the mesh result from VDBFusion result ?

Thanks for replying.

Help with Parametrization

Hi & thanks for your great repository!

Using Kitti Dataset I get very good results. Now I am trying to run your pipeline on a custom dataset. While the fine detail of cars is astonishing, the reconstruction of large structures such as the street is quite bad. I have tried different parametrizations but the problem stays the same.

Here are two screenshots of the resulting reconstructed mesh

image image

And here is a screenshot of the the merged point cloud:

image

As you can see the merged pointcloud (consisting of 50 scans) is very dense and provides great detail, but the mesh is full of holes and missing parts. I have used the standard Kitti parametrization you provided, but played around with the voxel_size, sdf_trunc, min_weight, fill_holes etc. in the range of [x0.1, x10] and the results were always almost the same.

Can you point me in any direction of what I could change in the parametrization / setting etc.?

Failed to extract accurate Point Cloud from VDB structure

First and foremost, thank you for your tremendous effort in creating this repository. It is truly inspiring and highly valuable to the scientific community.

I am currently working on evaluating the mapping accuracy of different frameworks and I am encountering difficulties in accurately extracting the point cloud from the VDB structure generated by VDBFusion.

Specifically, my challenge lies in the discrepancy between the number of points in the original point cloud and the number of points extracted from the VDB structure. Depending on how I set the voxel size and SDF truncation values, I either obtain a higher or lower number of points than originally populated. I assume this issue arises due to the DDA algorithm used.

Here are the details of my process:

  1. Original Point Cloud: The point cloud represented with the PCL library resulting in a total of 2,455,166 points was clustered which resulted in the same number of points as shown in the following visualized original point cloud:

original
original2

  1. VDB Structure: The point cloud represented with the VDB structure -by populating a points grid with the points from the point cloud- was clustered, however, upon extracting the points from this structure, the number of points were found to be only 1,340,674 as shown in the visualized vdb-extracted point cloud:

vdb_extracted
vdb_extracted2

In your publication, "VDBFusion: Flexible and Efficient TSDF Integration of Range Sensor Data," you mention densely sampling the maps generated by Voxblox and VDBFusion into a point cloud for evaluation purposes. Additionally, there is a reference in the GitHub issues about the ease and efficiency of extracting the point cloud using OpenVDB, but I have not been able to achieve the same accuracy.

I have also followed the suggestions mentioned in the issue "Realtime Point Cloud extraction #22" in order to extract the point cloud from the VDB structure but without success.

I understand that the evaluation code is not provided in the repository. Could you please provide guidance on the relevant script/code snippet that demonstrates how to accurately sample the point cloud from the VDB structure and also share ? Specifically, I am looking for a method to ensure that the extracted point cloud matches the original number of points before clustering.

Additionally, if possible, could you also share the evaluation code you used to compare the mapping accuracy of different frameworks? in ensure a consistent and accurate comparison for my thesis.

Any help or direction you could provide would be greatly appreciated. Thank you for your time and assistance.

and here is the used point extraction function for reference:

`
std::tuple<std::vectorEigen::Vector3d, std::vectorEigen::Vector3d, std::vector<uint8_t>, std::vector> VDBVolume::ExtractPointCloud(float thresh) const {

    std::vector<Eigen::Vector3d> points;
    std::vector<Eigen::Vector3d> colors;
    std::vector<uint8_t> labels;
    std::vector<int> cluster_ids;

    auto weights_accessor = weights_grid->getConstAccessor();
    auto points_accessor = points_grid->getConstAccessor();
    auto colors_accessor = colors_grid->getConstAccessor();
    auto labels_accessor = labels_grid->getConstAccessor();
    auto clusters_accessor = clusters_grid->getConstAccessor();

    for (auto iter = tsdf_grid->cbeginValueOn(); iter.test(); ++iter) {
        const auto &voxel = iter.getCoord();

        const auto &tsdf = iter.getValue();
        const auto tsdf_abs = std::abs(tsdf);

        if (tsdf_abs < thresh) {

            /* const auto point = points_accessor.getValue(voxel); */
            const auto point = GetVoxelCenter(voxel, points_grid->transform());   

            const auto& color = colors_accessor.getValue(voxel);
            const auto& label = labels_accessor.getValue(voxel);
            const auto& cluster_id = clusters_accessor.getValue(voxel);
            
            const auto r = color.x();
            const auto g = color.y();
            const auto b = color.z();

            points.push_back(Eigen::Vector3d(point.x(), point.y(), point.z()));
            colors.push_back(Eigen::Vector3d(r, g, b));
            labels.push_back(static_cast<uint8_t>(label));
            cluster_ids.push_back(cluster_id);
                

            //}
        }
    }
    return std::make_tuple(points, colors, labels, cluster_ids);
}

void vdbfusion::VDBVolume::saveVDBToPCD(const vdbfusion::VDBVolume& vdbVolume, const std::string& outputdirectory) {

    PointCloudXYZRGBLC::Ptr cloud(new PointCloudXYZRGBLC);

    auto [points, colors, labels, cluster_ids] = vdbVolume.ExtractPointCloud(0.7);

    if (points.size() != colors.size() || points.size() != labels.size() || points.size() != cluster_ids.size()) {
        std::cerr << "Inconsistent data sizes in extracted point cloud data." << std::endl;
        return;
    }

    for (size_t i = 0; i < points.size(); ++i) {
        PointXYZRGBI pt;
        pt.x = points[i].x();
        pt.y = points[i].y();
        pt.z = points[i].z();
        pt.r = static_cast<uint8_t>(colors[i].x());
        pt.g = static_cast<uint8_t>(colors[i].y());
        pt.b = static_cast<uint8_t>(colors[i].z());
        pt.SemanticLabel = labels[i];
        pt.cluster_id = cluster_ids[i];

        cloud->points.push_back(pt);
    }

    cloud->width = cloud->points.size();
    cloud->height = 1;
    cloud->is_dense = false;

    std::string outputFilePath = outputdirectory + "No.Pts=" + std::to_string(cloud->points.size()) + "__.pcd";

    // Save the cloud to a PCD file
    pcl::io::savePCDFileBinary(outputFilePath, *cloud);
    std::cout << "\nVDB saved " << cloud->points.size() << " data points." << std::endl;
    std::cout << "--> at" << outputFilePath << std::endl;
}

`

So in other words, you had the input to the algorithm as a point cloud and then through VDBFusion algorithm, we got a vdb structure representation of the data which you visualized specifically using a mesh representation only and didn't extract and visualize a point cloud from the vdb structure, so, my questions, is whether there is a specific reason for not visualizing it as a point cloud?

installing VDBFusion C++ API

Hello!

I am attempting to install VDBFusion, including the C++ API, using the Docker image.

This is what I get as a message towards the end of the Docker Compose process:

#14 3.984 -- ----------------------------------------------------
#14 3.984 -- ----------- Configuring OpenVDBBinaries ------------
#14 3.984 -- ----------------------------------------------------
#14 3.989 -- Found TBB: /usr/include (found suitable version "2020.1", minimum required is "2019.0") found components: tbbmalloc 
#14 3.992 -- Configuring done
#14 4.032 -- Generating done
#14 4.034 -- Build files have been written to: /openvdb/build
#14 4.175 Scanning dependencies of target openvdb_static
#14 4.179 Scanning dependencies of target openvdb_shared
#14 4.200 [  2%] Building CXX object openvdb/openvdb/CMakeFiles/openvdb_static.dir/instantiations/VolumeAdvect.cc.o
#14 4.200 [  2%] Building CXX object openvdb/openvdb/CMakeFiles/openvdb_static.dir/instantiations/VolumeToSpheres.cc.o
#14 4.200 [  2%] Building CXX object openvdb/openvdb/CMakeFiles/openvdb_static.dir/instantiations/VolumeToMesh.cc.o
#14 4.201 [  2%] Building CXX object openvdb/openvdb/CMakeFiles/openvdb_shared.dir/instantiations/VolumeToSpheres.cc.o
#14 46.93 c++: fatal error: Killed signal terminated program cc1plus
#14 46.93 compilation terminated.
#14 46.93 make[2]: *** [openvdb/openvdb/CMakeFiles/openvdb_static.dir/build.make:63: openvdb/openvdb/CMakeFiles/openvdb_static.dir/instantiations/VolumeToSpheres.cc.o] Error 1
#14 46.93 make[2]: *** Waiting for unfinished jobs....
#14 47.07 [  3%] Building CXX object openvdb/openvdb/CMakeFiles/openvdb_shared.dir/instantiations/VolumeToMesh.cc.o
#14 97.09 c++: fatal error: Killed signal terminated program cc1plus
#14 97.09 compilation terminated.
#14 97.10 make[2]: *** [openvdb/openvdb/CMakeFiles/openvdb_shared.dir/build.make:63: openvdb/openvdb/CMakeFiles/openvdb_shared.dir/instantiations/VolumeToSpheres.cc.o] Error 1
#14 97.10 make[2]: *** Waiting for unfinished jobs....
#14 118.5 make[1]: *** [CMakeFiles/Makefile2:166: openvdb/openvdb/CMakeFiles/openvdb_static.dir/all] Error 2
#14 118.5 make[1]: *** Waiting for unfinished jobs....
#14 133.5 make[1]: *** [CMakeFiles/Makefile2:193: openvdb/openvdb/CMakeFiles/openvdb_shared.dir/all] Error 2
#14 133.5 make: *** [Makefile:141: all] Error 2
------
failed to solve: executor failed running [/bin/sh -c git clone --depth 1 https://github.com/nachovizzo/openvdb.git -b nacho/vdbfusion     && cd openvdb     && mkdir build && cd build     && cmake     -DOPENVDB_BUILD_PYTHON_MODULE=ON     -DUSE_NUMPY=ON     -DCMAKE_POSITION_INDEPENDENT_CODE=ON     -DUSE_ZLIB=OFF     ..    && make -j$(nproc) all install     && rm -rf /openvdb]: exit code: 2

Would you happen to have insights as to what went wrong? Many thanks.

How to get TSDF volume?

Dear authors, thank you for such awesome tool, it is working like a charm! I wonder, what is the fastest way to get TSDF volume as numpy array, as well its volume bounds?

Compile with PYOPENVDB_SUPPORT_ENABLED

Hello

I recently came across this library and it is doing almost all the things I need for a project I am working on. Thank you! I want to experiment with using different weights, but unfortunately when using the python API I encounter the following error:
NotImplementedError: Please compile with PYOPENVDB_SUPPORT_ENABLED

I called the following function, similar to the example in the paper
vdb_volume.integrate(pcd_numpy, np.identity(4), lambda sdf: 1 if sdf < eps else np.exp(-sigma * (sdf-eps) ** 2))
and simply installed vdbfusion using pip. The python version is 3.10

I have very little experience with compiling libraries from source and so was wondering what should be done exactly to fix this issue. Do I simple follow the steps from the install instructions?

Thanks in advance

Extrinsics in RGBD integration

Hallo, while trying out the example for RGB-D image based integration, I notice that the extrinsic/global poses are inverted. Since normally the global poses are given as camera to world, shall I interpret the inverted pose as world to camera transformation?

Lets take an example, the global pose is inverted here for scannet dataset.

pose = np.linalg.inv(pose)

Then the RGBD point cloud is transformed using the inverted pose here

pcd = o3d.geometry.PointCloud.create_from_rgbd_image(
rgbd, intrinsic, pose, project_valid_depth_only=True
)

So far is fine, as I vaguely remember open3d indeed assumes an extrinsic from world to camera. However, this inverted pose is further fed to the integration pipeline then apparently regarded as the frame origin. I am wondering whether this is really the purpose?

return xyz, np.array(pose)

Worse results than the paper displayed

I'm running the kitti 00 sequence with python API, but I got the result below:
image
image

which is much worse than the paper displayed:

image

I got this result without editing the config file.

And I repeated it by changing the fill_holes to True, but the result did not change.

Why there are two different results?

cannot make install succeed

hello, I want to use C++ API, then I followed your instructions Build from source in Linux. But, when I tried to use sudo make instal, I got some messages.
make_install.log

You know, most of the CMakeLists.txt projects can be installed as the below instructions:

git clone https://github.com/PRBonn/vdbfusion.git
cd vbdfusion && mkdir build && cmake ..
make -j4

Some things looked better than before( Because I can see the download packages process). However, I also got some messages;
make_j4.log

As the terminal output to screen, I tried to find what happened in make.
bootstrap.log

It just looks like having some problems with boost, I found some answers to this question(undefined reference to), but I don't know if it's correct. By the way, my system(Ubuntu 20.04) has installed boost(1.71), and your packages also need to reinstall boost as 3third libraries(the required boose version also is 1.71).

I don't know the next what I should do. Please give some tips.
So, I wish you can help me solve this problem when you have little time. Thank you!

Any trial on ESDF and gradient computation

Hi, thanks for your great work!
From the SLAM perspective, it would be better if the residual and gradient can be computed from the map to support frame-to-mesh registration (as you did in the PUMA paper, this is another good work). Also, the generation of the ESDF can be used for robotic planning. Have you tried these two directions? Or could you please share some hints on how to achieve them? I will try to make some contributions ^v^.
Thanks.

Build VDBFusion on MSVC 2019/Win 10

I am trying to build this repo on MSVC 2019/Windows 10. I used Cmake to configure and Generate, it was smooth. When I build the generated project, I face the error below, does anyone have any idea to fix it?
image

Comparison to Voxblox in paper

Hallo, since I have been using voxblox for a while. So far I am pretty satisfied with the performance it can bring. Especially the speed of its fast integrator. So as for the runtime, the experiments in paper point out the VDB's runtime is even faster than voxblox. Since there are three integrator types in voxblox, i.e. simple, merged and fast and apparently it means a lot to runtime, I am wondering which integrator type specifically does the comparison use? Thanks in advance for your reply!

Collision Detection

How would I query the map for collision detection?
Is there a way to use it with fcl for example?

Question about Eye-to-hand Scenario Usage

Hi

I have a depth camera mounted on the base and an object mounted on the end effector of robot arm. After scanning, hand_T_cam was calculated and used as the pose and sent along the scan result for fusion. I thought I could get the result including a clear model of the object and a messy background. However, on the contrary, I got a clear background and a messy foreground. Why is that?
截图 2024-04-23 15-58-28

Thanks

How to convert bunny.ply to dataset?

You say that
"""The bun.conf does not specify how to work with the trasnformation, after hours of tyring to
debug how to use it, I couldn't find how to use the 1996 dataset.
So I've created my own. Contact me if you feel curious on how I've obtianed it.
./mesh_to_dataset.py bunny.ply --scan-count 10
"""
So could you please tell me how to convert bunny.ply to dataset?
Thanks!

How to use the TUM RGBD dataset?

Dear professor,
Thanks for your great work. I have compiled this code on Windows with VS2019, and run with the KITTI odometry dataset sequence 00, and get the right result consistent with your paper. As i know, we can get the Tr form the calib.txt file of the KITTI, and get the final pose by:

T_velo_cam * P * T_cam_velo

Source code in KITTIOdometry.cpp:

屏幕截图 2024-02-02 103831

But how can i run it with the TUM RGBD dataset? and how can i get the Tr of the TUM RGBD data. I tried to set the T_cam_velo and the T_velo_cam to Eigen::Matrix4d::Identify(), but the output is wrong.

Looking forward for your reply.

Ubuntu 18 support or reimplementation

Hi, really great work on the volumetric mapping! I really appreciate it!

I want to ask if there is a possibility of Ubuntu 18 support? If not, maybe can you tell me a pathway for reimplementing this framework on ubuntu 18.

I saw that the newer versions of openVDB don't support ubuntu 18 out of the box, so I want to use an older version of it for ubuntu 18, maybe version 5 or 6. Is there any feature that is only present in the newer version for this vdbfusion?

Thanks~

ERROR: No metrics available, please compile with PYOPENVDB_SUPPORT

Thank you for sharing your great work!
VDBFusion is work well, but i have some problem..

I'm having a hard time building vdbfusion with pyopenvdb.
I just follow this instructions on my M2 mac with conda.
And get this message : No metrics available, please compile with PYOPENVDB_SUPPORT.

Is there any idea?

ROS Integration example

Hi,

I'm currently looking at integrating this algorithm to our ROS based robot software stack. Our robot is equipped with a LiDAR, a RealSense D435i and encoders. We're currently using the gmapping SLAM algorithm to provide the transform from the /map frame to the /realsense_depth_optical_frame.

I was wondering if you managed to integrate this library with ROS in the past and if you have pointers on how to integrate it with our robot?

Thanks!
Alex

cmake does not produce "install" target if eigen is newer than 3.4.0

Hi Nacho,

I'd been trying to follow the "Using system installed 3rdparty libraries" and ran into problems in several build environments.

Initially I was using a Ubuntu 18.04 VM which didn't have sufficiently new packages to build OpenVDB 10, so I had to install from source. This eventually worked after a bunch of trial and error, but I'd forgotten the exact steps I took.

More recently I switched to a Debian 10 machine and encountered a similar set of problems. I was trying to follow the instructions mentioned here and kept encountering an issue where cmake in vdbfusion/build would succeed, but the following would occur when trying to call make:

$ make -j4
Scanning dependencies of target external_eigen
Scanning dependencies of target vdbfusion
[ 9%] Creating directories for 'external_eigen'
[ 27%] Building CXX object src/vdbfusion/vdbfusion/CMakeFiles/vdbfusion.dir/MarchingCubes.cpp.o
[ 27%] Building CXX object src/vdbfusion/vdbfusion/CMakeFiles/vdbfusion.dir/VDBVolume.cpp.o
[ 36%] Linking CXX static library libvdbfusion.a
[ 45%] Performing download step (download, verify and extract) for 'external_eigen'
-- Downloading...
dst='/mathworks/devel/sandbox/cstabile/Prototype/PROTOTYPE/R2023b/sdf3D/vdbFusion/vdbfusion/build/eigen/src/eigen-3.4.0.tar.bz2'
timeout='none'
-- Using src='https://gitlab.com/libeigen/eigen/-/archive/3.4.0/eigen-3.4.0.tar.bz2'
[ 45%] Built target vdbfusion
-- verifying file...
file='/mathworks/devel/sandbox/cstabile/Prototype/PROTOTYPE/R2023b/sdf3D/vdbFusion/vdbfusion/build/eigen/src/eigen-3.4.0.tar.bz2'
-- Downloading... done
-- extracting...
src='/mathworks/devel/sandbox/cstabile/Prototype/PROTOTYPE/R2023b/sdf3D/vdbFusion/vdbfusion/build/eigen/src/eigen-3.4.0.tar.bz2
>dst='/mathworks/devel/sandbox/cstabile/Prototype/PROTOTYPE/R2023b/sdf3D/vdbFusion/vdbfusion/build/eigen/src/external_eigen'
-- extracting... [tar xfz]
-- extracting... [analysis]
-- extracting... [rename]
-- extracting... [clean up]
-- extracting... done
[ 54%] No update step for 'external_eigen'
[ 63%] No patch step for 'external_eigen'
[ 72%] No configure step for 'external_eigen'
[ 81%] No build step for 'external_eigen'
[ 90%] No install step for 'external_eigen'
[100%] Completed 'external_eigen'
[100%] Built target external_eigen
[cstabile@ah-qemachine1-l:/mathworks/devel/sandbox/cstabile/Prototype/PROTOTYPE/R2023b/sdf3D/vdbFusion/vdbfusion/build] ...
$ make install
make: *** No rule to make target 'install'. Stop.

At this point I had already built OpenVDB 10 from source and installed all of the packages mentioned with your command.

It turned out that the latest version of eigen I could get from apt-get is 3.3.9-2, so I ended up installing 3.4.9 from the repo, thinking that the newest version would be safest, but it resulted in the same behavior described above when I call make.

I think you should be able to reproduce this behavior with the following:

Try to install packages (this might be insufficient on older versions of Ubuntu/Debian, I believe I needed to install some from source)

sudo apt-get update && sudo apt-get install --no-install-recommends -y libblosc-dev libboost-iostreams-dev libboost-dev numpy-dev libboost-python-dev libboost-system-dev libeigen3-dev libtbb-dev

Manually install OpenVDB from source

git clone https://github.com/AcademySoftwareFoundation/openvdb.git
mkdir -p openvdb/build; cd openvdb/build; cmake ..; sudo make -j${nproc} install; cd ../..;

Manually install newest version of Eigen (3.4.9)

git clone https://gitlab.com/libeigen/eigen.git
mkdir -p eigen/build; cd eigen/build; cmake ..; sudo make -j${nproc} install; cd ../..;

pkg-config --modversion eigen3 # This should report 3.4.9 or newer

Attempt to install vdbFusion

git clone https://github.com/PRBonn/vdbfusion.git
mkdir -p vdbfusion/build; cd vdbfusion/build;
cmake .. #This works fine
make j${nproc} # This works, but attempts to download eigen 3.4.0 (no error message)
make install # This fails saying there's no "install" target

Assuming you can reproduce this on your end, the workaround is to enter into the downloaded eigen directory and build THAT from source:

Build the downloaded source repo

cd eigen/src/external_eigen;
mkdir build; cd build; cmake ..; sudo make -j${nproc} install; cd ../../../..;

pkg-config --modversion eigen3 # Should now show 3.4.0

Build vdbFusion (this should now work)

sudo make install

I'm not sure whether this restriction was intentional, but it was difficult to determine what was going on behind the scenes (I'm fairly clueless when it comes to build systems so I have no idea what's triggering the behavior). It would be good to indicate why the install target wasn't generated (a biproduct of the build thinking it didn't have the right version?), but in the meantime hopefully this can help someone else if they run into a similar issue in the future.

Thanks in advance!

sporadic "free(): invalid pointer Aborted (core dumped)" when creating VDBVolume

I am getting the (sporadic but persistent) error:

free(): invalid pointer
Aborted (core dumped)

when creating a VDBVolume, using

vdb_volume = vdbfusion.VDBVolume(voxel_size, sdf_trunc)

From what I can tell from debugging, the volume is created in VDBVolume.cpp in the code block below, and this code runs fine, however nothing else is called and the error still occurs afterwards.

VDBVolume::VDBVolume(float voxel_size, float sdf_trunc, bool space_carving /* = false*/)
    : voxel_size_(voxel_size), sdf_trunc_(sdf_trunc), space_carving_(space_carving) {
    std::cout << "VDBVolume constructor" << std::endl;
    tsdf_ = openvdb::FloatGrid::create(sdf_trunc_);
    std::cout << "VDBVolume constructor: Float Grid Created" << std::endl;
    tsdf_->setName("D(x): signed distance grid");
    tsdf_->setTransform(openvdb::math::Transform::createLinearTransform(voxel_size_));
    tsdf_->setGridClass(openvdb::GRID_LEVEL_SET);
    std::cout << "VDBVolume constructor: Set TSDF properties" << std::endl;
    weights_ = openvdb::FloatGrid::create(0.0f);
    weights_->setName("W(x): weights grid");
    weights_->setTransform(openvdb::math::Transform::createLinearTransform(voxel_size_));
    weights_->setGridClass(openvdb::GRID_UNKNOWN);
    std::cout << "VDBVolume constructor: Set weights" << std::endl;
}

To recreate:
Build vdbfusion from source as per README.md.
Run Python script

import vdbfusion
vdbfusion.VDBVolume(1,1)

Realtime Point Cloud extraction

Introduction

For real-time applications, it is very useful to visualize the volume, for instance for debugging. This can be done currently by using marching cubles which generates a mesh. The problem is that generating meshes is very computationally expensive, unless recent commits to OpenVSB make it fast and high-quality enough. This implies, the volume currently cannot be displayed in real time.

Besides, to do ICP to correct TFs/Frames, which is necessary to do real-time, it'd be necessary to have cloudpoints in realtime, which, as said, it is not currently possible. Note that to correct errors that occur during integration ( for instance "Lady and Cow" ), ICP would potentially help. Also note, this is used in Voxblox

Note that Open3D, in its tensor SLAM pipeline, does implement this and does work realtime ( example )

Proposed Work

1 - Test whether recent changes in OpenVDB make generation of meshes quality and speed wise good enough. Also analyze different MeshToVolumeFlags
2 - In case point (1) does not hold true, then implement either in OpenVDB or in vdbfusion a way to quickly extract pointclouds ( maybe optionally with normals) in realtime.

Questions

I'd like to know.
1- Generally what's your opinion/POV regarind this line of work in terms of utility, feasabliitty etc.
2- Whether that's something you have planned to do or will do
3- Whether you need extra help with that.

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.