ethz-asl / voxblox

A library for flexible voxel-based mapping, mainly focusing on truncated and Euclidean signed distance fields.
BSD 3-Clause "New" or "Revised" License
1.35k stars 357 forks source link

Voxel Weight for laser scan integration #220

Open maciejmatuszak opened 6 years ago

maciejmatuszak commented 6 years ago

I am trying to use voxblox (via maplab console) to integrate PointCloud2 messages generated from LaserScan messages. I am using voxblox master branch from 27/08/2018 https://github.com/ethz-asl/voxblox/tree/d75c980408270f94b396b34bc6371994cf36014b . I did not see changes to the relevant function in any of the new commits. When I run it first time no map was generated, after a bit of debugging I notice that the voxel weight is generated based on Point.z coordinate int the sensor reference frame. In the 2D scanner I use (hokuyo UST-10) the z axis is the axis of mirror rotation i.e. all points has z=0.0 The relevant code is here: https://github.com/ethz-asl/voxblox/blob/master/voxblox/src/integrator/tsdf_integrator.cc#L249 in TsdfIntegratorBase::getVoxelWeight. I did not check the paper yet but I assume the weight represent increasing uncertainty of measurement with the distance from the sensor. Once I changed the std::abs(point_C.z()) to point_C.norm() I am getting some data in the map. I am saying "some data" because I need to update the transform between laser and imu (base_link), but I assume it will work after I will do that.

Is that a bug, limitation of the framework (it uses z coordinate to speed up computation) or I am barking at the wrong tree? Do you know someone else is also playing with voxblox and laser scanner?

ZacharyTaylor commented 6 years ago

We use a voxel weighting that drops off with the square of the z value by default as this models the accuracy of stereo vision systems. When using lidars we set config_.use_const_weight to true so all points are weighted equally.

In one of the most recent changes we actually added an example launchfile that shows the system running on a lidar dataset. Here is a video of it running.

This was with a 3D lidar, however while Voxblox may be a bit less efficient iit should work with 2D scans.

maciejmatuszak commented 6 years ago

Thanks @ZacharyTaylor ! I suspected that much :). The laser distance accuracy is modelled as fix value, however those usually have constant angular accuracy which mean the error on the axis perpendicular to the ray is linear function of distance... For now I will stick to config_.use_const_weight=true; see how it goes. Thanks again for your quick response!