fzi-forschungszentrum-informatik / vdb_mapping

Performantes 3D Kartierungs-Framework auf Basis von OpenVDB
Apache License 2.0
41 stars 10 forks source link

Framework performance in comparison to OctoMap #4

Closed jonasherzfeld closed 2 years ago

jonasherzfeld commented 2 years ago

Hi,

I have a question regarding the expected performance of the framework. I do not seem to be able to replicate the impressive performance that has been shown in the paper, as in in my tests the point cloud insertion tends to take considerably longer than for example the OctoMap framwork on the same data. Maybe you could help me understand where I am making a mistake here with the data insertion or representation.

I am running the follwing code

vdb_mapping::OccupancyVDBMapping map(0.025);
vdb_mapping::Config conf;
conf.max_range      = 10.0;
conf.prob_hit       = 0.9;
conf.prob_miss      = 0.1;
conf.prob_thres_max = 0.51;
conf.prob_thres_min = 0.49;
map.setConfig(conf);

vdb_mapping::OccupancyVDBMapping::PointCloudT::Ptr cloud(new vdb_mapping::OccupancyVDBMapping::PointCloudT);
vdb_mapping::OccupancyVDBMapping::PointCloudT::Ptr cloud_trans(new vdb_mapping::OccupancyVDBMapping::PointCloudT);
Eigen::Matrix<double, 3, 1> origin(0, 0, 0);

int i = 1;
while(file >> row)
{
    pcl_file = path + "pcl/scan_" + std::to_string(i) + ".pcd";
    if (pcl::io::loadPCDFile<pcl::PointXYZ>(pcl_file, *cloud) == -1)
    {
        PCL_ERROR ("Couldn't read scan file %d \n", i);
        return(-1);
    }

    ret = loadPosData(origin, rotation, row);
    if (ret)
    {
        PCL_ERROR ("Couldn't read line %d from pos.csv\n", i);
        return(-1);
    }

    getTransMatrix3d(tm, origin, rotation);
    pcl::transformPointCloud (*cloud, *cloud_trans, tm);

    map.insertPointCloud(cloud_trans, origin);
    i++;
}

I ran a comparison on the same data with around 23.000 points per scan and got the following point cloud insertion times respectively on map.insertPointCloud(cloud_trans, origin); and oc_tree->insertPointCloud(*oc_cloud, origin, 10.0); with a resolution of 0.1m. Insertion time with VDBMapping: image

Insertion time with OctoMap: image

Both resulting maps look good, and correct so I dont think that it is a general flaw in the data. Do you have an idea where I can tune this to improve the performance or if there are things that affect performance considerably in terms of data representation?

MGBla commented 2 years ago

Hi Jonas, that seems weirdly slow. Do you have build your node in Release oder Debug mode? Running it in Debug would hugely impair the performance of the mapping. Otherwise could you send me your pcd data than I can have a deeper look into it.

jonasherzfeld commented 2 years ago

Hi Marvin, Thanks for the fast reply, that solved my problem. Now it performs as fast as expected! Best regards, Jonas