Link Search Menu Expand Document

MPA Camera Interface

Table of Contents

  1. MPA Camera Interface
  2. Overview
    1. Published Format
    2. voxl-inspect-cam
      1. Arguments
        1. Required
        2. Optional
        3. Example Single Output
      2. Inspect all camera streams
      3. Debug Metrics
    3. Sending Commands Back to the Server
      1. Snapshot Command
      2. Exposure Control Commands
      3. Other Commands
    4. JSON Info File
    5. Stream to ROS
    6. Example to Programmatically use Data

Overview

MPA offers an ultra lightweight bidirectional interface to allow multiple clients to subscribe to image and video streams as well as send commands back to the server such as for taking snapshots or setting exposure. voxl-camera-server, voxl-lepton-server, and voxl-uvc-server (among others) share this common interface.

Published Format

Camera data is published to pipes in a binary form with a metadata struct followed by the raw image data (in a format defined by the metadata):

/**
 * The metadata for the camera image. One of these is sent before every frame
 */
typedef struct camera_image_metadata_t
{
    uint32_t magic_number;  ///< set to CAMERA_MAGIC_NUMBER
    int64_t  timestamp_ns;  ///< timestamp in apps-proc clock-monotonic of beginning of exposure
    int32_t  frame_id;      ///< iterator from 0++ starting from first frame when server starts on boot
    int16_t  width;         ///< image width in pixels
    int16_t  height;        ///< image height in bytes
    int32_t  size_bytes;    ///< size of the image, for stereo this is the size of both L+R together
    int32_t  stride;        ///< bytes per row
    int32_t  exposure_ns;   ///< exposure in microseconds
    int16_t  gain;          ///< ISO gain (100, 200, 400, etc..)
    int16_t  format;        ///< raw8, nv12, etc
    int16_t  framerate;     ///< expected framerate hz
    int16_t  reserved;      ///< extra reserved bytes
} __attribute__((packed)) camera_image_metadata_t;

This definition can be found here.

A number of common formats are defined in libmodal-pipe. Clients are not expected to be able to decode any arbitrary format, only the format they expect for normal operation. voxl-portal and voxl-logger can handle most of the common formats for debugging and logging. For example, a VIO algorithm may only accept raw8 format and it’s perfectly valid to error out if it’s told to subscribe to a pipe publishing an unexpected format.

// Common image formats for use by a camera server. This is not an exhaustive
// list and custom values not included here can be used as long as the server
// and client both agree on the image format.
#define IMAGE_FORMAT_RAW8           0   // 8-bit gray image, used for tracking camera
#define IMAGE_FORMAT_NV12           1
#define IMAGE_FORMAT_STEREO_RAW8    2   // 8-bit gray, two sequential images
#define IMAGE_FORMAT_H264           3
#define IMAGE_FORMAT_H265           4
#define IMAGE_FORMAT_RAW16          5   // 16-bit image, for disparity maps or HDR gray images
#define IMAGE_FORMAT_NV21           6   // Android NV21 format from hal3
#define IMAGE_FORMAT_JPG            7
#define IMAGE_FORMAT_YUV422         8   // Standard YUV422 with YUYV mapping scheme
#define IMAGE_FORMAT_YUV420         9
#define IMAGE_FORMAT_RGB            10  // 24-bits per pixel
#define IMAGE_FORMAT_FLOAT32        11  // 32-bit float per pixel, for depth map
#define IMAGE_FORMAT_STEREO_NV21    12  // Android NV21 format from hal3, two sequential images
#define IMAGE_FORMAT_STEREO_RGB     13  // 24-bits per pixel, two sequential images
#define IMAGE_FORMAT_YUV422_UYVY    14  // YUV422 with alternate UYVY mapping scheme
#define IMAGE_FORMAT_STEREO_NV12    15

voxl-inspect-cam

Project badge Project badge Project badge

The utility voxl-inspect-cam is a tool to check image metadata coming from MPA services that are publishing camera data. It requires that voxl-camera-server is running in the background, which can be checked with voxl-inspect-services. It can also be used to check non-camera images, such as the overlays coming out of VOXL TFLite Server or voxl-qvio-server.

Arguments

Required

Cam: Which image to display data from. Available images can be seen by typing voxl-inspect-cam {TAB} {TAB}. Options that will regularly be available are: tracking, stereo, hires, tof_depth, tof_conf, tof_noise, tof_ir, dfs_disparity, qvio_overlay, tflite_overlay.

Optional

ParameterDescriptionExample
-h –helpPrint help messagevoxl-inspect-cam --help
-n –newlinePrint each sample on a new line instead of updating the current output linevoxl-inspect-cam tracking -n
-t –testTest mode, simple pass/fail test after two seconds of waiting for a framevoxl-inspect-cam tracking -t

Example Single Output

voxl2:/$ voxl-inspect-cam tracking

|size(bytes)| height | width  |exposure(ms)| gain | frame id |latency(ms)|Framerate(hz)| format
|   307200  |    480 |    640 |        3.8 |  100 |   71976  |      18.6 |     30.0    | RAW8
voxl2:/$

Inspect all camera streams

When run with the -a or --all argument, voxl-inspect-cam will subscribe to every image and video pipe simultaneously. This is very useful, but remember it also puts a lot of stress on the system as a lot of image streams are often paused by default. As you can see, the hires_large_color raw NV12 video stream transfers over 3 gbps of data while the H265 encoded version of the same 4K stream is only 11.4mbps.

voxl2:/$ voxl-inspect-cam -a

voxl-streamer-arch

Debug Metrics

voxl-inspect-cam measures the bitrate of data it receives which is particularly useful for tuning video compression. It also identifies header, I and P frames for H264 and H265 streams. Using the --newline argument on a compressed video pipe will let you confirm that a header and I frame are being sent at the beginning of a new client connection. This will also let you count the number of P frames between I frames.

The latency is also calculated based on the time between the end of the exposure as reported by the image metadata and the time that voxl-inspect-camera receives its copy of the complete frame.

voxl-inspect-cam source code.

Sending Commands Back to the Server

libmodal-pipe supports clients sending commands back to a server. It’s up to the server to implement commands relevant to its functionality. Here are some camera-related commands:

Snapshot Command

This is only supported by voxl-camera-server. It sends a command to voxl-camera-server for a particular camera to instruct the ISP to process a single high quality image and save to disk. This is called by voxl-mavcam-server when the user clicks the image shutter button in QGroundControl.

Nothing needs to be subscribed to the pipe to take a snapshot. However, if something like voxl-inspect-cam is subscribed to a xyz_snapshot pipe then they will receive a JPG compressed image through the pipe whenever a snapshot is taken by them or another client or user.

If the user only wants the data through the pipe and does not want a copy saved to disk, they can use the snapshot-no-save command.

voxl2:/$ voxl-send-command hires_snapshot snapshot
OR
voxl2:/$ voxl-send-command hires_snapshot snapshot-no-save

Exposure Control Commands

This is only supported by voxl-camera-server.

VOXL Camera Server primarily uses ModalAI’s libmodal_exposure for camera auto exposure/gain values, but this can also be changed to use the ISP’s (Image Signal Processing) exp/gain settings, or can be disabled altogether. Additionally, you can use voxl-send-command to manually send commands to update the exposure/gain of a specific camera. If a camera was using auto exposure/gain when such a command is sent, the AE will be disabled until the start_ae command is sent and the camera will sit at the requested exposure/gain.

When an image sensor is configured to use a ModalAI exposure algorithm, (see voxl-camera-server config file) one can manually set exposure and gain values from the command line. This can be useful for debugging image sensor performance.

voxl2:/$ voxl-send-command tracking set_exp_gain <exposure> <gain>

For example:

voxl2:/$ voxl-send-command tracking set_exp_gain 200 150

Other Commands

Every server providing image data can implement their own commands. For example voxl-lepton-server provides commands to control the calibration shutter on the Flir Lepton.

voxl-send-command has dynamic tab completion that will show you that commands are available for a particular pipe. Just type the following and double-tap the tab button.

voxl2:/$ voxl-send-command tracking {TAB}{TAB}
voxl2:/$ voxl-send-command hires_small_encoded {TAB}{TAB}

JSON Info File

Any service publishing image or video pipes should be sure to set up the format, dimensions, and framerate where possible in the pipe’s json info file. This allows subscribers like voxl-streamer to validate and initialize based on this information before actually subscribing to the pipe data.

Good examples are the camera pipes published by voxl-camera-server, voxl-uvc-server, and voxl-lepton-server. Here is the hires_large_encoded pipe info for reference:

voxl2:/$ cat /run/mpa/hires_large_encoded/info
{
    "name":     "hires_large_encoded",
    "location": "/run/mpa/hires_large_encoded/",
    "type":     "camera_image_metadata_t",
    "server_name":  "voxl-camera-server",
    "size_bytes":   134217728,
    "server_pid":   1368,
    "available_commands":["set_exp_gain", "set_exp", "set_gain", "start_ae", "stop_ae", "snapshot", "snapshot-no-save"],
    "string_format":    "H265",
    "int_format":   4,
    "width":        4096,
    "height":       2160,
    "framerate":    30
}

Stream to ROS

The VOXL MPA to ROS node can be used to provide data coming out of camera server to ROS1.

ROS2 is supported in SDK 1.1 and later ROS2 Installation

Example to Programmatically use Data

To programmatically access the camera frame buffers from MPA, voxl-inspect-cam is a great example. One can use that project as a starting point to create their own application