Class DepthImageToLaserScan

Class Documentation

class DepthImageToLaserScan

Public Functions

explicit DepthImageToLaserScan(float scan_time, float range_min, float range_max, int scan_height, const std::string &frame_id)

Constructor.

Parameters:
  • scan_time – The value to use for outgoing sensor_msgs::msg::LaserScan. In sensor_msgs::msg::LaserScan, scan_time is defined as “time between scans [seconds]”. This value is not easily calculated from consecutive messages, and is thus left to the user to set correctly.

  • range_min – The minimum range for the sensor_msgs::msg::LaserScan. This is used to determine how close of a value to allow through when multiple radii correspond to the same angular increment.

  • range_max – The maximum range for the sensor_msgs::msg::LaserScan. This is used to set the output message.

  • scan_height – The number of rows (pixels) to use in the output. This will provide scan_height number of radii for each angular increment. The output scan will output the closest radius that is still not smaller than range_min. This can be used to vertically compress obstacles into a single LaserScan.

  • frame_id – The output frame_id for the LaserScan. This will probably NOT be the same frame_id as the depth image. Example: For OpenNI cameras, this should be set to ‘camera_depth_frame’ while the camera uses ‘camera_depth_optical_frame’.

~DepthImageToLaserScan()
sensor_msgs::msg::LaserScan::UniquePtr convert_msg(const sensor_msgs::msg::Image::ConstSharedPtr &depth_msg, const sensor_msgs::msg::CameraInfo::ConstSharedPtr &info_msg)

Converts the information in a depth image (sensor_msgs::Image) to a sensor_msgs::LaserScan.

This function converts the information in the depth encoded image (UInt16 or Float32 encoding) into a sensor_msgs::msg::LaserScan as accurately as possible. To do this, it requires the synchronized Image/CameraInfo pair associated with the image.

Parameters:
  • depth_msg – UInt16 or Float32 encoded depth image.

  • info_msg – CameraInfo associated with depth_msg

Returns:

sensor_msgs::msg::LaserScan::SharedPtr for the center row(s) of the depth image.