Overview

This package contains a ROS driver node for IDS Imaging uEye cameras.

The driver node has been tested with the version 4.60 https://en.ids-imaging.com/download-ueye.html for USB cameras. Future versions should be ABI compatible, and therefore should work.

This package can be installed with apt-get. However, the IDS Imaging driver mentioned above must also be installed.

The driver node has been tested with the following cameras:

  • UI-1225LE-C
  • UI-124xLE-C
  • UI-164xLE-C
  • UI-222xSE-C (two cameras synchronized for stereo)
  • UI-324xCP-C

Nodes

camera

ROS driver node for uEye cameras.

Published Topics

image_raw (sensor_msgs/Image)
  • The raw image topic.
camera_info (sensor_msgs/CameraInfo)
  • Calibration info for each image.

Services

set_camera_info (sensor_msgs/SetCameraInfo)
  • Sets the calibration parameters saved to a file.

Parameters

~cameraId (int)
  • Id of the camera to open. Zero for any.
~force_streaming (bool)
  • Force camera to stream images. If false, streaming will stop if no nodes subscribe to the image topic.
~hardware_gamma (bool)
  • Enable hardware gamma correction if the camera supports it.
~auto_exposure (bool)
  • Enable auto-exposure time if the camera supports it.
~exposure_time (double)
  • Exposure time in milliseconds if ~auto_exposure is false.
~zoom (int)
  • Zoom level with global binning.
~frame_rate (double)
  • Image stream rate. The node will not allow ~frame_rate to exceed the limits of the camera with the constraints of other parameters such as ~zoom and ~pixel_clock.
~pixel_clock (int)
  • Pixel clock speed for USB in MHz.
~frame_id (string)
  • The tf frame_id in the published message headers.
~auto_gain (bool)
  • Enable automatic hardware gain if the camera supports it.
~gain_boost (bool)
  • Enables constant hardware analog gain boost if the camera supports it.
~gain (int)
  • Sets the image hardware gain if ~auto_gain is false.

framerate

Node that displays the actual rate of an image stream.

Subscribed Topics

image_raw (sensor_msgs/Image)
  • The raw image topic.

Parameters

~topic (string)
  • Topic name of the image stream to subscribe to.

Usage

To run stereo cameras

$ rosrun ueye stereo

You might want to lower resolution by setting the zoom parameter

$ rosrun ueye stereo _zoom:=2

In case there are multiple cameras connected, you can choose the cameras that will be used by specifying the camera ids.

$ rosrun ueye stereo _lCameraId:=1 _rCameraId:=3

Camera Calibration

The camera node supports calibration with the camera_calibration package.

There are tutorials on how to run the calibration tool for monocular and stereo cameras.

Wiki: ueye (last edited 2016-06-03 07:51:37 by LeonhardtSchwarz)