Struct DepthImageInputHandlerConfig

Inheritance Relationships

Base Type

Struct Documentation

struct DepthImageInputHandlerConfig : public wavemap::ConfigBase<DepthImageInputHandlerConfig, 10>

Config struct for the depth image input handler.

Public Functions

inline operator InputHandlerConfig() const
virtual bool isValid(bool verbose) const override

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.

Public Static Attributes

static MemberMap memberMap