UbiquityRobotics / raspicam_node

ROS node for camera module of Raspberry Pi
BSD 3-Clause "New" or "Revised" License
293 stars 162 forks source link

cv_bridge conversion error: 'Image is wrongly formed #115

Closed ibaranov-cp closed 3 years ago

ibaranov-cp commented 3 years ago

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:

<launch>
  <arg name="enable_raw" default="true"/>
  <arg name="enable_imv" default="false"/>
  <arg name="camera_id" default="0"/>
  <arg name="camera_frame_id" default="raspicam"/>
  <arg name="camera_name" default="camerav2_410x308"/>

  <node type="raspicam_node" pkg="raspicam_node" name="raspicam_node" output="screen">
    <param name="private_topics" value="true"/>

    <param name="camera_frame_id" value="$(arg camera_frame_id)"/>
    <param name="enable_raw" value="$(arg enable_raw)"/>
    <param name="enable_imv" value="$(arg enable_imv)"/>
    <param name="camera_id" value="$(arg camera_id)"/>

    <param name="camera_info_url" value="package://raspicam_node/camera_info/camerav2_410x308.yaml"/>
    <param name="camera_name" value="$(arg camera_name)"/>
    <param name="width" value="410"/>
    <param name="height" value="308"/>

    <param name="framerate" value="30"/>
    <param name="exposure_mode" value="antishake"/>
    <param name="shutter_speed" value="0"/>

  </node>

  <node 
    pkg="image_proc" 
    type="image_proc" 
    name="ip_node" 
    ns="raspicam_node"
    >
    <remap from="image_raw" to="image" />
  </node>

</launch>

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:

roslaunch sherlock.launch 
... logging to /home/pi/.ros/log/ae673b92-ba60-11eb-9fc2-e45f01006b1a/roslaunch-raspberrypi-10671.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://raspberrypi:42061/

SUMMARY
========

PARAMETERS
 * /raspicam_node/camera_frame_id: raspicam
 * /raspicam_node/camera_id: 0
 * /raspicam_node/camera_info_url: package://raspica...
 * /raspicam_node/camera_name: camerav2_410x308
 * /raspicam_node/enable_imv: False
 * /raspicam_node/enable_raw: True
 * /raspicam_node/exposure_mode: antishake
 * /raspicam_node/framerate: 30
 * /raspicam_node/height: 308
 * /raspicam_node/private_topics: True
 * /raspicam_node/shutter_speed: 0
 * /raspicam_node/width: 410
 * /rosdistro: noetic
 * /rosversion: 1.15.11

NODES
  /
    raspicam_node (raspicam_node/raspicam_node)
  /raspicam_node/
    ip_node (image_proc/image_proc)

auto-starting new master
process[master]: started with pid [10681]
ROS_MASTER_URI=http://localhost:11311

setting /run_id to ae673b92-ba60-11eb-9fc2-e45f01006b1a
process[rosout-1]: started with pid [10693]
started core service [/rosout]
process[raspicam_node-2]: started with pid [10700]
process[raspicam_node/ip_node-3]: started with pid [10701]
[ INFO] [1621621000.515685874]: splitter component done

[ INFO] [1621621000.658256539]: camera calibration URL: package://raspicam_node/camera_info/camerav2_410x308.yaml
[ INFO] [1621621000.724715293]: Camera successfully calibrated from default file
[ INFO] [1621621000.724869717]: using default calibration URL
[ INFO] [1621621000.724998548]: camera calibration URL: file:///home/pi/.ros/camera_info/camerav2_410x308.yaml
[ INFO] [1621621000.725737482]: Unable to open camera calibration file [/home/pi/.ros/camera_info/camerav2_410x308.yaml]
[ WARN] [1621621000.725852536]: Camera calibration file /home/pi/.ros/camera_info/camerav2_410x308.yaml not found.
[ INFO] [1621621000.725984349]: No device specifc calibration found
[ INFO] [1621621000.813223898]: Starting video capture (410, 308, 80, 30)

[ INFO] [1621621000.814790653]: Video capture started

[ WARN] [1621621017.091772718]: cv_bridge conversion error: 'Image is wrongly formed: height * step != size  or  308 * 1230 != 399360'
[ WARN] [1621621026.900036445]: [image_transport] Topics '/raspicam_node/image_mono' and '/raspicam_node/camera_info' do not appear to be synchronized. In the last 10s:
    Image messages received:      0
    CameraInfo messages received: 87
    Synchronized pairs:           0
[ WARN] [1621621069.543076217]: cv_bridge conversion error: 'Image is wrongly formed: height * step != size  or  308 * 1230 != 399360'
[ WARN] [1621621079.349486509]: [image_transport] Topics '/raspicam_node/image_mono' and '/raspicam_node/camera_info' do not appear to be synchronized. In the last 10s:
    Image messages received:      0
    CameraInfo messages received: 109
    Synchronized pairs:           0
[ WARN] [1621621410.177510698]: cv_bridge conversion error: 'Image is wrongly formed: height * step != size  or  308 * 1230 != 399360'
[ WARN] [1621621419.989858705]: [image_transport] Topics '/raspicam_node/image_mono' and '/raspicam_node/camera_info' do not appear to be synchronized. In the last 10s:
    Image messages received:      0
    CameraInfo messages received: 97
    Synchronized pairs:           0

Likely the image_mono issue is not important (at least to my use case)...

ibaranov-cp commented 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...

ibaranov-cp commented 3 years ago

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" 
  />
realizator commented 3 years ago

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.