Inputs

The settings in the config’s inputs section are used to add measurement inputs to wavemap, similar to dataloaders in a machine learning framework. The expected format is a YAML list, where each item corresponds to a separate measurement input handler.

C++ Library

We believe that input handlers for standard datasets like KITTI, Redwood, 3DMatch, Replica, and others would be valuable additions to wavemap’s C++ library. However, these have not been implemented yet. If you’re interested in contributing, please reach out to us here.

ROS1 Interface

Each input subscribes to a measurement ROS topic, retrieves the pose for each received measurement using TF2, and then calls the integrators specified under measurement_integrator_names to add the measurement to the map.

Pointcloud input handler

Selected by setting inputs[i]/type to "pointcloud_topic".

The remaining settings are available under inputs[i] will then be:

struct PointcloudTopicInputConfig : public ConfigBase<PointcloudTopicInputConfig, 12, PointcloudTopicType, StringList>

Config struct for the pointcloud input handler.

Public Members

std::string topic_name

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.

StringList measurement_integrator_names

Name(s) of the measurement integrator(s) used to integrate the measurements into the map.

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 projected_range_image_topic_name

Name of the topic on which to publish the range image generated from the pointclouds.

Useful for debugging, to see how well the projection model matches the LiDAR. Disabled if not set.

std::string undistorted_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.

Depth image input handler

Selected by setting inputs[i]/type to "depth_image_topic".

The remaining settings are available under inputs[i] will then be:

struct DepthImageTopicInputConfig : public ConfigBase<DepthImageTopicInputConfig, 10, StringList>

Config struct for the depth image input handler.

Public Members

std::string topic_name

Name of the ROS topic to subscribe to.

int topic_queue_length = 10

Queue length to use when subscribing to the ROS topic.

StringList measurement_integrator_names

Name(s) of the measurement integrator(s) used to integrate the measurements into the map.

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 projected_pointcloud_topic_name

Name of the topic on which to publish the depth images as pointclouds.

Useful to share the pointclouds with other ROS nodes and for debugging. Disabled if not set.