Closed ibaranov-cp closed 3 years ago
BTW, here's the output of rostopic echo --noarr /raspicam_node/image
header:
seq: 240
stamp:
secs: 1621622258
nsecs: 895839001
frame_id: "raspicam"
height: 308
width: 410
encoding: "bgr8"
is_bigendian: 0
step: 1230
data: "<array type: uint8, length: 399360>"
So yes, data length is a bit odd...
Found a workaround, seems to be slightly more efficient anyway: Republish compressed images as raw image (slight loss of quality is fine for my use case). Disable raspicam raw output, and add to launch file:
<!-- node to replublish compressed images as raw -->
<node
name="republish"
type="republish"
pkg="image_transport"
output="screen"
args="compressed
in:=/raspicam_node/image
raw out:=/raspicam_node/image"
/>
BTW, here's the output of rostopic echo --noarr /raspicam_node/image
height: 308 width: 410 .. data: "<array type: uint8, length: 399360>"
So yes, data length is a bit odd...
This is not the raspicam_node issue, but the issue with the native MMAL RAW image capture used for Pi cameras. Both the width and height of the image should be dividable by 16. If not - it's rounded up. In your case: 308/16 = 19.25 ~~~> rounded up to 20, so the actual width of the captured image is 320 410/16 = 25.625 ~~~> rounded up to 26, so the actual height of the captured image is 416 So you are having 320 416 3 = 399 360 bytes, exactly as reported.
You should either use appropriate resolution, or raspicam_node should do the resolution check and warning the user.
And if you are using the compressed image - this is not an issue, as in this case, GPU is resizing the RAW image to fit the requested resolution. That's why your workaround works fine. But for the hard-real-time tasks, this decompression can affect your solution latency.
Hello,
When trying to use ros image_proc to rectify the image, I get an error when I try to subscribed to the output rectified image: cv_bridge conversion error: 'Image is wrongly formed: height step != size or 308 1230 != 399360'
Here's my launch file:
I can see that the topic /raspicam_node/image comes through at 30Hz, no issues.
Subscribing to /raspicam_node/image_rect generates no messages however.
Here's the launch output:
Likely the image_mono issue is not important (at least to my use case)...