Measurement integrators

The settings in the config’s measurement_integrators section are used to add measurement integrators to wavemap. The expected format is a YAML dictionary, where each item represents a separate measurement integrator. The item’s key defines the integrator’s name, while its value specifies the integrator’s settings. Note that the integrator’s name can be chosen freely. It will later be used in the inputs section to direct measurements to specific integrators.

In most cases, a single integrator per sensor type is sufficient. However, the system also allows you to forward a single input to multiple integrators. This can be useful, for example, to integrate data at a very high resolution close to the robot (e.g., 1 to 3 meters) with one integrator, while using another integrator for lower resolution updates over a longer range (e.g., 3 to 30 meters).

For each integrator, you need to specify the projection_model, measurement_model and integration_method.

Projection models

These settings control the projection model that is used to convert coordinates in the sensor’s frame to/from cartesian coordinates. They are nested in the top level config under measurement_integrators["your_integrator"]/projection_model.

Spherical projection model

Selected by setting projection_model/type to 'spherical_projector'.

This projection model is appropriate for most LiDARs, including Velodynes. It also works with dome LiDARs such as the Robosense RS-Bpearl.

The remaining settings available under projection_model will then be:

struct SphericalProjectorConfig : public wavemap::ConfigBase<SphericalProjectorConfig, 2, CircularProjectorConfig>

Config struct for the spherical projection model.

Public Members

CircularProjectorConfig elevation

Properties of the projection model along the elevation axis.

CircularProjectorConfig azimuth

Properties of the projection model along the azimuth axis.

Ouster LiDAR projection model

Selected by setting projection_model/type to 'ouster_projector'.

This projection model improves the reconstruction accuracy for Ouster based LiDARs including the OS0 and OS1, by taking their staggered beam pattern into account.

The remaining settings available under projection_model will then be:

struct OusterProjectorConfig : public wavemap::ConfigBase<OusterProjectorConfig, 4, CircularProjectorConfig>

Config struct for the ouster LiDAR projection model.

Public Members

CircularProjectorConfig elevation

Properties of the projection model along the elevation axis.

CircularProjectorConfig azimuth

Properties of the projection model along the azimuth axis.

Meters<FloatingPoint> lidar_origin_to_beam_origin = 0.02767f

Offset between the Ouster LiDAR frame’s origin and the laser beam’s start point (radial direction).

For illustrations and additional information, please see the Ouster sensor’s manual.

Meters<FloatingPoint> lidar_origin_to_sensor_origin_z_offset = 0.03618f

Offset between the Ouster sensor and LiDAR frame’s origins (z-direction).

For illustrations and additional information, please see the Ouster sensor’s manual.

Pinhole camera projection model

Selected by setting projection_model/type to 'pinhole_camera_projector'.

This projection model is appropriate for most depth cameras.

The remaining settings available under projection_model will then be:

struct PinholeCameraProjectorConfig : public wavemap::ConfigBase<PinholeCameraProjectorConfig, 6>

Config struct for the pinhole camera projection model.

Public Members

IndexElement width = 0

The image’s width in pixels.

IndexElement height = 0

The image’s height in pixels.

FloatingPoint fx = 0.f

Fx according to ROS’ CameraInfo convention: http://docs.ros.org/en/melodic/api/sensor_msgs/html/msg/CameraInfo.html.

FloatingPoint fy = 0.f

Fy according to ROS’ CameraInfo convention: http://docs.ros.org/en/melodic/api/sensor_msgs/html/msg/CameraInfo.html.

FloatingPoint cx = 0.f

Cx according to ROS’ CameraInfo convention: http://docs.ros.org/en/melodic/api/sensor_msgs/html/msg/CameraInfo.html.

FloatingPoint cy = 0.f

Cy according to ROS’ CameraInfo convention: http://docs.ros.org/en/melodic/api/sensor_msgs/html/msg/CameraInfo.html.

Measurement models

These settings control the measurement model that is used to convert measurements into corresponding occupancy updates. They are nested in the top level config under measurement_integrators["your_integrator"]/measurement_model.

Continuous ray measurement model

Selected by setting measurement_model/type to 'continuous_ray'.

This measurement model accounts for uncertainty along each measured ray, but does not include angular uncertainty. It is appropriate for high density sensors with a limited range, such as most depth cameras. Considering angular uncertainty usually does not significantly improve reconstruction accuracy when the rays densely cover the entire observed volume, in which case the computational overhead is unnecessary.

The remaining settings available under measurement_model will then be:

struct ContinuousRayConfig : public wavemap::ConfigBase<ContinuousRayConfig, 4, BeamSelectorType>

Config struct for the continuous ray measurement model.

Public Members

Meters<FloatingPoint> range_sigma = 0.f

Uncertainty along the range axis.

FloatingPoint scaling_free = 0.5f

Scale factor to apply to the continuous Bayesian occupancy model for cells that are observed as free.

This can, for example, be used to give a higher weight to occupied updates than free updates.

FloatingPoint scaling_occupied = 0.5f

Scale factor to apply to the continuous Bayesian occupancy model for cells that are observed as occupied.

This can, for example, be used to give a higher weight to occupied updates than free updates.

Continuous beam measurement model

Selected by setting measurement_model/type to 'continuous_beam'.

This measurement model extends the continuous ray model, by including angular uncertainty. For LiDAR sensors, whose ray density is low at long range, it significantly improves the reconstruction quality and recall on thin objects.

The remaining settings available under measurement_model will then be:

struct ContinuousBeamConfig : public wavemap::ConfigBase<ContinuousBeamConfig, 5, BeamSelectorType>

Config struct for the continuous beam measurement model.

Public Members

Radians<FloatingPoint> angle_sigma = 0.f

Uncertainty along the angle axis.

Meters<FloatingPoint> range_sigma = 0.f

Uncertainty along the range axis.

FloatingPoint scaling_free = 0.5f

Scale factor to apply to the continuous Bayesian occupancy model for cells that are observed as free.

This can, for example, be used to give a higher weight to occupied updates than free updates.

FloatingPoint scaling_occupied = 0.5f

Scale factor to apply to the continuous Bayesian occupancy model for cells that are observed as occupied.

This can, for example, be used to give a higher weight to occupied updates than free updates.

BeamSelectorType beam_selector_type = BeamSelectorType::kAllNeighbors

Which neighboring beams to consider when computing a cell’s measurement update.

Integration method

These settings control the algorithm that is used to apply measurement updates to the map. They are nested in the top level config under measurement_integrators["your_integrator"]/integration_method.

The following map data structure and integration method types are compatible:

Data structure

Integration method

wavelet_octree

wavelet_integrator

hashed_wavelet_octree

hashed_wavelet_integrator

hashed_chunked_wavelet_octree

hashed_chunked_wavelet_integrator

The integration methods support the following settings:

struct ProjectiveIntegratorConfig : public wavemap::ConfigBase<ProjectiveIntegratorConfig, 4>

Config struct for projective integrators.

Public Members

Meters<FloatingPoint> min_range = 0.5f

Minimum range measurements should have to be considered.

Measurements below this threshold are ignored.

Meters<FloatingPoint> max_range = 20.f

Maximum range up to which to update the map.

Measurements that exceed this range are used as free-space beams, up to the maximum range.

Meters<FloatingPoint> max_update_resolution = 0.f

Maximum resolution at which to update the map.

Can be used to fuse multiple inputs with different maximum resolutions into a single map. Set to zero to match the map’s maximum resolution.

FloatingPoint termination_update_error = 0.1f

The update error threshold at which the coarse-to-fine measurement integrator is allowed to terminate, in log-odds.

For more information, please refer to: https://www.roboticsproceedings.org/rss19/p065.pdf.