API review

Proposer: Chad Rockey

Present at review:

  • Eric Perko
  • Michael Ferguson
  • Jack O'Quin
  • Michael Carroll
  • Christian Dornhege
  • Dave Hershberger
  • Tully Foote

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

  • No new messages

  • No possibility of a migration

  • All existing sensor_msgs/LaserScan code is preserved

  • New RVIZ plugin not needed

Disadvantages

  • Messages published on different topics

  • Requires synchronization

  • Message filters currently limited to ~9 synchronized topics.

  • Inefficient storage (could publish many empty messages for N >> 2)

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

  • Efficient representation
  • No synchronization necessary
  • Single topic

Disadvantages

  • New message type that's incompatible with existing tools.
  • Requires laser_proc like functionality.
  • Users may want or need to migrate from sensor_msgs/LaserScan.

  • New, complicated RVIZ plugin would be needed for full visualization effect.

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

  • Efficient representation
  • Could be used with all existing tools (almost all single return lasers are 'first' return).

Disadvantages

  • Some synchronization necessary
  • New, complicated RVIZ plugin would be needed for full visualization effect.
  • Requires laser_proc like functionality.

Method 4: Use sensor_msgs/PointCloud2

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

Advantages

  • Existing representation

  • Existing and flexible visualization with additional fields for 'echo_num'.

Disadvantages

  • Missing information from the driver level since 'time_increment' is required to project a laser accurately into a fixed frame from a moving platform or robot. This would also require the driver to subscribe to tf and depend on calibrations, etc.

  • Very space inefficient representation.

  • Echos could not be colored from channels different than how the first returns are colored without adding an echo number channel.

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

  • Efficient

  • No needs synchronization

  • Single topic

  • No need to change the message type

Disadvantages

  • User can't work with separated echo data without modifying the code

  • Policies have to be decided beforehand and implemented in the driver

Question / concerns / comments

  • (Mike) A third method would be to create a new lighter-weight message specifically for the additional echoes. You could then publish the traditional LaserScan which could be used with tools supporting it, and then a second message carrying the additional data which could be used by any tools supporting it. I'd very much avoid method 2, as it is very unlikely you would ever get support for this new message in all the laser stuff out there (mapping packages, navigation, laser pipeline, etc). Further, I think you would quickly find that many people are publishing the traditional message plus the new message so that all tools work, and any efficiency gains are lost.

    • (Chad) That may be reasonable. The 90% of users case is surely a node that takes in the new formats, whatever those will be, and outputs either the first return or the last return for each angle increment.
    • (Chad) Is everyone OK with the 'traditional' scan at the driver level being only the first (shortest) returns? If we do not define this, you may see some drivers output 'last' returns instead, which would break many of the common multi-echo assumptions that any echos are further and noisier than the first return.
      • (Jack) I am mostly unfamiliar with these devices. Things I found via google search suggest that the first return may not always be the most important. For example, outdoors it may report an echo from some foliage before the echo from a building. Could there be cases where the "strongest" echo should be reported instead of the first?
        • (Chad) Absolutely. It's still an unknown and manufacturer dependent problem of which single echo is the 'best' to use at each increment.
        • (Jack) In that case, having the driver also publish a sensor_msgs/LaserScan as Christian suggested would be doubly valuable. The driver could make a device-dependent decision which to report.

  • (Christian Dornhege) What about a dual solution where LaserScan and the MultiEchoLaserScan are provided as topics by the driver? This would be used similar to e.g. the openni driver that provides images and the processed point clouds side by side. This should cover the advantages of both approaches. Users would subscribe to the topic needed for the application. Regarding the new rviz plugin for the Multi-Echo message: I think that shouldn't be that hard (although I have not written one).

    • (Michael Carroll) I agree with Christian. This would allow users to keep using existing infrastructure (rviz, nav stack, scan matching) with the current LaserScan message, but then additionally provide an upgrade path for people to use the new MultiEcho message. I've found that syncronizing multiple topics can become cumbersome, especially if you are trying to synchronize parallel topics (such as the multiple scans) as well as through time (sequentially). Additionally, it was my understanding that the multi-echoes would have less information than the original scan, depending on the environment.

      • (Chad) Would the time synchronization be easier to use if we created something like 'laser_transport'? This should not be more difficult than the existing case of synchronizing 2 pairs of images and 2 pairs of camera_info.
      • (Chad) Yes, there is much less information in the secondary + returns. For instance, I could not get the SICK 511 to output a 5th return.
      • (Jack) I would expect missing returns to be represented as quiet float NaNs, as suggested by REP-0117.

      • (Jack) Both the new message and the old LaserScan say "values < range_min or > range_max should be discarded". Doesn't REP-0117 say they should be -Infinity or +Infinity?

    • (Dave Hershberger) I agree with Christian as well. Backwards compatibility from the old topic and a nice clean solution for those wanting to use the new data. As the maintainer of RViz, I'm not concerned with the difficulty of writing a new MultiEchoLaserScanDisplay. All the math for LaserScanDisplay is currently done in laser_geometry.cpp inside package laser_geometry. That just takes a LaserScan message and generates a PointCloud or PointCloud2 message. Would be easy to add corresponding MultiEchoLaserScan message handling.

      • (Chad) The laser_geometry package will need to be updated for efficiency no matter which approach is taken. Applying the same transform to each angle_increment's echos is much more efficient than calling the transform function N times.
      • (Chad) I'm mostly concerned about the complexity of the display. I've found that it makes it much easier to use this data by treating each level of return differently. For instance, I may use axis/intensity for the first return but make the second return bright red, the third returns orange, and so on. Handling the case of arbitrary coloring of arbitrary number of echos will make for a complex interface. Method 1 expands this complexity across multiple Displays but allows for full customization by the user. In the case of SICK lasers, the effective (not actual) intensity scales are also much different for the echos than the first returns, so it's useful to have those scales for each echo 'step' as well.
        • (Michael) Wouldn't it be easier just to make "echo" a field in a PointCloud2 message? I think that Jack did this in his Velodyne driver (except for "ring"), which gives a quick way to filter by echo and visualize echo by color.

        • (Jack) Interesting idea. The whole thing probably could be done with a two-dimensional PointXYZI point cloud, with each different echo occupying different rows, height equal to the number of echoes provided, and width equal to the number of laser returns. (I only added the "ring" field because some Velodyne models output different numbers of packets for some of their lasers.)

        • (Chad) I have a few reservations about using PointCloud2s at this time. The first is that I, personally, prefer the data organization to be explicit. Most of the information gain from multi-echo lidars is from comparing the echos for each angle increment, so I would prefer to have a structure that clearly defines these sets of returns.

        • (Chad) A NxM PointCloud2 would be sending a large amount of data that isn't strictly necessary. Besides the issues with vectorization alignment on PointCloud<PointXYZI>s, the lasers can rarely output some points. For instance, the SICK 511 has an angular increment of 0.25 degrees, 185 degree field of view, and up to 5 returns per pulse. This would be 740*5 measurements per scan at up to 100Hz scanning rate. It's highly likely that nearly 80% of that data would be NaNs. It would be a win overall to avoid serializing and logging this data, especially from the driver level.

        • (Chad) It complicates the projection into a fixed frame since the final step requires the time_increment value for the laser. Time_increment could be avoided by projecting directly in the driver, but this could easily corrupt data and doesn't support things such as changing calibrations, etc.
    • (Dave) With respect to RViz, method 1 is certainly simplest because it doesn't change anything. You want to see echoes, you just add more displays. However, please don't make major design decisions based on RViz display complexity. I think it's more important to arrive at a message interface that is easy to write new code against. In my limited experience, I find it much easier when each message stands alone, rather than having to coordinate between multiple callbacks. Even Image messages coming separate from CameraInfo messages is kind of a hassle, in my opinion.

    • (Dave) An RViz display for method 2, if you want each echo level to be colored differently can be done pretty easily by adding an "echo number" channel to the PointCloud or PointCloud2 which is output from the new laser_geometry functions. Then we (or I) write a new PointCloudColorTransformer class which colors based on intensity and echo number.

      • (Chad) Thanks for your input. That's a good point that we can use new channels. In fact, it may be a good idea to optionally include those fields in an updated version of laser_geometry. I think the RVIZ interface could grow cumbersome, but at this point, Method 3 seems preferable.
    • (Christian) Following up on my original suggestion: My intention was to have the driver require to publish two topics: a compatible LaserScan and some richer message that provides data for all echoes. This is orthogonal to deciding how the multi-echoes are represented. So I would suggest to maybe regroup the methods for two things: a) What should the driver publish (only LaserScan, LaserScan + Echoes separate, only echoes) b) What should these contain? (LaserScan is first return, up to the driver (best-return), maybe multiple topics for first-return/best-return; Echoes is a specific message as suggested, pointcloud, etc.). I think that this will give a better picture, although they are somewhat dependent.

      • (Jack) +1 to LaserScan plus a separate message containing all the echoes. Leave it up to the driver which echoes to include in the LaserScan (it could provide parameters for that, if desired).

        • (Tully) I'm very wary of creating parallel data structures which would double the maintenance burden of all people processing laser scans. I like the idea of having the driver output a LaserScan with reconfigurable parameters (first, strongest, farthest, custom?) And then have the full data available as a full PointCloud2 if all the data is wanted at once. This will allow most users to not think much about it. And the power user can know that the full data should be worth the overhead of the PointCloud2, and this will avoid the issue of syncronization, which if kept as several LaserScans would likely make up for the PointCloud2 overhead if coding errors and complexity can offset pure throughput.

          • (Chad) Unfortunately, PointCloud2 cannot be accurately projected into a fixed frame from a moving platform. The timing between measurements is still needed. The representation is also at least 2x less efficient even before the necessary time_increment field would be added.

          • (Chad) Having each driver maintain code to output legacy scans doesn't sound great. The two options seem to be to follow the example of image_proc (separate node), image_transport (C++ class), or both. I'll create a new section of this review page to hear feedback on these options.
    • (Christian) Maybe it is a good idea to provide something like multi-echo laser_transport package that can be used to publish a multi-echo message and will automatically produce topics for multi_echo, first_return, strongest_return, although this couldn't handle a device specific best return.
  • (Christian) Regarding method 5: This should be how a LaserScan is produced, although it shouldn't be the only published topic as that would eliminate the purpose of a multi-echo laser.

    • (Marti) well, It wouldn't eliminate the purpose since the user would choose how the driver deals with the multi-echo.
    • (Marti) It's true that if the user would like to work with all the data this is not a good option.
      • (Christian) These were the use cases that I meant. Otherwise, we made the multi-echo scanner into a "maybe better" single return scanner.

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:

  • Is provided/subscribes to standalone MultiEchoLaserScan messages.

  • Advertises a default assortment of more compatible LaserScan messages:

    • First return (nearest distance echo per increment)
    • Last return (furthest distance echo per increment)
    • Strongest/Brightest return (most intense echo per increment)
  • Some method of custom output. I'm imagining something where the user provides a custom topic name and supplies the C++ class with a LaserScan message that will be published on that topic. This will fill the usage gap for sensors that provide a "best" single return that was not provided by default.

Conclusion

Package status change mark change manifest)

  • /!\ Action items that need to be taken.

  • {X} Major issues that need to be resolved


Wiki: sensor_msgs/Reviews/2012-08-01_MultiEchoLaser_API_review_API_Review (last edited 2012-08-29 21:31:10 by ChadRockey)