Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[Feature-Request] RVL Depth Image Compression #1362

Closed
borongyuan opened this issue Oct 21, 2024 · 5 comments
Closed

[Feature-Request] RVL Depth Image Compression #1362

borongyuan opened this issue Oct 21, 2024 · 5 comments

Comments

@borongyuan
Copy link
Contributor

RVL is a lossless depth image compression algorithm developed by Microsoft. RVL frame is supported by some Orbbec cameras. RVL codec has been added to ROS since Noetic/Jazzy. I think it will help reduce the size of the database and save bandwidth (for camera data transfer and ROS communication).

@matlabbe
Copy link
Member

Thanks for the link, that could be indeed useful! As a comparison, we are currently using PNG:
image

Implementation details:

@borongyuan
Copy link
Contributor Author

Hi, RVL only supports the depth image in 16 bits format. So I went to see how the depth image in 32 bits format was processed previously. According to
https://github.com/introlab/rtabmap/blob/b2e26e81c14bd7a1394da10998d0264968089cbe/corelib/src/Compression.cpp#L105C1-L110C4
It looks like it will be converted to 8bits-4channel data first and then encoded using png. What I'm curious about is can this be compressed effectively? Because the resulting data after the conversion doesn't seem to be a reasonable image.

If I add another _depthCompressionFormat option, how should 32 bits images be processed when it is set to '.rvl'? From a compatibility perspective, we should keep the original approach. Or force conversion to 16 bits format and give a warning when ".rvl" is set?

@borongyuan
Copy link
Contributor Author

  • We may check if opencv is adding some header in compressed data when encoding, so we could create a new encoding header to know the compressed data is "rvl", and not "png" or "jpg". That should be backward compatible to still load old databases.

Both JPEG and PNG data have standard defined signatures.
https://en.wikipedia.org/wiki/List_of_file_signatures
OpenCV also uses this to determine the decoder. As for RVL, it is not yet a standardized format. If we define a signature ourselves, it will not be compatible with ROS messages. The format is specifically specified in sensor_msgs/CompressedImage, so they do not rely on the signature of the data. Now we will first check the signature of the data, if it cannot be parsed as "jpg" or "png", it will be processed as "rvl". If we may support other formats later, and if that format has its own signature, that's no problem, because rvl will still be the only one without a signature. If we may support other formats later, and if that format has its own signature, that's fine, because rvl will still be the only one without a signature.

@matlabbe
Copy link
Member

matlabbe commented Nov 26, 2024

Thank you for the info. A quick check on an existing database and we can indeed see the signatures:

# JPEG
sqlite3 241126-100002.db "select hex(image) from Data where id=1"
FFD8FFE0...

# PNG
sqlite3 241126-100002.db "select hex(depth) from Data where id=1"
89504E470D0A1A0A...

I'll double check, but I think we don't convert back from internal rtabmap format to ROS, just ROS to rtabmap, so we could add our own signature ("DEPTHRVL" to make easy to read, that's 16 Hex characters like PNG). Maybe data_player node needs to publish as a ROS image, but we could strip the signature before converting to ROS.

Another thing to keep in mind, to keep compatibility with all image exporting methods, we may have to convert it back to PNG when doing so. So a RVL to PNG converter function would be nice.

It looks like it will be converted to 8bits-4channel data first and then encoded using png. What I'm curious about is can this be compressed effectively? Because the resulting data after the conversion doesn't seem to be a reasonable image.

PNG is simply a ZIP file. Even for a normal image there is no special optimization, unlike JPG. I could have compressed the OpenCV matrix (32FC1) directly instead of encoding it in an image.

If I add another _depthCompressionFormat option, how should 32 bits images be processed when it is set to '.rvl'? From a compatibility perspective, we should keep the original approach. Or force conversion to 16 bits format and give a warning when ".rvl" is set?

We could warn one time that it may result in loss of accuracy and maximum range of 65 meters (max USHORT in mm), but still compress RVL.

@matlabbe
Copy link
Member

matlabbe commented Dec 16, 2024

Closed by #1409

A new ticket to support RVL on rtabmap_ros has been added: introlab/rtabmap_ros#1257

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

No branches or pull requests

2 participants