Inputs
These settings control the measurement input handlers.
They are nested in the top level config under inputs
. Note that inputs
takes a YAML list, and one input handler will be created for each item in the list.
Each input subscribes to a measurement ROS topic, looks up the pose for each measurement, and then calls its integrators to integrate the measurement into the map. We cover the measurement input handler types and their general settings first, followed by the integrator settings.
Input handlers
Pointcloud input handler
Selected by setting inputs[i]/type: "pointcloud"
.
The settings are available under inputs[i]/general
are:
-
struct PointcloudInputHandlerConfig : public wavemap::ConfigBase<PointcloudInputHandlerConfig, 11, PointcloudTopicType>
Config struct for the pointcloud input handler.
Public Members
-
std::string topic_name = "scan"
Name of the ROS topic to subscribe to.
-
PointcloudTopicType topic_type = PointcloudTopicType::kPointCloud2
Message type of the ROS topic to subscribe to.
-
int topic_queue_length = 10
Queue length to use when subscribing to the ROS topic.
-
Seconds<FloatingPoint> processing_retry_period = 0.05f
Time period used to control the rate at which to retry getting the sensor pose when ROS TF lookups fail.
-
Seconds<FloatingPoint> max_wait_for_pose = 1.f
Maximum amount of time to wait for the sensor pose to become available.
-
std::string sensor_frame_id
The frame_id to use to look up the sensor pose using ROS TFs.
Note that setting this is optional, when left blank the header.frame_id of the measurement’s msg is used.
-
Seconds<FloatingPoint> time_offset = 0.f
Time offset to apply to the header.stamp of the measurement’s msg when looking up its pose using ROS TFs.
Can be used when the time offset is known (e.g. through calibration) but not corrected by the sensor’s driver.
-
bool undistort_motion = false
Whether to undistort each pointcloud based on the sensor’s motion while it was captured.
We strongly recommend turning this on, unless the robot’s odometry is very jerky or the sensor’s driver already performs motion undistortion.
-
int num_undistortion_interpolation_intervals_per_cloud = 100
Number of intermediate poses to sample from ROS TFs when performing motion undistortion.
-
std::string reprojected_pointcloud_topic_name
Name of the topic on which to republish the motion-undistorted pointclouds.
Useful to share the undistorted pointclouds with other ROS nodes and for debugging. Disabled if not set.
-
std::string projected_range_image_topic_name
Name of the topic on which to republish the range image computed from the pointclouds.
Useful for debugging, to see how well the projection model matches the LiDAR. Disabled if not set.
-
std::string topic_name = "scan"
Depth image input handler
Selected by setting inputs[i]/type: "depth_image"
.
The settings are available under inputs[i]/general
are:
-
struct DepthImageInputHandlerConfig : public wavemap::ConfigBase<DepthImageInputHandlerConfig, 10>
Config struct for the depth image input handler.
Public Members
-
std::string topic_name = "scan"
Name of the ROS topic to subscribe to.
-
int topic_queue_length = 10
Queue length to use when subscribing to the ROS topic.
-
Seconds<FloatingPoint> processing_retry_period = 0.05f
Time period used to control the rate at which to retry getting the sensor pose when ROS TF lookups fail.
-
Seconds<FloatingPoint> max_wait_for_pose = 1.f
Maximum amount of time to wait for the sensor pose to become available when ROS TF lookups fail.
-
std::string sensor_frame_id
The frame_id to use to look up the sensor pose using ROS TFs.
Note that setting this is optional, when left blank the header.frame_id of the measurement’s msg is used.
-
std::string image_transport_hints = "raw"
Custom image_transport::TransportHints to use when subscribing to the depth image topic.
Defaults to ‘raw’. For more info, see http://wiki.ros.org/image_transport.
-
FloatingPoint depth_scale_factor = 1.f
Scale factor used to convert the depth image’s values to meters.
-
Seconds<FloatingPoint> time_offset = 0.f
Time offset to apply to the header.stamp of the measurement’s msg when looking up its pose using ROS TFs.
Can be used when the time offset is known (e.g. through calibration) but not corrected by the sensor’s driver.
-
std::string reprojected_pointcloud_topic_name
Name of the topic on which to republish the depth images as pointclouds.
Useful to share the pointclouds with other ROS nodes and for debugging. Disabled if not set.
-
std::string projected_range_image_topic_name
Name of the topic on which to republish the range image computed from the pointclouds.
Useful for debugging. Disabled if not set.
-
std::string topic_name = "scan"
Measurement integrators
These settings specify which integrators will be applied whenever the input they belong to receives a new measurement. In similar fashion to the inputs
key, inputs[i]/integrators
takes a YAML list, and one integrator will be created for each item in the list. In most cases, a single integrator will suffice. However, the option of specifying multiple integrators can, for example, be used to integrate a given input at a very high resolution close to the robot (e.g. 1 to 3m) with one integrator, and at a lower resolution over a long range (e.g. 3 to 30m) with another integrator.
For each integrator, you need to specify the integration_method
, projection_model
and measurement_model
.
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 inputs[i]/integrators[j]/integration_method
.
Compatible map data structure and integration method types:
Data structure |
Integration method |
---|---|
|
|
|
|
|
|
They 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.
-
NdtreeIndexElement termination_height = 0
Maximum resolution to use for this integrator, set as the height at which to terminate the coarse-to-fine measurement updates.
Defaults to 0 (max res). Can be set to 1 for 1/2 of the max resolution, to 2 for 1/4 of the max resolution, etc.This can be used to fuse multiple inputs with different maximum resolutions into a single map.
-
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.
-
Meters<FloatingPoint> min_range = 0.5f
Projection models
These settings control the projection model that is used to convert cartesian coordinates to/from sensor coordinates.
They are nested in the top level config under inputs[i]/integrators[j]/projection_model
.
Spherical projection model
Selected by setting inputs[i]/integrators[j]/projection_model/type: '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 inputs[i]/integrators[j]/projection_model
are:
-
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.
-
CircularProjectorConfig elevation
Ouster LiDAR projection model
Selected by setting inputs[i]/integrators[j]/projection_model/type: '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 inputs[i]/integrators[j]/projection_model
are:
-
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.
-
CircularProjectorConfig elevation
Pinhole camera projection model
Selected by setting inputs[i]/integrators[j]/projection_model/type: 'pinhole_camera_projector'
.
This projection model is appropriate for most depth cameras.
The remaining settings available under inputs[i]/integrators[j]/projection_model
are:
-
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.
-
IndexElement width = 0
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 inputs[i]/integrators[j]/measurement_model
.
Continuous ray measurement model
Selected by setting inputs[i]/integrators[j]/measurement_model/type: '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 inputs[i]/integrators[j]/measurement_model
are:
-
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.
-
Meters<FloatingPoint> range_sigma = 0.f
Continuous beam measurement model
Selected by setting inputs[i]/integrators[j]/measurement_model/type: '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 inputs[i]/integrators[j]/measurement_model
are:
-
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.
-
Radians<FloatingPoint> angle_sigma = 0.f