Note: This tutorial assumes that you have completed the previous tutorials: Camera Calibration.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

How to Use Multiple IEEE 1394 Cameras

Description: This tutorial explains how to handle multiple IEEE 1394 camera streams with ROS.

Tutorial Level: INTERMEDIATE

Multiple ROS Namespaces

One reasonable approach is to run each camera in its own namespace using $ROS_NAMESPACE or the roslaunch ns parameter. That gives all the topics and parameters unique names so they can be accessed without (much) confusion.

Unique Frame IDs

Each camera needs a unique tf frame of reference identifier. Set it using the frame_id parameter.

Example Launch File

This example assumes the local /cameras directory contains calibration files.

<launch>

  <!-- first camera and associated image pipeline -->
  <group ns="unibrain" >
    <node pkg="camera1394" type="camera1394_node" name="camera1394_node" >
      <param name="guid" value="08144361026320a0" />
      <param name="video_mode" value="640x480_yuv411" />
      <param name="frame_id" value="unibrain" />
      <param name="camera_info_url"
             value="file:///cameras/unibrain_calibration.yaml" />
    </node>
    <node ns="camera" pkg="image_proc" type="image_proc"
          name="image_proc" />
    <node pkg="image_view" type="image_view" name="image_view" >
      <remap from="image" to="camera/image_rect_color" />
    </node>
  </group>

  <!-- second camera and associated image pipeline -->
  <group ns="sony" >
    <node pkg="camera1394" type="camera1394_node" name="camera1394_node" >
      <param name="guid" value="0800461000821fa2" />
      <param name="video_mode" value="1280x960_mono8" />
      <param name="frame_id" value="sony" />
      <param name="bayer_pattern" value="gbrg" />
      <param name="camera_info_url"
             value="file:///cameras/sony_calibration.yaml" />
    </node>
    <node ns="camera" pkg="image_proc" type="image_proc"
          name="image_proc" />
    <node pkg="image_view" type="image_view" name="image_view" >
      <remap from="image" to="camera/image_rect_color" />
    </node>
  </group>

  <!-- monitoring and configuration tools -->
  <node pkg="rxtools" type="rxconsole" name="rxconsole" />
  <node pkg="dynamic_reconfigure" type="reconfigure_gui"
        name="reconfigure_gui" />

</launch>

Grouping Common Elements

With multiple cameras, it is often convenient to group the parameters for each camera in a separate rosparam YAML file.

We can pass equivalent parameters to the first camera by defining /cameras/unibrain.yaml like this:

guid: 08144361026320a0
video_mode: 640x480_yuv411
frame_id: unibrain
camera_info_url: file:///cameras/unibrain_calibration.yaml

For the second camera, define /cameras/sony.yaml like this:

guid: 0800461000821fa2
video_mode: 1280x960_mono8
frame_id: sony
camera_info_url: file:///cameras/sony_calibration.yaml
bayer_pattern: gbrg

It is generally a good idea to organize launch files hierarchically. So, let's create a common launch file for the image_pipeline in /cameras/image_pipeline.launch:

<launch>
  <node ns="camera" pkg="image_proc" type="image_proc" name="image_proc" />
  <node pkg="image_view" type="image_view" name="image_view" >
    <remap from="image" to="camera/image_rect_color" />
  </node>
</launch>

Now, the equivalent launch looks like this:

<launch>

  <!-- first camera and associated image pipeline -->
  <group ns="unibrain" >
    <node pkg="camera1394" type="camera1394_node" name="camera1394_node" >
      <rosparam file="/cameras/unibrain.yaml" /> 
    </node>
    <include file="/cameras/image_pipeline.launch" />
  </group>

  <!-- second camera and associated image pipeline -->
  <group ns="sony" >
    <node pkg="camera1394" type="camera1394_node" name="camera1394_node" >
      <rosparam file="/cameras/sony.yaml" /> 
    </node>
    <include file="/cameras/image_pipeline.launch" />
  </group>

  <!-- monitoring and configuration tools -->
  <node pkg="rxtools" type="rxconsole" name="rxconsole" />
  <node pkg="dynamic_reconfigure" type="reconfigure_gui"
        name="reconfigure_gui" />

</launch>

Setting Feature Values

So far, we started the cameras with whatever feature settings were currently defined in the devices. Sometimes that is useful, but we often want to set them explicitly. The configuring camera features tutorial explained how to do that.

My Sony XCD-SX90CR works better if I set several features in /cameras/sony.yaml explicitly:

guid: 0800461000821fa2
video_mode: 1280x960_mono8
frame_id: sony
camera_info_url: file:///cameras/sony_calibration.yaml
bayer_pattern: gbrg

# set some feature values:
auto_gamma: 3           # Manual
gamma: 2
auto_shutter: 2         # Auto
auto_white_balance: 2   # Auto

Stereo Cameras

The camera1394 driver does not handle stereo cameras directly.

It is possible to combine two monocular 1394 cameras to produce a stereo image if they are configured to trigger at the same time. Some IIDC cameras provide hardware trigger synchronization for this purpose. Since the timestamps of the left and right images will be close, but not identical, use the ~approximate_sync parameter for the stereo_image_proc nodelets and for camera_calibration.

The previous examples did not publish the topic names expected for stereo processing. The stereo image_pipeline components expect the published topic names to be grouped as left/image_raw and right/image_raw. That can be achieved by remapping the topic names as shown in this launch file:

<launch>

  <!-- run both cameras in the stereo_example namespace -->
  <group ns="stereo_example" >

    <!-- left camera -->
    <node pkg="camera1394" type="camera1394_node" name="left_node" >
      <rosparam file="/cameras/left.yaml" />
      <remap from="camera" to="left" />
    </node>

    <!-- right camera -->
    <node pkg="camera1394" type="camera1394_node" name="right_node" >
      <rosparam file="/cameras/right.yaml" />
      <remap from="camera" to="right" />
    </node>

  </group>
</launch>

Note the unique node names assigned to each driver instance.

Wiki: camera1394/Tutorials/UsingMultipleIEEE1394Cameras (last edited 2013-04-17 00:35:59 by JackOQuin)