Camera

The camera module is a base module which is available on every rc_visard NG and is responsible for image acquisition and rectification. It provides various parameters, e.g. to control exposure and frame rate.

Rectification

To simplify image processing, the camera module rectifies all camera images based on the camera calibration. This means that lens distortion is removed and the principal point is located exactly in the middle of the image.

The model of a rectified camera is described with just one value, which is the focal length. The rc_visard NG reports a focal length factor via its various interfaces. It relates to the image width for supporting different image resolutions. The focal length \(f\) in pixels can be easily obtained by multiplying the focal length factor by the image width in pixels.

In case of a stereo camera, rectification also aligns images such that an object point is always projected onto the same image row in both images. The cameras’ optical axes become exactly parallel.

Viewing and downloading images

The rc_visard NG provides the time-stamped, rectified images over the GenICam interface (see Provided image streams). Live streams of the images are provided with reduced quality in the Web GUI.

The Web GUI also provides the possibility to download a snapshot of the current scene as a .tar.gz file as described in Downloading camera images.

Parameters

The camera software module is called rc_camera and is represented by the Camera page in the Web GUI. The user can change the camera parameters there, or directly via the REST-API (REST-API interface) or GigE Vision (GigE Vision 2.0/GenICam image interface).

Note

Camera parameters cannot be changed via the Web GUI or REST-API if rc_visard NG is used via GigE Vision.

Parameter overview

This module offers the following run-time parameters:

Table 6 The rc_camera module’s run-time parameters
Name Type Min Max Default Description
exp_auto bool false true true Switching between auto and manual exposure (deprecated, please use exp_control instead)
exp_auto_average_max float64 0.0 1.0 0.75 Maximum average intensity in Auto exposure mode
exp_auto_average_min float64 0.0 1.0 0.25 Minimum average intensity in Auto exposure mode
exp_auto_mode string - - Normal Auto-exposure mode: [Normal, Out1High, AdaptiveOut1]
exp_control string - - Auto Exposure control mode: [Manual, Auto, HDR]
exp_height int32 0 959 0 Height of auto exposure region. 0 for whole image.
exp_max float64 6.6e-05 0.018 0.018 Maximum exposure time in seconds in Auto exposure mode
exp_offset_x int32 0 1279 0 First column of auto exposure region
exp_offset_y int32 0 959 0 First row of auto exposure region
exp_value float64 6.6e-05 0.018 0.005 Exposure time in seconds in Manual exposure mode
exp_width int32 0 1279 0 Width of auto exposure region. 0 for whole image.
fps float64 1.0 25.0 25.0 Frames per second in Hertz
gain_value float64 0.0 18.0 0.0 Gain value in decibel if not in Auto exposure mode
gamma float64 0.1 10.0 1.0 Gamma factor
wb_auto bool false true true Switching white balance on and off (only for color camera)
wb_ratio_blue float64 0.125 8.0 2.4 Blue to green balance ratio if wb_auto is false (only for color camera)
wb_ratio_red float64 0.125 8.0 1.2 Red to green balance ratio if wb_auto is false (only for color camera)

Description of run-time parameters

_images/webgui_camera_ng_en.png

Fig. 15 The Web GUI’s Camera page

fps (FPS)

This value is the cameras’ frame rate (fps, frames per second), which determines the upper frequency at which depth images can be computed. This is also the frequency at which the rc_visard NG delivers images via GigE Vision. Reducing this frequency also reduces the network bandwidth required to transmit the images.

Via the REST-API, this parameter can be set as follows.

PUT http://<host>/api/v2/pipelines/0/nodes/rc_camera/services/parameters?fps=<value>
PUT http://<host>/api/v1/nodes/rc_camera/parameters?fps=<value>

The camera always runs with 25 Hz to ensure proper working of internal modules such as visual odometry that need a constant frame rate. The user frame rate setting is implemented by excluding frames for stereo matching and transmission via GigE Vision to reduce bandwidth as shown in figure Fig. 16.

_images/fps_ng_en.png

Fig. 16 Images are internally always captured with 25 Hz. The fps parameter determines how many of them are sent as camera images via GigE Vision.

gamma (Gamma)

The gamma value determines the mapping of perceived light to the brightness of a pixel. A gamma value of 1 corresponds to a linear relationship. Lower gamma values let dark image parts appear brighter. A value around 0.5 corresponds to human vision.

Via the REST-API, this parameter can be set as follows.

PUT http://<host>/api/v2/pipelines/0/nodes/rc_camera/services/parameters?gamma=<value>
PUT http://<host>/api/v1/nodes/rc_camera/parameters?gamma=<value>

exp_control (Exposure Auto, HDR or Manual)

The exposure control mode can be set to Auto, HDR or Manual. This replaces the deprecated exp_auto parameter.

Auto: This is the default mode in which the exposure time and gain factor is chosen automatically to correctly expose the image. The last automatically determined exposure and gain values are set into exp_value and gain_value when switching auto-exposure off.

HDR: The HDR mode computes high-dynamic-range images by combining images with different exposure times to avoid under-exposed and over-exposed areas. This decreases the frame rate and is only suitable for static scenes.

Manual: In the manual exposure mode the exposure time and gain are kept fixed independent of the resulting image brightness.

Via the REST-API, this parameter can be set as follows.

PUT http://<host>/api/v2/pipelines/0/nodes/rc_camera/services/parameters?exp_control=<value>
PUT http://<host>/api/v1/nodes/rc_camera/parameters?exp_control=<value>

exp_auto (deprecated)

This parameter is deprecated and will be removed in a future release. Please use exp_control.

This value can be set to true for auto-exposure mode, or to false for manual exposure mode. In manual exposure mode, the chosen exposure time is kept, even if the images are overexposed or underexposed. In auto-exposure mode, the exposure time and gain factor is chosen automatically to correctly expose the image. The last automatically determined exposure and gain values are set into exp_value and gain_value when switching auto-exposure off.

Via the REST-API, this parameter can be set as follows.

PUT http://<host>/api/v2/pipelines/0/nodes/rc_camera/services/parameters?exp_auto=<value>
PUT http://<host>/api/v1/nodes/rc_camera/parameters?exp_auto=<value>

exp_auto_mode (Auto Exposure Mode)

The auto exposure mode can be set to Normal, Out1High or AdaptiveOut1. These modes are relevant when the rc_visard NG is used with an external light source or projector connected to the rc_visard’s or rc_viscore’s GPIO Out1, which can be controlled by the IOControl module (IO and Projector Control).

Normal: All images are considered for exposure control, except if the IOControl mode for GPIO Out1 is ExposureAlternateActive: then only images where GPIO Out1 is HIGH will be considered, since these images may be brighter in case GPIO Out1 is used to trigger an external light source.

Out1High: This exposure mode adapts the exposure time using only images with GPIO Out1 HIGH. Images where GPIO Out1 is LOW are not considered at all, which means, that the exposure time does not change when only images with Out1 LOW are acquired. This mode is recommended for using the acquisition_mode SingleFrameOut1 in the stereo matching module as described in Stereo Matching Parameters and having an external projector connected to GPIO Out1, when changes in the brightness of the scene should only be considered when Out1 is HIGH. This is the case, for example, when a bright part of the robot moves through the field of view of the camera just before a detection is triggered, which should not affect the exposure time.

AdaptiveOut1: This exposure mode uses all camera images and tracks the exposure difference between images with GPIO Out1 LOW and HIGH. While the IOControl mode for GPIO Out1 is LOW, the images are under-exposed by this exposure difference to avoid over-exposure for when GPIO Out1 triggers an external projector. The resulting exposure difference is given as Out1 Reduction below the live images. This mode is recommended for using the acquisition_mode SingleFrameOut1 in the stereo matching module as described in Stereo Matching Parameters and having an external projector connected to GPIO Out1, when changes in the brightness of the scene should be considered at all times. This is the case, for example, in applications where the external lighting changes.

Via the REST-API, this parameter can be set as follows.

PUT http://<host>/api/v2/pipelines/0/nodes/rc_camera/services/parameters?exp_auto_mode=<value>
PUT http://<host>/api/v1/nodes/rc_camera/parameters?exp_auto_mode=<value>

exp_max (Max Exposure)

This value is the maximal exposure time in auto-exposure mode in seconds. The actual exposure time is adjusted automatically so that the images are exposed correctly. If the maximum exposure time is reached, but the images are still underexposed, the rc_visard NG stepwise increases the gain to increase the images’ brightness. Limiting the exposure time is useful for avoiding or reducing motion blur during fast movements. However, higher gain introduces noise into the image. The best trade-off depends on the application.

Via the REST-API, this parameter can be set as follows.

PUT http://<host>/api/v2/pipelines/0/nodes/rc_camera/services/parameters?exp_max=<value>
PUT http://<host>/api/v1/nodes/rc_camera/parameters?exp_max=<value>

exp_auto_average_max (Max Brightness) and exp_auto_average_min (Min Brightness)

The auto-exposure tries to set the exposure time and gain factor such that the average intensity (i.e. brightness) in the image or exposure region is between a maximum and a minimum. The maximum brightness will be used if there is no saturation, e.g. no over-exposure due to bright surfaces or reflections. In case of saturation, the exposure time and gain factor are reduced, but only down to the minimum brightness.

The maximum brightness has precedence over the minimum brightness parameter. If the minimum brightness is larger than the maximum brightness, the auto-exposure always tries to make the average intensity equal to the maximum brightness.

The current brightness is always shown in the status bar below the images.

Via the REST-API, this parameter can be set as follows.

PUT http://<host>/api/v2/pipelines/0/nodes/rc_camera/services/parameters?<exp_auto_average_max|exp_auto_average_min>=<value>
PUT http://<host>/api/v1/nodes/rc_camera/parameters?<exp_auto_average_max|exp_auto_average_min>=<value>

exp_offset_x, exp_offset_y, exp_width, exp_height (Exposure Region)

These values define a rectangular region in the left rectified image for limiting the area used for computing the auto exposure. The exposure time and gain factor of both images are chosen to optimally expose the defined region. This can lead to over- or underexposure of image parts outside the defined region. If either the width or height is 0, then the whole left and right images are considered by the auto exposure function. This is the default.

The region is visualized in the Web GUI by a rectangle in the left rectified image. It can be defined using the sliders or by selecting it in the image after pressing the button Select Region in Image.

Via the REST-API, this parameter can be set as follows.

PUT http://<host>/api/v2/pipelines/0/nodes/rc_camera/services/parameters?<exp_offset_x|exp_offset_y|exp_width|exp_height>=<value>
PUT http://<host>/api/v1/nodes/rc_camera/parameters?<exp_offset_x|exp_offset_y|exp_width|exp_height>=<value>

exp_value (Exposure)

This value is the exposure time in manual exposure mode in seconds. This exposure time is kept constant even if the images are underexposed.

Via the REST-API, this parameter can be set as follows.

PUT http://<host>/api/v2/pipelines/0/nodes/rc_camera/services/parameters?exp_value=<value>
PUT http://<host>/api/v1/nodes/rc_camera/parameters?exp_value=<value>

gain_value (Gain)

This value is the gain factor in decibel that can be set in manual exposure mode. Higher gain factors reduce the required exposure time but introduce noise.

Via the REST-API, this parameter can be set as follows.

PUT http://<host>/api/v2/pipelines/0/nodes/rc_camera/services/parameters?gain_value=<value>
PUT http://<host>/api/v1/nodes/rc_camera/parameters?gain_value=<value>

wb_auto (White Balance Auto or Manual)

This value can be set to true for automatic white balancing or false for manually setting the ratio between the colors using wb_ratio_red and wb_ratio_blue. The last automatically determined ratios are set into wb_ratio_red and wb_ratio_blue when switching automatic white balancing off. White balancing is without function for monochrome cameras and will not be displayed in the Web GUI in this case.

Via the REST-API, this parameter can be set as follows.

PUT http://<host>/api/v2/pipelines/0/nodes/rc_camera/services/parameters?wb_auto=<value>
PUT http://<host>/api/v1/nodes/rc_camera/parameters?wb_auto=<value>

wb_ratio_blue and wb_ratio_red (Blue | Green and Red | Green)

These values are used to set blue to green and red to green ratios for manual white balance. White balancing is without function for monochrome cameras and will not be displayed in the Web GUI in this case.

Via the REST-API, this parameter can be set as follows.

PUT http://<host>/api/v2/pipelines/0/nodes/rc_camera/services/parameters?<wb_ratio_blue|wb_ratio_red>=<value>
PUT http://<host>/api/v1/nodes/rc_camera/parameters?<wb_ratio_blue|wb_ratio_red>=<value>

These parameters are also available over the GenICam interface with slightly different names and partly with different units or data types (see GigE Vision 2.0/GenICam image interface).

Status values

This module reports the following status values:

Table 7 The rc_camera module’s status values
Name Description
baseline Stereo baseline \(t\) in meters
brightness Current brightness of the image as value between 0 and 1
color 0 for monochrome cameras, 1 for color cameras
exp Current exposure time in seconds. This value is shown below the image preview in the Web GUI as Exposure (ms).
focal Focal length factor normalized to an image width of 1
fps Current frame rate of the camera images in Hertz. This value is shown in the Web GUI below the image preview as FPS (Hz).
gain Current gain factor in decibel. This value is shown in the Web GUI below the image preview as Gain (dB).
gamma Current gamma value.
height Height of the camera image in pixels. This value is shown in the Web GUI below the image preview as the second part of Resolution (px).
out1_reduction Fraction of reduction (0.0 - 1.0) of brightness for images with GPIO Out1=LOW in exp_auto_mode=AdaptiveOut1 or exp_auto_mode=Out1High. This value is shown in the Web GUI below the image preview as Out1 Reduction (%).
params_override_active 1 if parameters are temporarily overwritten by a calibration process
temp_left Temperature of the left camera sensor in degrees Celsius
temp_right Temperature of the right camera sensor in degrees Celsius
test 0 for live images and 1 for test images
time Processing time for image grabbing in seconds
width Width of the camera image in pixels. This value is shown in the Web GUI below the image preview as the first part of Resolution (px).

Services

The camera module offers the following services.

reset_defaults

Restores and applies the default values for this module’s parameters (“factory reset”).

Details

This service can be called as follows.

PUT http://<host>/api/v2/pipelines/0/nodes/rc_camera/services/reset_defaults
PUT http://<host>/api/v1/nodes/rc_camera/services/reset_defaults
This service has no arguments.

The definition for the response with corresponding datatypes is:

{
  "name": "reset_defaults",
  "response": {
    "return_code": {
      "message": "string",
      "value": "int16"
    }
  }
}