GigE Vision 2.0/GenICam image interface

Gigabit Ethernet for Machine Vision (“GigE Vision®” for short) is an industrial camera interface standard based on UDP/IP (see http://www.gigevision.com). The rc_visard is a GigE Vision® version 2.0 device and is hence compatible with all GigE Vision® 2.0 compliant frameworks and libraries.

GigE Vision® uses GenICam to describe the camera/device features. For more information about this Generic Interface for Cameras see http://www.genicam.org/.

Via this interface the rc_visard provides features such as

  • discovery,
  • IP configuration,
  • configuration of camera related parameters,
  • image grabbing, and
  • time synchronization via IEEE 1588-2008 PrecisionTimeProtocol (PTPv2).

Note

The rc_visard supports jumbo frames of up to 9000 bytes. Setting an MTU of 9000 on your GigE Vision client side is recommended for best performance.

Note

Roboception provides tools and a C++ API with examples for discovery, configuration, and image streaming via the GigE Vision/GenICam interface. See http://www.roboception.com/download.

GigE Vision ports

GigE Vision is a UDP based protocol. On the rc_visard the UDP ports are fixed and known:

  • UDP port 3956: GigE Vision Control Protocol (GVCP). Used for discovery, control and configuration.
  • UDP port 50010: Stream channel source port for GigE Vision Stream Protocol (GVSP) used for image streaming.

Important GenICam parameters

The following list gives an overview of the relevant GenICam features of the rc_visard that can be read and/or changed via the GenICam interface. In addition to the standard parameters, which are defined in the Standard Feature Naming Convention (SFNC, see http://www.emva.org/standards-technology/genicam/genicam-downloads/), rc_visard devices also offer custom parameters that account for special features of the Stereo camera and the Stereo matching component.

Important standard GenICam features

Category: ImageFormatControl

ComponentSelector
  • type: Enumeration, one of Intensity, IntensityCombined, Disparity, Confidence, or Error
  • default: -
  • description: Allows the user to select one of the five image streams for configuration (see Provided image streams).
ComponentIDValue (read-only)
  • type: Integer
  • description: The ID of the image stream selected by the ComponentSelector.
ComponentEnable
  • type: Boolean
  • default: -
  • description: If set to true, it enables the image stream selected by ComponentSelector; otherwise, it disables the stream. Using ComponentSelector and ComponentEnable, individual image streams can be switched on and off.
Width (read-only)
  • type: Integer
  • description: Image width in pixel of image stream that is currently selected by ComponentSelector.
Height (read-only)
  • type: Integer
  • description: Image height in pixel of image stream that is currently selected by ComponentSelector.
WidthMax (read-only)
  • type: Integer
  • description: Maximum width of an image, which is always 1280 pixels.
HeightMax (read-only)
  • type: Integer
  • description: Maximum height of an image in the streams. This is always 1920 pixels due to the stacked left and right images in the IntensityCombined stream (see Provided image streams).
PixelFormat
  • type: Enumeration, one of Mono8, YCbCr411_8 (color cameras only), Coord3D_C16, Confidence8 and Error8
  • description: Pixel format of the selected component. The enumeration only permits to choose the format among the possibly formats for the selected component. For a color camera, Mono8 or YCbCr411_8 can be chosen for the Intensity and IntensityCombined component.

Category: AcquisitionControl

AcquisitionFrameRate
  • type: Float, ranges from 1 Hz to 25 Hz
  • default: 25 Hz
  • description: Frame rate of the camera (FPS).
ExposureAuto
  • type: Enumeration, one of Continuous, AdaptiveOut1 or Off
  • default: Continuous
  • description: Can be set to Off for manual exposure mode, to Continuous or AdaptiveOut1 for auto exposure. The value Continuous maps to the value Normal of the exp_auto_mode (auto exposure mode) and AdaptiveOut1 to the mode of the same name.
ExposureTime
  • type: Float, ranges from 66 µs to 18000 µs
  • default: 5000 µs
  • description: The cameras’ exposure time in microseconds for the manual exposure mode (Exposure).

Category: AnalogControl

GainSelector (read-only)
  • type: Enumeration, is always All
  • default: All
  • description: The rc_visard currently supports only one overall gain setting.
Gain
  • type: Float, ranges from 0 dB to 18 dB
  • default: 0 dB
  • description: The cameras’ gain value in decibel that is used in manual exposure mode (Gain).
BalanceWhiteAuto (color cameras only)
  • type: Enumeration, one of Continuous or Off
  • default: Continuous
  • description: Can be set to Off for manual white balancing mode or to Continuous for auto white balancing. This feature is only available on color cameras (wb_auto).
BalanceRatioSelector (color cameras only)
  • type: Enumeration, one of Red or Blue
  • default: Red
  • description: Selects ratio to be modified by BalanceRatio. Red means red to green ratio and Blue means blue to green ratio. This feature is only available on color cameras.
BalanceRatio (color cameras only)
  • type: Float, ranges from 0.125 to 8
  • default: 1.2 if Red and 2.4 if Blue is selected in BalanceRatioSelector
  • description: Weighting of red or blue to green color channel. This feature is only available on color cameras (wb_ratio).

Category: DigitalIOControl

Note

If IOControl license is not available, then the outputs will be configured according to the factory defaults and cannot be changed. The inputs will always return the logic value false, regardless of the signals on the physical inputs.

LineSelector
  • type: Enumeration, one of Out1, Out2, In1 or In2
  • default: Out1
  • description: Selects the input or output line for getting the current status or setting the source.
LineStatus (read-only)
  • type: Boolean
  • description: Current status of the line selected by LineSelector.
LineStatusAll (read-only)
  • type: Integer
  • description: Current status of GPIO inputs and outputs represented in the lowest four bits.
Table 51 Meaning of bits of LineStatusAll field.
Bit 4 3 2 1
GPIO In 2 In 1 Out 2 Out 1
LineSource (read-only if IOControl component is not licensed)
  • type: Enumeration, one of ExposureActive, ExposureAlternateActive, Low or High
  • default: Low
  • description: Mode for output line selected by LineSelector as described in the IOControl module (out1_mode and out2_mode). See also parameter AcquisitionAlternateFilter for filtering images in ExposureAlternateActive mode.

Category: TransportLayerControl / PtpControl

PtpEnable
  • type: Boolean
  • default: false
  • description: Switches PTP synchronization on and off.

Category: Scan3dControl

Scan3dDistanceUnit (read-only)
  • type: Enumeration, is always Pixel
  • description: Unit for the disparity measurements, which is always Pixel.
Scan3dOutputMode (read-only)
  • type: Enumeration, is always DisparityC
  • description: Mode for the depth measurements, which is always DisparityC.
Scan3dFocalLength (read-only)
  • type: Float
  • description: Focal length in pixel of image stream selected by ComponentSelector. In case of the component Disparity, Confidence and Error, the value also depends on the resolution that is implicitely selected by DepthQuality.
Scan3dBaseline (read-only)
  • type: Float
  • description: Baseline of the stereo camera in meters.
Scan3dPrinciplePointU (read-only)
  • type: Float
  • description: Horizontal location of the principle point in pixel of image stream selected by ComponentSelector. In case of the component Disparity, Confidence and Error, the value also depends on the resolution that is implicitely selected by DepthQuality.
Scan3dPrinciplePointV (read-only)
  • type: Float
  • description: Vertical location of the principle point in pixel of image stream selected by ComponentSelector. In case of the component Disparity, Confidence and Error, the value also depends on the resolution that is implicitely selected by DepthQuality.
Scan3dCoordinateScale (read-only)
  • type: Float
  • description: The scale factor that has to be multiplied with the disparity values in the disparity image stream to get the actual disparity measurements. This value is always 0.0625.
Scan3dCoordinateOffset (read-only)
  • type: Float
  • description: The offset that has to be added to the disparity values in the disparity image stream to get the actual disparity measurements. For the rc_visard, this value is always 0 and can therefore be disregarded.
Scan3dInvalidDataFlag (read-only)
  • type: Boolean
  • description: Is always true, which means that invalid data in the disparity image is marked by a specific value defined by the Scan3dInvalidDataValue parameter.
Scan3dInvalidDataValue (read-only)
  • type: Float
  • description: Is the value which stands for invalid disparity. This value is always 0, which means that disparity values of 0 correspond to invalid measurements. To distinguish between invalid disparity measurements and disparity measurements of 0 for objects which are infinitely far away, the rc_visard sets the disparity value for the latter to the smallest possible disparity value of 0.0625. This still corresponds to an object distance of several hundred meters.

Category: ChunkDataControl

ChunkModeActive
  • type: Boolean
  • default: False
  • description: Enables chunk data that is delivered with every image.

Custom GenICam features of the rc_visard

Category: AcquisitionControl

AcquisitionAlternateFilter (read-only if IOControl component is not licensed)
  • type: Enumeration, one of Off, OnlyHigh or OnlyLow
  • default: Off
  • description: If this parameter is set to OnlyHigh (or OnlyLow) and the LineSource is set to ExposureAlternateActive for any output, then only camera images are delivered that are captured while the output is high, i.e. a potentially connected projector is on (or low, i.e. a potentially connected projector is off). This parameter is a simple means for only getting images without projected pattern. The minimal time difference between camera and disparity images will be about 40 ms in this case (see IOControl).
AcquisitionMultiPartMode
  • type: Enumeration, one of SingleComponent or SynchronizedComponents
  • default: SingleComponent
  • description: Only effective in MultiPart mode. If this parameter is set to SingleComponent the images are sent immediately as a single component per frame/buffer when they become available. This is the same behavior as when MultiPart is not supported by the client. If set to SynchronizedComponents all enabled components are time synchronized on the rc_visard and only sent (in one frame/buffer) when they are all available for that timestamp.
ExposureTimeAutoMax
  • type: Float, ranges from 66 µs to 18000 µs
  • default: 18000 µs
  • description: Maximal exposure time in auto exposure mode (Max Exposure).
ExposureRegionOffsetX
  • type: Integer in the range of 0 to 1280
  • default: 0
  • description: Horizontal offset of exposure region in pixel.
ExposureRegionOffsetY
  • type: Integer in the range of 0 to 960
  • default: 0
  • description: Vertical offset of exposure region in pixel.
ExposureRegionWidth
  • type: Integer in the range of 0 to 1280
  • default: 0
  • description: Width of exposure region in pixel.
ExposureRegionHeight
  • type: Integer in the range of 0 to 960
  • default: 0
  • description: Height of exposure region in pixel.
RcExposureAutoAverageMax
  • type: Float in the range of 0 to 1
  • default: 0.75
  • description: Maximum brightness for the auto exposure function as value between 0 (dark) and 1 (bright).
RcExposureAutoAverageMin
  • type: Float in the range of 0 to 1
  • default: 0.25
  • description: Minimum brightness for the auto exposure function as value between 0 (dark) and 1 (bright).

Category: Scan3dControl

FocalLengthFactor (read-only)
  • type: Float
  • description: The focal length scaled to an image width of 1 pixel. To get the focal length in pixels for a certain image, this value must be multiplied by the width of the received image. See also parameter Scan3dFocalLength.
Baseline (read-only)
  • type: Float
  • description: This parameter is deprecated. The parameter Scan3dBaseline should be used instead.

Category: DepthControl

DepthAcquisitionMode
  • type: Enumeration, one of SingleFrame, SingleFrameOut1 or Continuous
  • default: Continuous
  • description: In single frame mode, stereo matching is performed upon each call of DepthAcquisitionTrigger. The SingleFrameOut1 mode can be used to control an external projector. It sets the line source of Out1 to ExposureAlternateActive upon each trigger and resets it to Low as soon as the images for stereo matching are grabbed. However, the line source will only be changed if the IOControl license is available. In continuous mode, stereo matching is performed continuously.
DepthAcquisitionTrigger
  • type: Command
  • description: This command triggers stereo matching of the next available stereo image pair, if DepthAcquisitionMode is set to SingleFrame or SingleFrameOut1.
DepthQuality
  • type: Enumeration, one of Low, Medium, High, or Full (only with StereoPlus license)
  • default: High
  • description: Quality of disparity images. Lower quality results in disparity images with lower resolution (Quality).
DepthStaticScene
  • type: Boolean
  • default: False
  • description: True for averaging 8 consecutive camera images for improving the stereo matching result. (Static).
DepthSmooth (read-only if StereoPlus license is not available)
  • type: Boolean
  • default: False
  • description: True for advanced smoothing of disparity values. (Smoothing).
DepthFill
  • type: Integer, ranges from 0 pixel to 4 pixels
  • default: 3 pixels
  • description: Value in pixels for Fill-In.
DepthSeg
  • type: Integer, ranges from 0 pixel to 4000 pixels
  • default: 200 pixels
  • description: Value in pixels for Segmentation.
DepthMinConf
  • type: Float, ranges from 0.0 to 1.0
  • default: 0.0
  • description: Value for Minimum Confidence filtering.
DepthMinDepth
  • type: Float, ranges from 0.1 m to 100.0 m
  • default: 0.1 m
  • description: Value in meters for Minimum Distance filtering.
DepthMaxDepth
  • type: Float, ranges from 0.1m to 100.0 m
  • default: 100.0 m
  • description: Value in meters for Maximum Distance filtering.
DepthMaxDepthErr
  • type: Float, ranges from 0.01 m to 100.0 m
  • default: 100.0 m
  • description: Value in meters for Maximum Depth Error filtering.

Chunk data

The rc_visard supports chunk parameters that are transmitted with every image. Chunk parameters all have the prefix Chunk. Their meaning equals their non-chunk counterparts, except that they belong to the corresponding image, e.g. Scan3dFocalLength depends on ComponentSelector and DepthQuality as both can change the image resolution. The parameter ChunkScan3dFocalLength that is delivered with an image fits to the resolution of the corresponding image.

Particularly useful chunk parameters are:

  • ChunkComponentSelector selects for which component to extract the chunk data in MultiPart mode.
  • ChunkComponentID and ChunkComponentIDValue provide the relation of the image to its component (e.g. camera image or disparity image) without guessing from the image format or size.
  • ChunkLineStatusAll provides the status of all GPIOs at the time of image acquisition. See LineStatusAll above for a description of bits.
  • ChunkScan3d... parameters are useful for 3D reconstruction as described in Section Image stream conversions.
  • ChunkPartIndex provides the index of the image part in this MultiPart block for the selected component (ChunkComponentSelector).

Chunk data is enabled by setting the GenICam parameter ChunkModeActive to True.

Provided image streams

The rc_visard provides the following five different image streams via the GenICam interface:

Component name PixelFormat Width×Height Description
Intensity
Mono8 (monochrome cameras)
YCbCr411_8 (color cameras)
1280×960 Left rectified camera image
IntensityCombined
Mono8 (monochrome cameras)
YCbCr411_8 (color cameras)
1280×1920 Left rectified camera image stacked on right rectified camera image
Disparity Coord3D_C16
1280×1920
640×480
320×240
214×160
Disparity image in desired resolution, i.e., DepthQuality of Full, High, Medium or Low
Confidence Confidence8 same as Disparity Confidence image
Error Error8 (custom: 0x81080001) same as Disparity Disparity error image

Each image comes with a buffer timestamp and the PixelFormat given in the above table. This PixelFormat should be used to distinguish between the different image types. Images belonging to the same acquisition timestamp can be found by comparing the GenICam buffer timestamps.

Image stream conversions

The disparity image contains 16 bit unsigned integer values. These values must be multiplied by the scale value given in the GenICam feature Scan3dCoordinateScale to get the disparity values \(d\) in pixels. To compute the 3D object coordinates from the disparity values, the focal length and the baseline as well as the principle point are required. These parameters are transmitted as GenICam features Scan3dFocalLength, Scan3dBaseline, Scan3dPrincipalPointU and Scan3dPrincipalPointV. The focal length and principal point depend on the image resolution of the selected component. Knowing these values, the pixel coordinates and the disparities can be transformed into 3D object coordinates in the camera coordinate frame using the equations described in Computing depth images and point clouds.

Note

The rc_visard’s camera coordinate frame is defined as shown in sensor coordinate frame.

Assuming that \(d16_{ik}\) is the 16 bit disparity value at column \(i\) and row \(k\) of a disparity image, the float disparity in pixels \(d_{ik}\) is given by

\[d_{ik}=d16_{ik} \cdot \mathrm{Scan3dCoordinateScale}\]

The 3D reconstruction in meters can be written with the GenICam parameters as:

\[\begin{split}P_x&=\left(i+0.5-\mathrm{Scan3dPrincipalPointU}\right) \frac{\mathrm{Scan3dBaseline}}{d_{ik}},\\ P_y&=\left(k+0.5-\mathrm{Scan3dPrincipalPointV}\right) \frac{\mathrm{Scan3dBaseline}}{d_{ik}},\\ P_z&=\mathrm{Scan3dFocalLength} \frac{\mathrm{Scan3dBaseline}}{d_{ik}}.\end{split}\]

The confidence image contains 8 bit unsigned integer values. These values have to be divided by 255 to get the confidence as value between 0 an 1.

The error image contains 8 bit unsigned integer values. The error \(e_{ik}\) must be multiplied by the scale value given in the GenICam feature Scan3dCoordinateScale to get the disparity-error values \(d_{eps}\) in pixels. According to the description in Confidence and error images, the depth error \(z_{eps}\) in meters can be computed with GenICam parameters as

\[\begin{split}d_{ik}&=d16_{ik} \cdot \mathrm{Scan3dCoordinateScale},\\ z_{eps}&=\frac{e_{ik} \cdot \mathrm{Scan3dCoordinateScale} \cdot \mathrm{Scan3dFocalLength} \cdot \mathrm{Scan3dBaseline}} {(d_{ik})^2}.\end{split}\]

Note

It is preferable to enable chunk data with the parameter ChunkModeActive and to use the chunk parameters ChunkScan3dCoordinateScale, ChunkScan3dFocalLength, ChunkScan3dBaseline, ChunkScan3dPrincipalPointU and ChunkScan3dPrincipalPointV that are delivered with every image, because their values already fit to the image resolution of the corresponding image.

For more information about disparity, error, and confidence images, please refer to Stereo matching.