API review

Proposer: Patrick

Present at review:

  • List reviewers

Question / concerns / comments

To be removed: stereo_msgs/DisparityInfo, stereo_msgs/RawStereo, stereo_msgs/StereoInfo

stereo_msgs/DisparityImage should be revamped to:

  • Reuse existing messages (e.g. sensor_msgs/Image) instead of replicating their fields.

  • Not duplicate geometry parameters that should be pulled from sensor_msgs/CameraInfo.

  • Use more descriptive names.

Current DisparityImage:

# This message contains an uncompressed disparity (16-bit) image
# (0, 0) is at top-left corner of image
#

Header header        # Header timestamp should be acquisition time of image
                     # Header frame_id should be optical frame of camera
                     # origin of frame should be optical center of cameara
                     # +x should point to the right in the image
                     # +y should point down in the image
                     # +z should point into to plane of the image
                     # If the frame_id here and the frame_id of the CameraInfo
                     # message associated with the image conflict
                     # the behavior is undefined

uint32 height         # image height, that is, number of rows
uint32 width          # image width, that is, number of columns

# specifics for disparity

# stereo geometry
# focal length, lens center, horizontal baseline
float32 f # in pixels
float32 cx # in pixels
float32 cy # in pixels
float32 Tx # in meters

# dpp is the interpolation factor, e.g., dpp=16 means each disparity increment
#   is 1/16 of a pixel
uint32 dpp

# maximum search range for disparities, in pixels
uint32 num_disp

# subwindow of valid stereo values
uint32 im_Dtop
uint32 im_Dleft
uint32 im_Dwidth
uint32 im_Dheight

# The legal values for encoding are in file src/image_encodings.cpp
# Should be 16bit monochrome
string encoding       # Encoding of pixels -- channel meaning, ordering, size
                      # taken from the list of strings in src/image_encodings.cpp
uint8 is_bigendian    # is this data bigendian?
uint32 step           # Full row length in bytes
uint8[] data          # actual matrix data, size is (step * rows)

Proposed new DisparityImage:

# Uncompressed 16-bit integer disparity image. Divide values by
# increments_per_pixel to get disparities in pixel units.
sensor_msgs/Image image

# Subwindow of valid stereo values.
sensor_msgs/RegionOfInterest valid_window

# Interpolation factor, e.g. increments_per_pixel=16 means each
# disparity increment is 1/16 of a pixel.
uint32 increments_per_pixel

# Maximum search range for disparities, in pixels.
uint32 search_range

New proposal 11/23, just use floats instead of fixed point special-casing:

# Floating point disparity image.
sensor_msgs/Image image

# Subwindow of valid stereo values.
sensor_msgs/RegionOfInterest valid_window

# Maximum search range for disparities, in pixels.
uint32 search_range

Proposal 12/4: Explicitly state 3D volume covered by the search range (the horopter), computable from search_range AND min_disparity (may be non-zero). Add back in smallest allowed disparity increment, useful for computing depth range resolution.

# Floating point disparity image.
sensor_msgs/Image image

# Subwindow of valid stereo values.
sensor_msgs/RegionOfInterest valid_window

# The horopter, or 3D volume covered by the disparity search. Points with Z less than min_depth or greater than max_depth could not be found.
float64 min_depth
float64 max_depth

# Smallest allowed disparity increment. The smallest achievable depth range resolution is delta_Z = (Z^2/fT)*delta_d.
float64 delta_d

Meeting agenda

To be filled out by proposer based on comments gathered during API review period

Conclusion

Package status change mark change manifest)

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

  • {X} Major issues that need to be resolved


Wiki: stereo_msgs/Reviews/2009-11-12-DisparityImage_API_Review (last edited 2009-12-04 20:03:30 by PatrickMihelich)