Skip to content

Cameras Connected to Flight Controller Outputs

This topic explains how to use PX4 with a camera that is attached to flight controller outputs.

WARNING

MAVLink cameras that use the MAVLink Camera Protocol v2 are recommended.

Overview

PX4 can trigger a camera connected to flight controller outputs using camera commands in missions or sent by a ground control stations. The supported commands are a subset of those defined in the MAVLink Camera Protocol v1.

Whenever a camera is triggered, the MAVLink CAMERA_TRIGGER message is published containing the current session's image sequence number and the corresponding timestamp. This timestamp can be used for several purposes, including: timestamping photos for aerial surveying and reconstruction, synchronising a multi-camera system or visual-inertial navigation.

The camera can be connected to different outputs, including PWM outputs, GPIO outputs, and a Seagull MAP2 via PWM outputs.

Cameras can also (optionally) signal PX4 at the exact moment that a photo/frame is taken using a camera capture pin that is attached to their hot shoe. This allows more precise mapping of images to GPS position for geotagging, or the right IMU sample for VIO synchronization, etc.

PX4 supports the following MAVLink commands for FC-connected cameras, in both missions and if received from a GCS:

The supported behaviour is listed below (these do not precisely match the MAVLink specification).

MAV_CMD_DO_TRIGGER_CONTROL

MAV_CMD_DO_TRIGGER_CONTROL - Accepted in "command controlled" mode (TRIG_MODE 1).

Command ParameterDescription
Param #1Trigger enable/disable. 1: enable (start), 0: disable.
Param #2Reset trigger sequence. 1: reset, any other value does nothing.
Param #3Pause triggering, but without switching the camera off or retracting it. 1: pause, 0: restart.

MAV_CMD_DO_DIGICAM_CONTROL

MAV_CMD_DO_DIGICAM_CONTROL - Accepted in all modes.

This is used by the GCS to test-shoot the camera from the user interface. The trigger driver does not support all camera control parameters defined by the MAVLink spec.

Command ParameterDescription
Param #5Trigger one-shot command (set to 1 to trigger a single image frame).

MAV_CMD_DO_SET_CAM_TRIGG_DIST

MAV_CMD_DO_SET_CAM_TRIGG_DIST - Accepted in "mission controlled" mode (TRIG_MODE 4)

This command is autogenerated during missions to trigger the camera based on survey missions from the GCS.

MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL

MAV_CMD_DO_SET_CAM_TRIGG_INTERVAL

MAV_CMD_OBLIQUE_SURVEY

MAV_CMD_OBLIQUE_SURVEY - Mission command to set a camera auto mount pivoting oblique survey.

This accepts param1 to param4 as defined in the MAVLink message definition. The shutter integration setting (param2) is only obeyed with a GPIO backend.

Trigger Configuration

Cameras can be connected to the FC for triggering using different intefaces, such as PWM, and GPIO, by specifying the appropriate trigger interface backend. You can also indicate the camera trigger mode.

This configuration can most easily be done from the QGroundControl Vehicle Setup > Camera section.

Trigger pins

The different trigger modes, backend interfaces and trigger output configuration are described below (these can also be set directly from parameters).

INFO

The camera settings section is not available by default for FMUv2-based flight controllers (e.g. 3DR Pixhawk) because the camera module is not automatically included in firmware. For more information see Finding/Updating Parameters > Parameters Not In Firmware.

Trigger Modes

Four different modes are supported, controlled by the TRIG_MODE parameter:

ModeDescription
0Camera triggering is disabled.
1Works like a basic intervalometer that can be enabled and disabled by using the MAVLink command MAV_CMD_DO_TRIGGER_CONTROL. See command interface for more details.
2Switches the intervalometer constantly on.
3Triggers based on distance. A shot is taken every time the set horizontal distance is exceeded. The minimum time interval between two shots is however limited by the set triggering interval.
4Triggers automatically when flying a survey in Mission mode.

INFO

If it is your first time enabling the camera trigger app, remember to reboot after changing the TRIG_MODE parameter.

Trigger Interface Backends

The camera trigger driver supports several backends - each for a specific application, controlled by the TRIG_INTERFACE parameter:

NumberDescription
1Enables the GPIO interface. The AUX outputs are pulsed high or low (depending on the TRIG_POLARITY parameter) every TRIG_INTERVAL duration. This can be used to trigger most standard machine vision cameras directly. Note that on PX4FMU series hardware (Pixhawk, Pixracer, etc.), the signal level on the AUX pins is 3.3v.
2Enables the Seagull MAP2 interface. This allows the use of the Seagull MAP2 to interface to a multitude of supported cameras. Pin/Channel 1 (camera trigger) and Pin/Channel 2 (mode selector) of the MAP2 should be connected to the lower and higher mapped camera trigger pins. Using Seagull MAP2, PX4 also supports automatic power control and keep-alive functionalities of Sony Multiport cameras like the QX-1.
3This mode enables MAVLink cameras that used the legacy MAVLink interface listed above. The messages are automatically emitted on the MAVLink onboard channel when found in missions. PX4 emits the CAMERA_TRIGGER MAVLink message when a camera is triggered, by default to the onboard channel (if this is not used, custom stream will need to be enabled). Simple MAVLink cameras explains this use case in more detail.
4Enables the generic PWM interface. This allows the use of infrared triggers or servos to trigger your camera.

Trigger Output Pin Configuration

Camera trigger pins are set in the QGroundControl Actuators configuration screen.

The trigger pins can be set by assigning the Camera_Trigger function on any FMU output. If using trigger setup that requires two pins (e.g. Seagull MAP2) you can assign to any two outputs.

Note however that if a PWM output has been used for camera triggering (such as Seagull MAP2), the whole PWM group cannot be used for anything else (you can't use another output in the group for an actuator, motor, or camera capture, because the timer has already been used).

INFO

At time of writing triggering only works on FMU pins:

  • On a Pixhawk flight controller that has both FMU and I/O boards FMU pins map to AUX outputs (e.g. Pixhawk 4, CUAV v5+) .
  • A controller that only has an FMU, the pins map to MAIN outputs (e.g. Pixhawk 4 mini, CUAV v5 nano).

Other Parameters

ParameterDescription
TRIG_POLARITYRelevant only while using the GPIO interface. Sets the polarity of the trigger pin. Active high means that the pin is pulled low normally and pulled high on a trigger event. Active low is vice-versa.
TRIG_INTERVALDefines the time between two consecutive trigger events in milliseconds.
TRIG_ACT_TIMEDefines the time in milliseconds the trigger pin is held in the "active" state before returning to neutral. In PWM modes, the minimum is limited to 40 ms to make sure we always fit an activate pulse into the 50Hz PWM signal.

The full list of parameters pertaining to the camera trigger module can be found on the parameter reference page.

Camera Capture Configuration

Cameras can also (optionally) use a camera capture pin to signal the exact moment when a photo/frame is taken. This allows more precise mapping of images to GPS position for geotagging, or the right IMU sample for VIO synchronization, etc.

Camera capture/feedback is enabled in PX4 by setting CAM_CAP_FBACK = 1. The pin used for camera capture is then set in the QGroundControl Actuators configuration screen by assigning the Camera_Capture function on any FMU output.

Note that if a PWM output is used as a camera capture input, the whole PWM group cannot be used for anything else (you can't use another output in the group for an actuator, motor, or camera trigger, because the timer has already been used).

INFO

At time of writing camera capture only works on FMU pins:

  • On a Pixhawk flight controller that has both FMU and I/O boards FMU pins map to AUX outputs (e.g. Pixhawk 4, CUAV v5+).
  • A controller that only has an FMU, the pins map to MAIN outputs (e.g. Pixhawk 4 mini, CUAV v5 nano).

PX4 detects a rising edge with the appropriate voltage level on the camera capture pin (for Pixhawk flight controllers this is normally 3.3V). If the camera isn't outputting an appropriate voltage, then additional circuitry will be required to make the signal compatible.

Cameras that have a hotshoe connector (for connecting a flash) can usually be connected via a hotshoe-adaptor. For example, the Seagull #SYNC2 Universal Camera Hot Shoe Adapter is an optocoupler that decouples and shifts the flash voltage to the Pixhawk voltage. This slides into the flash slot on the top of the camera. The red and black ouptputs are connected to the servo rail/ground and the white wire is connected to the input capture pin.

Seagull SYNC#2

INFO

PX4 emits the MAVLink CAMERA_TRIGGER message on both camera trigger and camera capture. If camera capture is configured, the timestamp from the camera capture driver is used, otherwise the triggering timestamp.

Testing Trigger Functionality

WARNING

The following sections are out of date and need retesting.

  1. On the PX4 console:

    shell
    camera_trigger test
  2. From QGroundControl:

    Click on Trigger Camera in the main instrument panel. These shots are not logged or counted for geotagging.

    QGC Test Camera

Sony QX-1 example (Photogrammetry)

photogrammetry

In this example, we will use a Seagull MAP2 trigger cable to interface to a Sony QX-1 and use the setup to create orthomosaics after flying a fully autonomous survey mission.

Trigger Settings

The recommended camera settings are:

  • TRIG_INTERFACE=2 (Seagull MAP2).
  • TRIG_MODE=4 (Mission controlled).
  • Leave the remaining parameters at their defaults.

You will need to connect the Seagull MAP2 to FMU pins on your autopilot. The other end of the MAP2 cable will go into the QX-1's "MULTI" port.

Camera Configuration

We use a Sony QX-1 with a 16-50mm f3.5-5.6 lens for this example.

To avoid autofocus and metering lag when the camera is triggered, the following guidelines should be followed:

  • Manual focus to infinity
  • Set camera to continuous shooting mode
  • Manually set exposure and aperture
  • ISO should be set as low as possible
  • Manual white balance suitable for scene

Mission Planning

QGC Survey Polygon

QGC Survey Parameters

Geotagging

Download/copy the logfile and images from the flight and point QGroundControl to them. Then click on Start Tagging.

QGC Geotagging

You can verify the geotagging using a free online service like Pic2Map. Note that Pic2Map is limited to only 40 images.

Reconstruction

We use Pix4D for 3D reconstruction.

GeoTag

Camera-IMU sync example (VIO)

In this example, we will go over the basics of synchronising IMU measurements with visual data to build a stereo Visual-Inertial Navigation System (VINS). To be clear, the idea here isn't to take an IMU measurement exactly at the same time as we take a picture but rather to correctly time stamp our images so as to provide accurate data to our VIO algorithm.

The autopilot and companion have different clock bases (boot-time for the autopilot and UNIX epoch for companion), so instead of skewing either clock, we directly observe the time offset between the clocks. This offset is added or subtracted from the timestamps in the MAVLink messages (e.g. HIGHRES_IMU) in the cross-middleware translator component (e.g. MAVROS on the companion and mavlink_receiver in PX4). The actual synchronisation algorithm is a modified version of the Network Time Protocol (NTP) algorithm and uses an exponential moving average to smooth the tracked time offset. This synchronisation is done automatically if MAVROS is used with a high-bandwidth onboard link (MAVLink mode onboard).

For acquiring synchronised image frames and inertial measurements, we connect the trigger inputs of the two cameras to a GPIO pin on the autopilot. The timestamp of the inertial measurement from start of exposure and a image sequence number is recorded and sent to the companion computer (CAMERA_TRIGGER message), which buffers these packets and the image frames acquired from the camera. They are matched based on the sequence number (first image frame is sequence 0), the images timestamped (with the timestamp from the CAMERA_TRIGGER message) and then published.

The following diagram illustrates the sequence of events which must happen in order to correctly timestamp our images.

Mermaid sequence diagram

Step 1

First, set the TRIG_MODE to 1 to make the driver wait for the start command and reboot your FCU to obtain the remaining parameters.

Step 2

For the purposes of this example we will be configuring the trigger to operate in conjunction with a Point Grey Firefly MV camera running at 30 FPS.

  • TRIG_INTERVAL: 33.33 ms
  • TRIG_POLARITY: 0 (active low)
  • TRIG_ACT_TIME: 0.5 ms. The manual specifies it only has to be a minimum of 1 microsecond.
  • TRIG_MODE: 1, because we want our camera driver to be ready to receive images before starting to trigger. This is essential to properly process sequence numbers.

Step 3

Wire up your cameras to your AUX port by connecting the ground and signal pins to the appropriate place.

Step 4

You will have to modify your driver to follow the sequence diagram above. Public reference implementations for IDS Imaging UEye cameras and for IEEE1394 compliant cameras are available.

See Also