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.

  • There is now a version of the driver that runs as a nodelet.

  • Format7 modes.
  • Focus and Zoom features.
  • The reset_on_open parameter now defaults to False.

  • The driver will only set video_mode or frame_rate parameters to values supported by the device.

  • New in fuerte: camera1394 is now released as a separate, unary stack. Previously, it was included in the camera_drivers stack.

  • New in hydro: pan feature.

  • New in hydro: the driver is now built using catkin. If you are building that version from source, put it in a catkin workspace.

  • New in indigo: added support for software and hardware triggering. Does not yet provide a ROS polled_camera interface, or trigger commands to the device, but a separate node can do it.

  • New in indigo: added get_control_registers and set_control_registers service calls to access device-specific registers.

Limitations

IIDC Options

IIDC options still not supported:

  • Format6 modes
  • Trigger support

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:

  • Off(0): turns the feature off (if possible)

  • Query(1): returns the current mode and (if possible) the value of the feature, with no change to the device

  • Auto(2): the camera sets the value continuously (if possible)

  • Manual(3): sets a specific value from the corresponding parameter (if possible)

  • OnePush(4): the camera sets the value once, then holds it constant (if possible)

  • None(5): the camera does not provide this feature

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:

  • Standard ROS image_pipeline decoding.

    To use this, set the bayer_method parameter to "" (the default). This is the preferred method, it behaves like the other ROS camera drivers.

  • Built-in decoding provided by libdc1394 conversions (now Deprecated).

    To use this, select one of the other bayer_method options. They may have less CPU overhead in some systems, in others they may slow down the camera frame rate since decoding is done in the main driver thread. Performance depends on image size, decoding method, CPU speed and number of processors available. Experimenting with the different options may reveal the best setting for a specific camera and system.

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:

  • ~binning_x and ~binning_y are typically determined by the specific Format7 mode selected, but may need to be provided if the driver fails to automatically detect them.

  • ~roi_width and ~roi_height specify ROI size in units of unbinned pixels.

  • ~x_offset and ~y_offset specify top left corner of the ROI, in unbinned pixels.

  • ~format7_color_coding defines the pixel format.

    For devices providing Bayer color coding, use the raw8 coding and specify the default ~bayer_method, the other Bayer methods are not supported for Format7. The camera should normally define its own ~bayer_pattern in this mode.

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)
  • A stream of images from the camera.
camera/camera_info (sensor_msgs/CameraInfo)
  • Camera intrinsics for images published on camera/image_raw with matching time stamps and frame IDs. If CameraInfo calibration is not available or is incompatible with the current video_mode, uncalibrated data will be provided instead.
diagnostics (diagnostic_msgs/DiagnosticStatus)
  • Diagnostic status, with camera frame rate (New in fuerte).

Services

camera/set_camera_info (sensor_msgs/SetCameraInfo)
  • Set the camera's calibration.

Parameters

Dynamically Reconfigurable Parameters
See the dynamic_reconfigure package for details on dynamically reconfigurable parameters.
~guid (str, default: )
  • Global Unique ID of camera, 16 hex digits (use first camera if null).
~reset_on_open (bool, default: False)
  • Reset camera when opening the device.
~video_mode (str, default: 640x480_mono8)
  • IIDC video mode. Possible values are: Format0_Mode0 (160x120_yuv444): , Format0_Mode1 (320x240_yuv422): , Format0_Mode2 (640x480_yuv411): , Format0_Mode3 (640x480_yuv422): , Format0_Mode4 (640x480_rgb8): , Format0_Mode5 (640x480_mono8): , Format0_Mode6 (640x480_mono16): , Format1_Mode0 (800x600_yuv422): , Format1_Mode1 (800x600_rgb8): , Format1_Mode2 (800x600_mono8): , Format1_Mode6 (800x600_mono16): , Format1_Mode3 (1024x768_yuv422): , Format1_Mode4 (1024x768_rgb8): , Format1_Mode5 (1024x768_mono8): , Format1_Mode7 (1024x768_mono16): , Format2_Mode0 (1280x960_yuv422): , Format2_Mode1 (1280x960_rgb8): , Format2_Mode2 (1280x960_mono8): , Format2_Mode6 (1280x960_mono16): , Format2_Mode3 (1600x1200_yuv422): , Format2_Mode4 (1600x1200_rgb8): , Format2_Mode5 (1600x1200_mono8): , Format2_Mode7 (1600x1200_mono16): , Format7_Mode0 (format7_mode0): , Format7_Mode1 (format7_mode1): , Format7_Mode2 (format7_mode2): , Format7_Mode3 (format7_mode3): , Format7_Mode4 (format7_mode4): , Format7_Mode5 (format7_mode5): , Format7_Mode6 (format7_mode6): , Format7_Mode7 (format7_mode7):
~frame_id (str, default: camera)
  • ROS tf frame of reference, resolved with tf_prefix unless absolute.
~frame_rate (double, default: 15.0)
  • Camera speed (frames per second). Range: 1.875 to 240.0
~iso_speed (int, default: 400)
  • Total IEEE 1394 bus bandwidth (Megabits/second). Range: 100 to 3200
~camera_info_url (str, default: ) ~binning_x (int, default: 0)
  • Number of pixels combined for Format7 horizontal binning, use device hints if zero. Range: 0 to 4
~binning_y (int, default: 0)
  • Number of pixels combined for Format7 vertical binning, use device hints if zero. Range: 0 to 4
~roi_width (int, default: 0)
  • Width of Format7 Region of Interest in unbinned pixels, full width if zero. Range: 0 to 65535
~roi_height (int, default: 0)
  • Height of Format7 Region of Interest in unbinned pixels, full height if zero. Range: 0 to 65535
~x_offset (int, default: 0)
  • Horizontal offset for left side of Format7 ROI in unbinned pixels. Range: 0 to 65535
~y_offset (int, default: 0)
  • Vertical offset for top of Format7 ROI in unbinned pixels. Range: 0 to 65535
~format7_packet_size (int, default: 0)
  • Format7 packet size (bytes), device-recommended size if zero. Range: 0 to 39320
~format7_color_coding (str, default: mono8)
  • Color coding (only for Format7 modes) Possible values are: "mono8", "mono16", "mono16s", "raw8", "raw16", "rgb8", "rgb16", "rgb16s", "yuv411", "yuv422", "yuv444"
~bayer_pattern (str, default: )
  • Bayer color encoding pattern (default: ""). Possible values are: "": No Bayer encoding, "rggb", "gbrg", "grbg", "bggr".
~bayer_method (str, default: )
  • Bayer decoding method (default: ROS image_proc). Possible values are: "": Decode via ROS image_proc, "DownSample", "Simple", "Bilinear", "HQ", "VNG", "AHD"
~auto_brightness (int, default: 1)
  • Brightness control state. Possible values are: Off (0): Use fixed value, Query (1): Query current values, Auto (2): Camera sets continuously, Manual (3): Use explicit value, OnePush (4): Camera sets once, None (5): Feature not available
~brightness (double, default: 0.0)
  • Black level offset. Range: 0.0 to 4095.0
~auto_exposure (int, default: 1)
  • Combined Gain, Iris & Shutter control. Possible values are: Off (0): Use fixed value, Query (1): Query current values, Auto (2): Camera sets continuously, Manual (3): Use explicit value, OnePush (4): Camera sets once, None (5): Feature not available
~exposure (double, default: 0.0)
  • Auto exposure value (like contrast). Range: -10.0 to 4095.0
~auto_focus (int, default: 1)
  • Focus control state. Possible values are: Off (0): Use fixed value, Query (1): Query current values, Auto (2): Camera sets continuously, Manual (3): Use explicit value, OnePush (4): Camera sets once, None (5): Feature not available
~focus (double, default: 0.0)
  • Focus control. Range: 0.0 to 4095.0
~auto_gain (int, default: 1)
  • Gain control state. Possible values are: Off (0): Use fixed value, Query (1): Query current values, Auto (2): Camera sets continuously, Manual (3): Use explicit value, OnePush (4): Camera sets once, None (5): Feature not available
~gain (double, default: 0.0)
  • Relative circuit gain. Range: -10.0 to 4095.0
~auto_gamma (int, default: 1)
  • Gamma control state. Possible values are: Off (0): Use fixed value, Query (1): Query current values, Auto (2): Camera sets continuously, Manual (3): Use explicit value, OnePush (4): Camera sets once, None (5): Feature not available
~gamma (double, default: 2.2)
  • Gamma expansion exponent. Range: 0.0 to 10.0
~auto_hue (int, default: 1)
  • Hue control state. Possible values are: Off (0): Use fixed value, Query (1): Query current values, Auto (2): Camera sets continuously, Manual (3): Use explicit value, OnePush (4): Camera sets once, None (5): Feature not available
~hue (double, default: 0.0)
  • Color phase. Range: 0.0 to 4095.0
~auto_iris (int, default: 1)
  • Iris control state. Possible values are: Off (0): Use fixed value, Query (1): Query current values, Auto (2): Camera sets continuously, Manual (3): Use explicit value, OnePush (4): Camera sets once, None (5): Feature not available
~iris (double, default: 8.0)
  • Iris control. Range: 0.0 to 4095.0
~auto_saturation (int, default: 1)
  • Saturation control state. Possible values are: Off (0): Use fixed value, Query (1): Query current values, Auto (2): Camera sets continuously, Manual (3): Use explicit value, OnePush (4): Camera sets once, None (5): Feature not available
~saturation (double, default: 1.0)
  • Color saturation. Range: 0.0 to 4095.0
~auto_sharpness (int, default: 1)
  • Sharpness control state. Possible values are: Off (0): Use fixed value, Query (1): Query current values, Auto (2): Camera sets continuously, Manual (3): Use explicit value, OnePush (4): Camera sets once, None (5): Feature not available
~sharpness (double, default: 1.0)
  • Image sharpness. Range: 0.0 to 4095.0
~auto_shutter (int, default: 1)
  • Shutter control state. Possible values are: Off (0): Use fixed value, Query (1): Query current values, Auto (2): Camera sets continuously, Manual (3): Use explicit value, OnePush (4): Camera sets once, None (5): Feature not available
~shutter (double, default: 1.0)
  • Shutter speed. Range: 0.0 to 4095.0
~auto_white_balance (int, default: 1)
  • White balance control state. Possible values are: Off (0): Use fixed value, Query (1): Query current values, Auto (2): Camera sets continuously, Manual (3): Use explicit value, OnePush (4): Camera sets once, None (5): Feature not available
~white_balance_BU (double, default: 0.0)
  • Blue or U component of white balance. Range: 0.0 to 4095.0
~white_balance_RV (double, default: 0.0)
  • Red or V component of white balance. Range: 0.0 to 4095.0
~auto_zoom (int, default: 1)
  • Zoom control state. Possible values are: Off (0): Use fixed value, Query (1): Query current values, Auto (2): Camera sets continuously, Manual (3): Use explicit value, OnePush (4): Camera sets once, None (5): Feature not available
~zoom (double, default: 0.0)
  • Zoom control. Range: 0.0 to 4095.0
~num_dma_buffers (int, default: 4)
  • Number of frames in the DMA ring buffer (New in indigo).
~max_consecutive_errors (int, default: 0 (disabled))
  • Max number of consecutive read errors before attempting reconnection (0 to disable)

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)