Parameters
Wavemap’s configuration system is designed to be flexible and expressive. Let’s start with an example to illustrate the overall structure:
general:
world_frame: "odom"
logging_level: debug
allow_reset_map_service: true
map:
type: hashed_chunked_wavelet_octree
min_cell_width: { meters: 0.1 }
map_operations:
- type: threshold_map
once_every: { seconds: 2.0 }
- type: prune_map
once_every: { seconds: 10.0 }
- type: publish_map
once_every: { seconds: 2.0 }
measurement_integrators:
ouster_os0:
projection_model:
type: ouster_projector
lidar_origin_to_beam_origin: { millimeters: 27.67 }
lidar_origin_to_sensor_origin_z_offset: { millimeters: 36.18 }
elevation:
num_cells: 128
min_angle: { degrees: -45.73 }
max_angle: { degrees: 46.27 }
azimuth:
num_cells: 1024
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:
- type: pointcloud_topic
topic_name: "/os_cloud_node/points"
topic_type: ouster
measurement_integrator_names: ouster_os0
undistort_motion: true
topic_queue_length: 10
max_wait_for_pose: { seconds: 1.0 }
The framework’s general settings, such as its logging_level (verbosity) and the coordinate frame in which the map is represented, are configured under general
.
The data structure used to store the volumetric map is configured under map
.
Next, a list of map_operations
can be specified that are called after each map update – possibly throttled to happen at most once every n seconds, for efficiency.
The last two sections control how new measurements are added to the map. The inputs
param allows you to specify a list of inputs which take care of receiving depth measurements and looking up their poses, before forwarding them to measurement integrators defined in the measurement_integrator
dictionary. In the above example, we create a single input of type: pointcloud_topic
which subscribes to a pointcloud topic in ROS, looks up the pose of each measurement using ROS’ TF2 and then forwards it to a measurement integrator we named ouster_os0.
You might have noticed two peculiarities in wavemap’s configs.
The first is that subsections often contain a type tag. This tag determines the type of the object that should be created for the corresponding element. For example, setting map/type: hashed_chunked_wavelet_octree
tells wavemap to create a HashedChunkedWaveletOctree data structure to store the map.
The second is that units are specified explicitly. This eliminates misunderstandings and enables automatic conversions from derived units, such as { millimeters: 27.67 }
or { degrees: 180.0 }
, to SI base units, such as { meters: 0.02767 }
or { radians: 3.14159 }
. Wavemap’s code internally always operates in SI base units.
Tip
Wavemap’s ROS server prints warnings for all unrecognized params at startup. This can be helpful for debugging and to quickly find typos in config param names.
To get started quickly, we recommend skimming through these example configs. For reference, an overview of all available config options is provided below.