ethz-asl / wavemap

Fast, efficient and accurate multi-resolution, multi-sensor 3D occupancy mapping
https://ethz-asl.github.io/wavemap/
BSD 3-Clause "New" or "Revised" License
425 stars 37 forks source link

Very sparse occupancy map #74

Closed sverrevr closed 2 days ago

sverrevr commented 4 days ago

Question Hi! Im trying out wavemap on our drone using an ouster OS0-64 lidar. First of I want to thank you for making it so simple to set up. But one problem I am having which I was unable to find any documentation on is why my resulting point-cloud is so sparse, se the following picture:

image

The map seems to fill out if I move the drone, but I need it to fill out also when standing still.

Note that in the config (see below) we changed from using outer projection_model to spherical_projector, as the ouster driver is already de staggering the point cloud. Is this correct? Furthermore, what are the elevation and azimuth used for? Id think the point cloud information would be enough?

Runtime information: Please fill out these questions in case a specific dataset or sensor setup is relevant to your question.


- Config file:

general: world_frame: "map" logging_level: debug allow_reset_map_service: true

map: type: hashed_chunked_wavelet_octree min_cell_width: { meters: 0.1 }

Her kan man spesifisere min og max log odds

map_operations:

measurement_integrators: ouster_os0: # kan fritt velges, skal henge sammen med "measurement_integrator_names" i inputs projection_model: type: spherical_projector elevation: num_cells: 64 min_angle: { degrees: -45.73 } max_angle: { degrees: 46.27 } azimuth: num_cells: 512 min_angle: { degrees: -180.0 } max_angle: { degrees: 180.0 } measurement_model: type: continuous_beam angle_sigma: { degrees: 0.035 }

NOTE: For best results, we recommend setting range_sigma to

  #       max(min_cell_width / 2, ouster_noise) where ouster_noise = 0.05
  range_sigma: { meters: 0.05 }
  scaling_free: 0.2
  scaling_occupied: 0.4
integration_method:
  type: hashed_chunked_wavelet_integrator
  min_range: { meters: 1.0 }
  max_range: { meters: 15.0 }

inputs:



- Dataset name [e.g. Newer College Cloister sequence]: Online use
- Custom setup:                                        # For online use or personal datasets
    - depth sensor: Ouster OS0-64
    - pose source: From custom SLAM algorithm 

**System information:**
Please fill out these questions in case your hardware is relevant to your question. For example, if you would like help to tune wavemap's performance on your robot.

- CPU: N/A
- GPU: N/A
- RAM: N/A
- OS: Ubuntu 22, Ros noetic
- Wavemap
    - install: Native
    - version: 2.0.1
victorreijgwart commented 4 days ago

Hi @sverrevr,

Thank you for your question and the detailed explanation, including screenshots! The reason wavemap needs to (roughly) know your sensor's projection model is because it stores the input pointcloud in a look-up table that's organized like a range image (with one 3D ray per pixel). This allows wavemap's integrator to leverage projective integration, which is generally faster and more efficient than ray tracing. As opposed to regular projective integrators, which only store a single range value per pixel, we store a full 3D ray to be less sensitive to calibration errors in the projection model and to work better with undistorted or disorganized (e.g. Livox) pointclouds. It also allows the continuous_beam measurement model to consider exact beam angles when updating each voxel, which improves the reconstruction of thin objects (more info here).

Which beam configuration does your OS0-64 have (e.g. uniform, gradient, tight, ...)? And in what lidar_mode are you running it (e.g. 1024x10, 512x20, ...)? You could also increase angle_sigma, for example to 0.08, to make each LiDAR beam a bit thicker. This improves infilling, especially for LiDARs with fewer beams or when the robot is standing still.

sverrevr commented 4 days ago

Hi Victor, thanks a lot for the response. After reading these two comments from you 1, 2 together with your reply now I started to understand how this is working.

Would you say that this interpretaion is correct? :) A problem when using occupancy voxels is that if an obstacle is much thinner than a voxel, there there will be many more LIDAR beams that traverse through the voxel than reflect innside it. This makes the voxel conventionally evaluate to empty, even though there is something there and we detected it. To handle this, when using "continuous_beam" measurement model, wavemap will not consider all LIDAR beams that go through the voxel, only those close enough to the center of the voxel. Close enough is defined as 6*beam width at that distance, which should be 6*tan(angle_sigma). So for a wall perpendicular to the lidar beam direction if the angle_sigma = angle_between_beams/6 then there should be no holes.

I think this sounds like a smart solution as when the drone moves around it will fill potential holes.

We are using the lidar in 512x10 mode. Setting the angle_sigma to 0.70.07 made the holes few enough to not be a problem.

image

victorreijgwart commented 4 days ago

Yes, exactly :) Did you mean 0.07 instead of 0.7? Theoretically, an angle_sigma = 90 deg / (2 * 6 * (64 - 1)) ~= 0.12 deg should be enough to avoid all holes. In practice, I'd set it slightly lower to keep the map more crisp. Using thick beams tends to smear the map a bit, as the beams inflate obstacles that they hit while also carving away the borders of obstacles they graze past.

sverrevr commented 4 days ago

Yes, i meant 0.07 :)

But what happens with obstacles thinner than a voxel, if they do not alight with the voxel center, then they would never be detected will they?

victorreijgwart commented 4 days ago

Yes, that's right. Most occupancy/TSDF mapping frameworks cannot represent obstacles thinner than one voxel. With any discretization, there's always a fundamental trade-off between the chosen approximation order (e.g. constant, linear, or higher-order functions) and resolution (or, more generally, the number of coefficients/weights/params). Higher-order approximations can represent details with sub-voxel accuracy, but they also increase the cost of storing and updating each voxel and performing inference. More extreme examples are Hilbert Maps, GPOMs, and NeRFs, which can create non-voxelized, continuous maps but are generally expensive. Instead of aiming for higher-order approximation, wavemap opts for very high computational efficiency and the flexibility of multi-resolution. For a given computational budget, it can therefore map at a higher resolution, which in turn yields high recall and accuracy :)

sverrevr commented 2 days ago

Makes sense :) Thanks for the help!

victorreijgwart commented 1 day ago

Welcome!