ros-drivers / libuvc_ros

http://www.ros.org/wiki/libuvc_ros
81 stars 97 forks source link

Image not rendered correctly #51

Open yoann-solana opened 5 years ago

yoann-solana commented 5 years ago

Hi, I would like to test a USB camera on ROS. I have followed the procedure to setup libuvc but the image on the raw topic is not rendered well.

This is a capture of the image on the topic /camera/image_raw, as you will see the image seems to be duplicated. libuvc_problem

This is the output of the v4l2-ctl --list-formats-ext command:

ioctl: VIDIOC_ENUM_FMT
    Index       : 0
    Type        : Video Capture
    Pixel Format: 'UYVY'
    Name        : UYVY 4:2:2
        Size: Discrete 640x480
            Interval: Discrete 0.017s (60.000 fps)
            Interval: Discrete 0.022s (45.000 fps)
        Size: Discrete 960x540
            Interval: Discrete 0.017s (58.000 fps)
            Interval: Discrete 0.033s (30.000 fps)
        Size: Discrete 1280x960
            Interval: Discrete 0.029s (34.000 fps)
            Interval: Discrete 0.044s (22.500 fps)
        Size: Discrete 1280x720
            Interval: Discrete 0.022s (45.000 fps)
            Interval: Discrete 0.033s (30.000 fps)
        Size: Discrete 1920x1080
            Interval: Discrete 0.033s (30.000 fps)
            Interval: Discrete 0.067s (15.000 fps)

And this is my launch file:

<launch>
  <group ns="camera">
    <node pkg="libuvc_camera" type="camera_node" name="mycam">
      <!-- Parameters used to find the camera -->
      <param name="vendor" value="0x2560"/>
      <param name="product" value="0xc120"/>
      <param name="serial" value=""/>
      <!-- If the above parameters aren't unique, choose the first match: -->
      <param name="index" value="3"/>

      <!-- Image size and type -->
      <param name="width" value="960"/>
      <param name="height" value="540"/>
      <!-- choose whichever uncompressed format the camera supports: -->
      <param name="video_mode" value="uyvy"/> <!-- or uncompressed/ yuyv/nv12/mjpeg -->
      <param name="frame_rate" value="30"/>

      <param name="timestamp_method" value="start"/> <!-- start of frame -->
      <param name="camera_info_url" value="package://robot/config/cam0_calib.yaml"/>

      <param name="auto_exposure" value="3"/> <!-- use aperture_priority auto exposure -->
      <param name="auto_white_balance" value="false"/>
    </node>
  </group>
</launch>

Do you see something wrong?

My configuration is a computer running Ubuntu 16.04 with ROS Kinetic.

Thanks in advance, Yoann.

7675t commented 5 years ago

Have you check your camera with other camera softwares, say, guvcview?

yoann-solana commented 5 years ago

Hi, Thank you for the help. Yes I tried Guvcview for the 960x540 resolution at 30fps. And it works for all the next formats:

If it can help, I tried the usb_cam ROS package and it works. This is the configuration I used:

 <node name="cam_$(arg cam_id)" pkg="usb_cam" type="usb_cam_node" output="screen" >
    <param name="video_device" value="$(arg dev_path)" />
    <param name="image_width" value="960" />
    <param name="image_height" value="540" />
    <param name="pixel_format" value="uyvy" />
    <param name="camera_frame_id" value="$(arg cam_frame_id)" />
    <param name="io_method" value="mmap"/>
    <param name="framerate" value="30"/>
    <param name="camera_info_url" value="$(arg camera_info_url)" />
  </node>
7675t commented 5 years ago

In that case, it may be from libuvc_camera driver itself... I personally cannot debug this, but someone could if you share the information of your camera product.

yoann-solana commented 5 years ago

Hi, Thank you, the camera is this model Is it enough information?

7675t commented 5 years ago

I'm not quite sure, it seems from the pixel format of UYVY that not supported by ROS Image.

Can you show a image message by rostopic echo? encoding member should be yuv422.

yoann-solana commented 5 years ago

I have made the test with usb_cam and libuvc_ros. Indeed the encoding of the image is different.

This is the short version of a message with usb_cam:

header: 
  seq: 16
  stamp: 
    secs: 1536135825
    nsecs: 368116116
  frame_id: "cam_2_lens_link"
height: 540
width: 960
encoding: "rgb8"
is_bigendian: 0
step: 2880
data: [32, 49, 50,

This is the short version of a message with libuvc_ros:

header: 
  seq: 199
  stamp: 
    secs: 1536137775
    nsecs: 629784377
  frame_id: camera
height: 540
width: 960
encoding: yuv422
is_bigendian: 0
step: 2880

I have also attached the complete message files. cam_2_image_raw.txt libuvc-cam_2_image_raw.txt

7675t commented 5 years ago

What happens if you set video_mode to "rgb"?

yoann-solana commented 5 years ago

The rgb mode is not supported.

process[camera/mycam-2]: started with pid [2465]
unsupported descriptor subtype VS_STILL_IMAGE_FRAME
uvc_get_stream_ctrl_format_size: Invalid mode (-51)
[ERROR] [1536156261.372000402]: check video_mode/width/height/frame_rate are available

If you have an idea, I can look at the source to help.

7675t commented 5 years ago

This camera seems to produce raw bayer images to image_raw. In case of that, you may need to use image_proc/debayer node or nodelet. Please try it.

yoann-solana commented 5 years ago

Thank you. I just test it and the image is still the same. Below is a copy of may launch file and the output of the terminal if it can help. Launch file:

<launch>
  <!-- Push down all topics/nodelets into "camera" namespace -->
  <group ns="camera">

    <node pkg="nodelet" type="nodelet" name="camera_nodelet_manager" args="manager" />

    <node pkg="libuvc_camera" type="camera_node" name="mycam">
      <!-- Parameters used to find the camera -->
      <param name="vendor" value="0x2560"/>
      <param name="product" value="0xc120"/>
      <param name="serial" value=""/>
      <!-- If the above parameters aren't unique, choose the first match: -->
      <param name="index" value="2"/>

      <!-- Image size and type -->
      <param name="width" value="960"/>
      <param name="height" value="540"/>
      <!-- choose whichever uncompressed format the camera supports: -->
      <param name="video_mode" value="uncompressed"/> <!-- or uncompressed/rgb/yuyv/nv12/mjpeg, not work uyvy-->
      <param name="frame_rate" value="30"/>

      <param name="timestamp_method" value="start"/> <!-- start of frame -->
      <param name="camera_info_url" value="package://platform_misumi_bringup/config/cam0_calib.yaml"/>

      <param name="auto_exposure" value="3"/> <!-- use aperture_priority auto exposure -->
      <param name="auto_white_balance" value="false"/>
    </node>
    <node pkg="nodelet" type="nodelet" name="image_proc_debayer"
          args="load image_proc/debayer camera_nodelet_manager">
      <param name="debayer" value="2" />
    </node>

  </group> <!-- camera ns -->

</launch>

Terminal output:

started roslaunch server http://10.42.10.1:39059/

SUMMARY
========

PARAMETERS
 * /camera/image_proc_debayer/debayer: 2
 * /camera/mycam/auto_exposure: 3
 * /camera/mycam/auto_white_balance: False
 * /camera/mycam/camera_info_url: package://platfor...
 * /camera/mycam/frame_rate: 30
 * /camera/mycam/height: 540
 * /camera/mycam/index: 2
 * /camera/mycam/product: 0xc120
 * /camera/mycam/serial: 
 * /camera/mycam/timestamp_method: start
 * /camera/mycam/vendor: 0x2560
 * /camera/mycam/video_mode: uncompressed
 * /camera/mycam/width: 960
 * /rosdistro: kinetic
 * /rosversion: 1.12.13

NODES
  /camera/
    camera_nodelet_manager (nodelet/nodelet)
    image_proc_debayer (nodelet/nodelet)
    mycam (libuvc_camera/camera_node)

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

setting /run_id to 9ff23a20-b1ae-11e8-8f3c-0007324983dc
process[rosout-1]: started with pid [29567]
started core service [/rosout]
process[camera/camera_nodelet_manager-2]: started with pid [29583]
process[camera/mycam-3]: started with pid [29585]
process[camera/image_proc_debayer-4]: started with pid [29586]
unsupported descriptor subtype VS_STILL_IMAGE_FRAME
attempt to claim already-claimed interface 1
7675t commented 5 years ago

Hmm, running out of my idea, sorry. Could you share an image bag file for several seconds? Anyway it may difficult to debug without the device if it is from the driver code.

yoann-solana commented 5 years ago

Hi, Sorry for the delay. I have recorded the bag file with the configuration from the launch file I have posted before.

The bag file was recorded for 0.3s and its size is 14.8MB. 2018-09-13-12-34-03.bag.zip

Regards, Yoann

7675t commented 5 years ago

I have no idea, sorry. The image shows the data is inerlace, but I can't find any de-interlace code in libuvc.

https://github.com/ktossell/libuvc/search?l=C&q=interlace

So, I guess you may better to stick to other packages (usb_cam, gscam, etc) if you can.

skohlbr commented 5 years ago

Stumbled across the same issue. So in https://github.com/ros-drivers/libuvc_ros/blob/master/libuvc_camera/src/camera_driver.cpp#L187, the contents of the YUV buffer get directly memcpy'd into the RGB frame. That appears wrong, as a proper conversion makes 6 RGB bytes out of 4 YUV ones. As this is not done, it would be expected that only 2/3 of the image contain actual image data, and that's exactly what can be observed in the image in original post. It looks like maybe the conversion code for the other YUV convention (https://github.com/ros-drivers/libuvc_ros/blob/master/libuvc_camera/src/camera_driver.cpp#L192) should be also employed.

skohlbr commented 5 years ago

Fixed (and tested with the CU20 camera) via #52.

7675t commented 5 years ago

Wow, I should've noticed! Great job! Good for all and thank you @skohlbr , @yoann-solana