[Documentation] [TitleIndex] [WordIndex

API review

Proposer: Chad Rockey

Present at review:

Suggested Solutions

Current planar laser scanners have outgrown the current sensor_msgs/LaserScan message. New technology allows the lasers to return multiple distances for each pulse emitted. This multi-echo technology is present on lasers such as Sick's LMS151 and LMS511 as well as Hokuyo's UTM-30LX-EW. These lasers output 2, 5, and 3 returns respectively. The discussion of this review should serve as a REP if the sensor_msgs/LaserScan message is to remain unchanged or as the review for a new message if that is decided as the best course of action.

If anyone has an alternate method not described below, please feel free to add it to the list.

Method 1: Multiple topics using sensor_msgs/LaserScan

This method was used in evaluation of the UTM-30LX-EW. The example implementation can be found here: http://code.google.com/p/urgwidget-wrapper/source/browse/urgwidget_driver/urgwidget_wrapper/ros_src/urg_node.cpp

This approach would require a REP as it expands the stated API of sensor_msgs/LaserScan within the ROS ecosystem. N full sensor_msgs/LaserScan would be published on multiple topics. These scans would require identical header timestamps and frame_ids so that easy recombination could be performed through message_filters exact_sync. The topics would be similar to the following:

/laser/scan
/laser/echo1
/laser/echo2
/laser/echo3

Advantages

Disadvantages

Method 2: Space efficient multi-echo message

This method would add a new multi-echo message that could be translated back into the older message. The new message should only send the amount of data required. This proposed message sends an array of arrays for ranges and intensity. The outer array represents the angle_increment as in sensor_msgs/LaserScan, but the inner array is sized according to the number of echos for that angle_increment. There is no requirement for all inner arrays to be the same size. However, if present, the intensity outer array size must be equal to the range outer array size and each inner array must be the same size as the corresponding range inner array. Notify the reviewers if a laser violates this assumption. The following is for example only, please feel free to suggest a better message.

MultiEchoLaserScan.msg

# Single scan from a multi-echo planar laser range-finder
#
# If you have another ranging device with different behavior (e.g. a sonar
# array), please find or create a different message, since applications
# will make fairly laser-specific assumptions about this data

Header header            # timestamp in the header is the acquisition time of 
                         # the first ray in the scan.
                         #
                         # in frame frame_id, angles are measured around 
                         # the positive Z axis (counterclockwise, if Z is up)
                         # with zero angle being forward along the x axis
                         
float32 angle_min        # start angle of the scan [rad]
float32 angle_max        # end angle of the scan [rad]
float32 angle_increment  # angular distance between measurements [rad]

float32 time_increment   # time between measurements [seconds] - if your scanner
                         # is moving, this will be used in interpolating position
                         # of 3d points
float32 scan_time        # time between scans [seconds]

float32 range_min        # minimum range value [m]
float32 range_max        # maximum range value [m]

LaserEcho[] ranges       # range data [m] (Note: NaNs, values < range_min or > range_max should be discarded)  +Inf measurements are out of range, -Inf measurements are too close to determine exact distance.
LaserEcho[] intensities  # intensity data [device-specific units].  If your
                         # device does not provide intensities, please leave
                         # the array empty.

LaserEcho.msg

float32[] echoes  # Multiple values of ranges or intensities. Each array represents data from the same angle increment.

Advantages

Disadvantages

Method 3: Encode first return differently

This approach would keep the existing message for the first returns but add an additional topic and message for echoes. If only the last (furthest) returns are desired, the two topics could be combined into a different sensor_msgs/LaserScan by an external node. The topic structure would be similar to the following:

/laser/scan     sensor_msgs/LaserScan
/laser/echoes   MultiEchoLaserScan

Advantages

Disadvantages

Method 4: Use sensor_msgs/PointCloud2

This approach would skip directly to sensor_msgs/PointCloud2 for representing multiple points.

Advantages

Disadvantages

Method 5: Driver deals with multiecho

This method would have different policies to treat multiecho data and would publish a single sensor_msgs/LaserScan as the driver does at the moment. Policies could be, choose the maximum, the minimum, the first value... The user would be able to choose it.

Advantages

Disadvantages

Question / concerns / comments

Meeting agenda

Create a new message in the format of MultiEchoLaserScan that will contain every return from a multi-echo scanner. This will be the base structure for each return. It should default publish to the 'echoes' topic. It will also be the supported message for full multi-echo communication and visualization.

For backwards compatibility, I will create (and we will review) a C++ class and ROS node/nodelet (in the vein of image_transport and image_proc) that supports the following:

Conclusion

Package status change mark change manifest)



2023-10-28 13:04