Note: If your camera is not yet configured, take a look at the following tutorials: Determining the Prosilica's IP address, Configure the Prosilica for a desktop computer, or Configuring the Prosilica for the PR2.
(!) 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.

Introduction to working with the Prosilica camera.

Description: This introduction will teach you how to work with a pre-configured Prosilica camera.

Keywords: prosilica, camera, high res, image, introduction

Tutorial Level: BEGINNER

This is an introduction to using the high-resolution Prosilica camera. It assumes that the camera has already been configured. If you need to configure a new Prosilica camera, please see the other tutorials in this package.

Starting the camera

The camera is started by running the driver node, prosilica_node. An example can be found in the launch file prosilica.launch in the prosilica_camera package. It was most likely started from your robot launch file (for example, on the PR2s, prX.launch). Use rosnode list to see if the node is running.

Streaming mode

The camera can start in two modes. The first is streaming. This mode looks like most other cameras.

Published Topics

image_raw (sensor_msgs/Image)
  • The raw image topic.
camera_info (sensor_msgs/CameraInfo)
  • Camera intrinsics for images published on image_raw.

Polled mode

Since the camera is high resolution, continuous streaming may use up too much bandwidth. So the Prosilica can also be run in a polled mode. In this mode, nothing is published until an image is requested using the request_image (polled_camera/GetPolledImage) service. For example, from the command line, you can request a 100x100 pixel image using:

rosservice call /prosilica/request_image /<response_namespace> '{x_offset: 0, y_offset: 0, height: 100, width: 100}'

Published Topics

<response_namespace>/image_raw (sensor_msgs/Image)
  • The polled image topic for a particular client.
<response_namespace>/camera_info (sensor_msgs/CameraInfo)
  • Camera intrinsics for images published on <response_namespace>/image_raw.

Changing parameters

As for all cameras, the easiest way to change parameters is to use dynamic_reconfigure.

From a GUI:

rosmake dynamic_reconfigure
rosrun dynamic_reconfigure reconfigure_gui

and select prosilica from the drop-down menu.

From the command line or code, use dynparam in the dynamic_reconfigure package.

Switching modes

The mode is controlled by the parameter trigger_mode and can be set to polled or streaming mode.

In the reconfigure_gui, switch the "trigger_mode" field between polled and streaming mode.

Setting other parameters

The reconfigure_gui can be used to set any other of the prosilica_node's parameters.

Viewing Images

Streaming mode

To view images streaming from the camera:

$ rosrun image_view image_view image:=prosilica/image_raw

Polled mode

In polled mode we specify an output namespace to the camera driver. In this example we'll use my_output. First start the image viewer:

$ rosrun image_view image_view image:=my_output/image_raw

This should bring up a blank window. No image is displayed yet because in polled mode, the camera publishes images only on request (by service call). We can issue a request from the command line like this:

$ rosservice call prosilica/request_image my_output '{x_offset: 0, y_offset: 0, height: 100, width: 100}'

This requests an image of the camera's top-left 100x100 region, with publications in my_output. polled_camera contains a node to continually request images, like this:

$ rosrun polled_camera poller 2 camera:=prosilica output:=my_output

This requests images from the camera at 2 Hz.

Processing images

To learn how to process images from the Prosilica camera, see the image pipeline, in particular camera_calibration and image_proc.

Wiki: prosilica_camera/Tutorials/ProsilicaGigECameraIntroduction (last edited 2010-01-22 22:23:33 by PatrickMihelich)