Issues when converting from uyvy (yuv422) to bgr8 by using image_proc, is image step responsible?

asked 2021-10-21 02:21:22 -0500

Ifx13 gravatar image

updated 2021-10-21 02:21:55 -0500

Hello people, I am trying to convert an image topic with data in the uyvy (yuv422) format to bgr8 without success. Here is a description of the things I've tried, any ideas?

I have an image topic but the image data are in the UYVY encoding. This image topic contains the following fields:

  • header
  • height
  • width
  • data

But is missing the following:

  • encoding
  • step

So, in order to use the topics I need to correct the encoding so I am using image_proc.

And for that purpose I've created a node that subscribes to the initial topic and publishes an image_raw and a dummy camera_info topic. Here is the node:

#!/usr/bin/env python

import rospy
from ecam_v4l2.msg import image
from sensor_msgs.msg import Image, CameraInfo

img_pub = rospy.Publisher('/cam_30/image_raw', Image, queue_size = 1)
info_pub = rospy.Publisher('/cam_30/camera_info', CameraInfo, queue_size = 1)

img = Image()
info = CameraInfo()

def callback(data):
    img.header = data.header
    img.header.frame_id = 'cam_30'
    img.data = data.data
    img.encoding = 'bgr8'
    img.height = data.height
    img.width = data.width
    img_pub.publish(img)

    info.header = img.header
    info.width = data.width
    info.height = data.height
    info.distortion_model = "plumb_bob"

    info.D = [0, 0, 0, 0, 0]
    info.K = [0, 0, 0, 0, 0, 0, 0, 0, 0]
    info.R = [1, 0, 0, 0, 1, 0, 0, 0, 1]
    info.P = [0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0]
    info_pub.publish(info)

def listener():
    rospy.init_node('custom_listener', anonymous=True)
    rospy.Subscriber("/vi_output__ar1335_30_003c", image, callback)
    rospy.spin()

if __name__ == '__main__':
    listener()

So after the node is up and running and the topics are being published, I run image_proc

ROS_NAMESPACE=/cam_30 rosrun image_proc image_proc

But when I am trying to view the image on rviz I get the following error:

[ WARN] [1634799378.292660211]: OGRE EXCEPTION(2:InvalidParametersException): Stream size does not match calculated image size in Image::loadRawData at /build/ogre-1.9-i02lBV/ogre-1.9-1.9.0+dfsg1/OgreMain/src/OgreImage.cpp (line 283)
[ERROR] [1634799378.293464728]: Error loading image: OGRE EXCEPTION(2:InvalidParametersException): Stream size does not match calculated image size in Image::loadRawData at /build/ogre-1.9-i02lBV/ogre-1.9-1.9.0+dfsg1/OgreMain/src/OgreImage.cpp (line 283)

After reading this and similar posts I thought that for the error is responsible the encoding declared on the image_raw topic, and I set it at "bgr8" which I believe is the encoding that image_proc uses after debayers (color conversion) the topic.

But the error does not go away, and I suspect the fact that the filed step is missing is causing the error. I do not know how I should calculate this and does it matter if the initial data is UYVY (yuv422) in the calculation or I should calculate based on the bgr8 output?

edit retag flag offensive close merge delete

Comments

You could use opencv to convert yuv to bgr using yvu = cv2.cvtColor(img, cv2.COLOR_BGR2YCrCb)

Take a look at https://stackoverflow.com/questions/6...

osilva gravatar image osilva  ( 2021-10-21 19:47:32 -0500 )edit