raspicam_node icon indicating copy to clipboard operation
raspicam_node copied to clipboard

Raw Image does not Load into Rviz.

Open sradmard opened this issue 5 years ago • 5 comments

Hi there, When I enable the enable_raw flag to get the raw image, unfortunately the image cannot be loaded to Rviz. The reason is that the data being published into the /raspicam_node/image topic is somehow corrupted. Here is an instance of the published raw image:

header: seq: 1109 stamp: secs: 1555185561 nsecs: 712540212 frame_id: raspicam height: 308 width: 410 encoding: bgr8 is_bigendian: 0 step: 1230 data: <array type: uint8, length: 399360>

By looking at the published raw image above, we see that the stream size (length of the data:399360) does not match the calculated image size (3084103=378840). And that is why Rviz cannot visualise it. If I use the image_transport package to uncompress the compressed image published into the /raspicam_node/image/compressed, then I get the following data type, and I can visualise it in Rviz.

header: seq: 1246 stamp: secs: 1555185575 nsecs: 412069710 frame_id: raspicam height: 308 width: 410 encoding: bgr8 is_bigendian: 0 step: 1230 data: <array type: uint8, length: 378840>

I would appreciate any hint on how to fix this bug. Thank you

sradmard avatar Apr 13 '19 21:04 sradmard

Same problem here with web_video_server! Any idea how to fix this?

ludusrusso avatar Apr 19 '19 06:04 ludusrusso

I am also having this issue, hope to hear some kind of fix

AKrause4 avatar Oct 03 '19 03:10 AKrause4

me too! any comment?

elgarbe avatar Dec 08 '19 02:12 elgarbe

Can confirm this is still a problem.

MoffKalast avatar Apr 16 '20 15:04 MoffKalast

I think I know the source of this problem.

  1. Actually, while capturing RAW data from the sensor, native Pi utilities (like raspividyuv etc) requires width to be dividable by 32, and height to be dividable by 16.
  2. If you capture non-RAW (like using raspivid utility), these utilities do scaling to get final requested resolution, so you didn't notice this issue. Scaling is done by GPU, so performance is the same.

What's going on in your case:

  1. You ask to capture 308x410 resolution
  2. 308/16 = 19.25 (non dividable by 16). Next nearest to 19.25 is 20, so system captures 20x16= 320 instead of 308
  3. 410/32 = 12.8125 (not dividable by 32). Next nearest to 12.8125 is 13, so system captures 13x32 = 416
  4. You actually have 320x416x3 = 399360 bytes of data. Right these numbers are declared here in your first message: data: <array type: uint8, length: 399360>

We faced this problem in our stereoscopic OpenCV scripts, and use a couple of approaches here:

  1. Check, if the resolution you set is dividable by 16 (X and Y), and if not - fix it before transmitting these parameters to the capturing part. I.e. in your case try to set 320x416 instead of 308x410.
  2. Keep the resolution you use, but fix the X and Y you expect in output data.

UPD> More details in a PiCamera documentation here: https://picamera.readthedocs.io/en/release-1.13/recipes2.html#capturing-to-a-numpy-array

Cite: It is also important to note that when outputting to unencoded formats, the camera rounds the requested resolution. The horizontal resolution is rounded up to the nearest multiple of 32 pixels, while the vertical resolution is rounded up to the nearest multiple of 16 pixels. For example, if the requested resolution is 100x100, the capture will actually contain 128x112 pixels worth of data, but pixels beyond 100x100 will be uninitialized.

realizator avatar Apr 17 '20 09:04 realizator