Wiki

Only released in EOL distros:  

camera1394

Stack Summary

This is a ROS driver for devices supporting the IEEE 1394 Digital Camera (IIDC) protocol. It supports the ROS image_pipeline, using libdc1394 for device access.

camera_drivers: camera1394 | prosilica_camera | prosilica_gige_sdk | wge100_camera | wge100_camera_firmware

Package Summary

This is a ROS driver for devices supporting the IEEE 1394 Digital Camera (IIDC) protocol. It supports the ROS image_pipeline, using libdc1394 for device access.

camera1394

Package Summary

ROS driver for devices supporting the IEEE 1394 Digital Camera (IIDC) protocol. Supports the ROS image_pipeline, using libdc1394 for device access.

camera1394

Package Summary

ROS driver for devices supporting the IEEE 1394 Digital Camera (IIDC) protocol. Supports the ROS image_pipeline, using libdc1394 for device access.

pr2: audio_common | camera1394 | hokuyo_node | joystick_drivers | linux_networking | microstrain_3dmgx2_imu | pr2_base | pr2_ethercat_drivers | pr2_navigation_apps | pr2_power_drivers | pr2_robot | prosilica_camera | sicktoolbox | sicktoolbox_wrapper | wge100_driver | wifi_ddwrt

Package Summary

ROS driver for devices supporting the IEEE 1394 Digital Camera (IIDC) protocol. Supports the ROS image_pipeline, using libdc1394 for device access.

Package Summary

ROS driver for devices supporting the IEEE 1394 Digital Camera (IIDC) protocol. Supports the ROS image_pipeline, using libdc1394 for device access.

Package Summary

ROS driver for devices supporting the IEEE 1394 Digital Camera (IIDC) protocol. Supports the ROS image_pipeline, using libdc1394 for device access.

Overview

This package provides a ROS interface for digital cameras meeting the IEEE 1394 IIDC standard using libdc1394, which supports many camera makes and models. Of the thousands of IIDC models, we are accumulating a list of cameras tested with this driver.

It works with the ROS image_pipeline like other streaming camera_drivers.

This is a purely monocular driver, stereo applications need a separate driver node for each camera of the pair.

No C++ API is provided. There are no utility commands or launch files.

Support

For help, please check http://answers.ros.org. If your question is not answered, open a new one with the camera1394 tag, so we can see it and respond.

To report problems or request new features: https://github.com/ros-drivers/camera1394/issues

Road Map

The camera1394_node driver was first released with ROS C-Turtle. That API is stable.

Additional features have been added since. They are all compatible with the previous release, except for the default reset_on_open value.

Limitations

IIDC Options

IIDC options still not supported:

Stereo Image Synchronization

It is possible to combine two monocular 1394 cameras to produce a stereo image if they are configured to trigger together. Some IIDC cameras provide trigger synchronization over the 1394 bus or via external hardware.

By default, stereo_image_proc requires the message timestamps for both images to match exactly, which the camera1394 driver cannot do. The Diamondback release of stereo_image_proc provided a solution for this problem (enhancement #4217).

C-Turtle Version

The initial C-Turtle release had some significant limitations. Some have been removed in later releases. Please check the specific documentation for that release, if you are still using ROS C-Turtle.

Features

The IIDC specification lists a number of optional features that may be provided by conforming camera implementations. Many are supported by the driver as parameters. While the spec mentions the names of these features, it does not define what they do. Consult the technical specifications of the camera: manufacturers have great latitude in determining which features to support, what values they can take, and the meanings of those values.

For each supported feature there is a corresponding auto_ parameter providing user control. Different cameras handle these controls in various ways.

The control states are:

When setting an IIDC feature to a specific value, it is necessary to set the corresponding control state to Manual (3), otherwise the corresponding value will be ignored unless the device is already in the Manual state when the driver starts.

For example, to set brightness to 256 on the command line:

$ rosrun camera1394 camera1394_node _auto_brightness:=3 _brightness:=256.0

Bayer filtering

Many IIDC cameras use Bayer filtering to provide color information. For cameras of this type, set video_mode to an appropriate mono8 value, and select the correct bayer_pattern. If the bayer_pattern is "", all mono8 images are monochrome.

This driver provides two alternate mechanisms for decoding Bayer color information:

Best performance is likely to come from using the default bayer_decoding method while running image_proc/debayer and camera1394/driver nodelets both in a single process (see the camera1394_nodelet example below).

In both cases the camera/image_raw image stream is compatible with the ROS image_pipeline.

Format7

IIDC Format7 provides more flexible control of the image. Available options and modes vary greatly between different camera makes and models. Some do not support Format7 at all. Consult the documentation for your particular device to see what it provides.

Format7 parameters specify image size, position and pixel format. Some Format7 modes may provide binning, combining groups of hardware pixels into a single image pixel. The Format7 Region of Interest (ROI) selects a rectangular subset from the full hardware image. These options sometimes allow the camera to send images at a faster rate. (The ~frame_rate parameter has no effect in Format7.)

With an available video_mode selected, a number of Format7-specific parameters may be supported, depending on the device:

All these parameters are ignored when video_mode is not one of the Format7 options.

ROS API

camera1394_node

IEEE 1394 digital camera driver.

Published Topics

camera/image_raw (sensor_msgs/Image) camera/camera_info (sensor_msgs/CameraInfo) diagnostics (diagnostic_msgs/DiagnosticStatus)

Services

camera/set_camera_info (sensor_msgs/SetCameraInfo)

Parameters

Dynamically Reconfigurable Parameters
See the dynamic_reconfigure package for details on dynamically reconfigurable parameters. ~guid (str, default: ) ~reset_on_open (bool, default: False) ~video_mode (str, default: 640x480_mono8) ~frame_id (str, default: camera) ~frame_rate (double, default: 15.0) ~iso_speed (int, default: 400) ~camera_info_url (str, default: ) ~binning_x (int, default: 0) ~binning_y (int, default: 0) ~roi_width (int, default: 0) ~roi_height (int, default: 0) ~x_offset (int, default: 0) ~y_offset (int, default: 0) ~format7_packet_size (int, default: 0) ~format7_color_coding (str, default: mono8) ~bayer_pattern (str, default: ) ~bayer_method (str, default: ) ~auto_brightness (int, default: 1) ~brightness (double, default: 0.0) ~auto_exposure (int, default: 1) ~exposure (double, default: 0.0) ~auto_focus (int, default: 1) ~focus (double, default: 0.0) ~auto_gain (int, default: 1) ~gain (double, default: 0.0) ~auto_gamma (int, default: 1) ~gamma (double, default: 2.2) ~auto_hue (int, default: 1) ~hue (double, default: 0.0) ~auto_iris (int, default: 1) ~iris (double, default: 8.0) ~auto_saturation (int, default: 1) ~saturation (double, default: 1.0) ~auto_sharpness (int, default: 1) ~sharpness (double, default: 1.0) ~auto_shutter (int, default: 1) ~shutter (double, default: 1.0) ~auto_white_balance (int, default: 1) ~white_balance_BU (double, default: 0.0) ~white_balance_RV (double, default: 0.0) ~auto_zoom (int, default: 1) ~zoom (double, default: 0.0) ~num_dma_buffers (int, default: 4) ~max_consecutive_errors (int, default: 0 (disabled))

camera1394_nodelet

Nodelet version of the camera1394 driver.

This driver publishes the same topics and provides the same parameters as the camera1394_node version.

Examples

Run a standalone camera1394_nodelet, this behaves almost the same as running camera1394_node. Running the nodelet standalone does not provide zero-copy message sharing. For that, see the following example.

$ rosrun nodelet nodelet standalone camera1394/driver

To run the driver nodelet and image_proc all in a single address space with zero-copy message passing between those nodelets, use a roslaunch XML file like this:

<launch>

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

  <!-- camera driver nodelet -->
  <node pkg="nodelet" type="nodelet" name="camera1394_nodelet"
        args="load camera1394/driver camera_nodelet_manager" />
    
  <!-- Bayer color decoding -->
  <node pkg="nodelet" type="nodelet" name="image_proc_debayer"
        args="load image_proc/debayer camera_nodelet_manager">
    <remap from="image_color" to="camera/image_color" />
    <remap from="image_mono" to="camera/image_mono" />
    <remap from="image_raw" to="camera/image_raw" />
  </node>

  <!-- mono rectification -->
  <node pkg="nodelet" type="nodelet" name="image_proc_rect"
        args="load image_proc/rectify camera_nodelet_manager">
    <remap from="image_mono" to="camera/image_mono" />
    <remap from="image_rect" to="camera/image_rect" />
  </node>

  <!-- color rectification -->
  <node pkg="nodelet" type="nodelet" name="image_proc_rect_color"
        args="load image_proc/rectify camera_nodelet_manager">
    <remap from="image_mono" to="camera/image_color" />
    <remap from="image_rect" to="camera/image_rect_color" />
  </node>

</launch>

Depending on specific needs, some of the image_proc nodelets could be omitted. But, they do not incur much overhead when not being used.

Wiki: camera1394 (last edited 2016-05-23 15:02:03 by chataign)