anqixu / ueye_cam

A ROS nodelet and node that wraps the driver API for UEye cameras by IDS Imaging Development Systems GMBH.
Other
60 stars 102 forks source link

Master Slave in Free-run mode not in sync #66

Closed fehlfarbe closed 6 years ago

fehlfarbe commented 6 years ago

Hi! I'm trying to capture synced images with two UI-3060CP-M-GL Rev.2 cameras. I edited your master_slaves_rgb8.launch launchfile:

<launch>
  <node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager" output="screen" />

  <node pkg="nodelet" type="nodelet" name="ueye_cam_nodelet_master"
        args="load ueye_cam/ueye_cam_nodelet nodelet_manager">
    <param name="camera_name" type="str" value="master" /> <!-- == namespace for topics and services -->
    <param name="camera_topic" type="str" value="image_raw" />
    <param name="camera_id" type="int" value="1" /> <!-- 0 = any camera; 1+: camera ID -->
    <param name="camera_intrinsics_file" type="string" value="" /> <!-- default: ~/.ros/camera_info/<camera_name>.yaml -->
    <param name="camera_parameters_file" type="string" value="" /> <!-- default: ~/.ros/camera_conf/<camera_name>.ini -->

    <param name="ext_trigger_mode" type="bool" value="False" /> <!-- if False, then camera will operate in free-run mode; otherwise, frames need to be triggered by hardware signal (falling-edge) on digital input pin of camera -->

    <!-- the following are optional camera configuration parameters:
         they will be loaded on the camera after the .ini configuration
         file, and before dynamic_reconfigure. That means that any
         (lingering) dynamic parameters from dynamic_reconfigure will
         override these values, and that these will override parameters
         from the .ini file.
         See http://www.ros.org/wiki/ueye_cam for more details. -->

    <param name="color_mode" type="str" value="mono8" /> <!-- valid options: 'rgb8', 'mono8', 'bayer_rggb8' -->

    <!-- WARNING: the following 4 parameters specify dimensions for camera's area of interest. Values for image_width and image_height that are smaller than your camera's maximum values will result in cropped field of view. For typical cases, one should modify values for sensor_scaling / binning / subsampling to downsample the resulting ROS image to the desired dimensions, without losing potential field of view. -->
    <param name="image_width" type="int" value="1936" />
    <param name="image_height" type="int" value="1216" />
    <param name="image_top" type="int" value="-1" /> <!-- -1: center -->
    <param name="image_left" type="int" value="-1" /> <!-- -1: center -->

    <param name="subsampling" type="int" value="1" /> <!-- supported by only some UEye cameras -->
    <param name="binning" type="int" value="1" /> <!-- supported by only some UEye cameras -->
    <param name="sensor_scaling" type="double" value="1.0" /> <!-- supported by only some UEye cameras -->

    <param name="auto_gain" type="bool" value="True" />
    <param name="master_gain" type="int" value="0" />
    <param name="red_gain" type="int" value="0" />
    <param name="green_gain" type="int" value="1" />
    <param name="blue_gain" type="int" value="16" />
    <param name="gain_boost" type="bool" value="False" />

    <param name="auto_exposure" type="bool" value="False" />
    <param name="exposure" type="int" value="10" /> <!-- in ms -->

    <param name="auto_white_balance" type="bool" value="True" />
    <param name="white_balance_red_offset" type="int" value="0" />
    <param name="white_balance_blue_offset" type="int" value="0" />

    <param name="flash_delay" type="int" value="0" /> <!-- in us -->
    <param name="flash_duration" type="int" value="1000" /> <!-- in us -->

    <param name="auto_frame_rate" type="bool" value="False" />
    <param name="frame_rate" type="double" value="30.0" />
    <param name="pixel_clock" type="int" value="237" />
  </node>

  <!-- SLAVE -->

  <node pkg="nodelet" type="nodelet" name="ueye_cam_nodelet_slave1"
        args="load ueye_cam/ueye_cam_nodelet nodelet_manager">
    <param name="camera_name" type="str" value="slave1" /> <!-- == namespace for topics and services -->
    <param name="camera_topic" type="str" value="image_raw" />
    <param name="camera_id" type="int" value="2" /> <!-- 0 = any camera; 1+: camera ID -->
    <param name="camera_intrinsics_file" type="string" value="" /> <!-- default: ~/.ros/camera_info/<camera_name>.yaml -->
    <param name="camera_parameters_file" type="string" value="" /> <!-- default: ~/.ros/camera_conf/<camera_name>.ini -->

    <param name="ext_trigger_mode" type="bool" value="True" /> <!-- if False, then camera will operate in free-run mode; otherwise, frames need to be triggered by hardware signal (falling-edge) on digital input pin of camera -->

    <!-- the following are optional camera configuration parameters:
         they will be loaded on the camera after the .ini configuration
         file, and before dynamic_reconfigure. That means that any
         (lingering) dynamic parameters from dynamic_reconfigure will
         override these values, and that these will override parameters
         from the .ini file.
         See http://www.ros.org/wiki/ueye_cam for more details. -->

    <param name="color_mode" type="str" value="mono8" /> <!-- valid options: 'rgb8', 'mono8', 'bayer_rggb8' -->
    <param name="image_width" type="int" value="1936" />
    <param name="image_height" type="int" value="1216" />
    <param name="image_top" type="int" value="-1" /> <!-- -1: center -->
    <param name="image_left" type="int" value="-1" /> <!-- -1: center -->   

  <!--
    <param name="image_width" type="int" value="640" />
    <param name="image_height" type="int" value="480" />
    <param name="image_top" type="int" value="-1" /> 
    <param name="image_left" type="int" value="-1" />

    <param name="subsampling" type="int" value="1" />
    <param name="binning" type="int" value="1" />
    <param name="sensor_scaling" type="double" value="1.0" />

    <param name="auto_gain" type="bool" value="True" />
    <param name="master_gain" type="int" value="0" />
    <param name="red_gain" type="int" value="0" />
    <param name="green_gain" type="int" value="1" />
    <param name="blue_gain" type="int" value="16" />
    <param name="gain_boost" type="bool" value="False" />

    <param name="auto_exposure" type="bool" value="False" />
    <param name="exposure" type="int" value="33" />

    <param name="auto_white_balance" type="bool" value="True" />
    <param name="white_balance_red_offset" type="int" value="0" />
    <param name="white_balance_blue_offset" type="int" value="0" />
-->    
    <param name="flash_delay" type="int" value="0" />
    <param name="flash_duration" type="int" value="1000" />

    <param name="auto_frame_rate" type="bool" value="False" />
    <param name="auto_exposure" type="bool" value="False" />

    <param name="exposure" type="int" value="3" /> <!-- in ms -->
    <param name="pixel_clock" type="int" value="237" />
  </node>

</launch>

But when I record the image topics with rosbag record /master/image_raw /slave1/image_raw the image count for both cameras are different. Looks like the slave camera image is missing sometimes.

screenshot_bagfile

I tried with different flash durations, exposure times and frame rates it's always the same problem. Do you have any suggestions?

anqixu commented 6 years ago

Hmm flash duration of 1000us seems somewhat short. For 30fps, eg 33ms period, I would try a trigger (flash) duration of almost half the period, so 8000-16000us. If you still see dropped frames, I would suspect that your computer might have slow disk write (so rosbag is failing), or your usb connection to the slave camera doesn't have the best quality (so try a different cable/port).

Remember to tune the flash delay later to sync the time.

fehlfarbe commented 6 years ago

Thanks for the input! I tried:

So it's either a problem with the trigger cable or some setting is missing on the ROS node. I will investigate it further.

fehlfarbe commented 6 years ago

Sometimes the slave camera needs some frames to initialize: rqt_bag I solved this with a rostopic hz /master/image_raw and rostopic hz /slave1/image_raw subscription to keep the cameras busy. With these settings I can record the raw images with full resolution and 80fps without dropped frames to /dev/shm. For compressed images (my HDD is too slow for 80fps raw data) I can go up to 60fps.

So this is my working config:

<launch>
  <node pkg="nodelet" type="nodelet" name="nodelet_manager" args="manager" output="screen" />

  <node pkg="nodelet" type="nodelet" name="ueye_cam_nodelet_master"
        args="load ueye_cam/ueye_cam_nodelet nodelet_manager">
    <param name="camera_name" type="str" value="master" /> <!-- == namespace for topics and services -->
    <param name="camera_topic" type="str" value="image_raw" />
    <param name="camera_id" type="int" value="1" /> <!-- 0 = any camera; 1+: camera ID -->
    <param name="camera_intrinsics_file" type="string" value="" /> <!-- default: ~/.ros/camera_info/<camera_name>.yaml -->
    <param name="camera_parameters_file" type="string" value="" /> <!-- default: ~/.ros/camera_conf/<camera_name>.ini -->

    <param name="ext_trigger_mode" type="bool" value="False" /> <!-- if False, then camera will operate in free-run mode; otherwise, frames need to be triggered by hardware signal (falling-edge) on digital input pin of camera -->

    <!-- the following are optional camera configuration parameters:
         they will be loaded on the camera after the .ini configuration
         file, and before dynamic_reconfigure. That means that any
         (lingering) dynamic parameters from dynamic_reconfigure will
         override these values, and that these will override parameters
         from the .ini file.
         See http://www.ros.org/wiki/ueye_cam for more details. -->

    <param name="color_mode" type="str" value="mono8" /> <!-- valid options: 'rgb8', 'mono8', 'bayer_rggb8' -->

    <!-- WARNING: the following 4 parameters specify dimensions for camera's area of interest. Values for image_width and image_height that are smaller than your camera's maximum values will result in cropped field of view. For typical cases, one should modify values for sensor_scaling / binning / subsampling to downsample the resulting ROS image to the desired dimensions, without losing potential field of view. -->
    <param name="image_width" type="int" value="1936" />
    <param name="image_height" type="int" value="1216" />
    <param name="image_top" type="int" value="-1" /> <!-- -1: center -->
    <param name="image_left" type="int" value="-1" /> <!-- -1: center -->
    <!-- <param name="image_width" type="int" value="640" />
    <param name="image_height" type="int" value="480" /> -->

    <param name="subsampling" type="int" value="1" /> <!-- supported by only some UEye cameras -->
    <param name="binning" type="int" value="1" /> <!-- supported by only some UEye cameras -->
    <param name="sensor_scaling" type="double" value="1.0" /> <!-- supported by only some UEye cameras -->

    <param name="auto_gain" type="bool" value="True" />
    <param name="master_gain" type="int" value="0" />
    <param name="red_gain" type="int" value="0" />
    <param name="green_gain" type="int" value="1" />
    <param name="blue_gain" type="int" value="16" />
    <param name="gain_boost" type="bool" value="False" />

    <param name="auto_exposure" type="bool" value="False" />
    <param name="exposure" type="int" value="10" /> <!-- in ms -->

    <param name="auto_white_balance" type="bool" value="True" />
    <param name="white_balance_red_offset" type="int" value="0" />
    <param name="white_balance_blue_offset" type="int" value="0" />

    <param name="flash_delay" type="int" value="1000" /> <!-- in us -->
    <param name="flash_duration" type="int" value="1000" /> <!-- in us -->

    <param name="auto_frame_rate" type="bool" value="False" />
    <param name="frame_rate" type="double" value="60.0" />
    <param name="pixel_clock" type="int" value="237" />
  </node>

  <!-- SLAVE -->

  <node pkg="nodelet" type="nodelet" name="ueye_cam_nodelet_slave1"
        args="load ueye_cam/ueye_cam_nodelet nodelet_manager">
    <param name="camera_name" type="str" value="slave1" /> <!-- == namespace for topics and services -->
    <param name="camera_topic" type="str" value="image_raw" />
    <param name="camera_id" type="int" value="2" /> <!-- 0 = any camera; 1+: camera ID -->
    <param name="camera_intrinsics_file" type="string" value="" /> <!-- default: ~/.ros/camera_info/<camera_name>.yaml -->
    <param name="camera_parameters_file" type="string" value="" /> <!-- default: ~/.ros/camera_conf/<camera_name>.ini -->

    <param name="ext_trigger_mode" type="bool" value="True" /> <!-- if False, then camera will operate in free-run mode; otherwise, frames need to be triggered by hardware signal (falling-edge) on digital input pin of camera -->

    <!-- the following are optional camera configuration parameters:
         they will be loaded on the camera after the .ini configuration
         file, and before dynamic_reconfigure. That means that any
         (lingering) dynamic parameters from dynamic_reconfigure will
         override these values, and that these will override parameters
         from the .ini file.
         See http://www.ros.org/wiki/ueye_cam for more details. -->

    <param name="color_mode" type="str" value="mono8" /> <!-- valid options: 'rgb8', 'mono8', 'bayer_rggb8' -->
    <param name="image_width" type="int" value="1936" />
    <param name="image_height" type="int" value="1216" />
    <param name="image_top" type="int" value="-1" /> <!-- -1: center -->
    <param name="image_left" type="int" value="-1" /> <!-- -1: center -->   

    <!-- <param name="image_width" type="int" value="640" />
    <param name="image_height" type="int" value="480" /> -->

    <param name="flash_delay" type="int" value="0" />
    <param name="flash_duration" type="int" value="0" />

    <param name="auto_frame_rate" type="bool" value="False" />
    <param name="auto_exposure" type="bool" value="False" />

    <param name="exposure" type="int" value="3" /> <!-- in ms -->
    <param name="pixel_clock" type="int" value="237" />
  </node>

</launch>