# Camera Configuration
PX4 can be configured to connect physical outputs to trigger a camera, or it can be used with a MAVLink camera.
Note
We recommend that you use a MAVLink camera as this allows comprehensive control of cameras via the camera protocol (opens new window). Directly connected cameras only support a small subset of MAVLink camera commands.
Whenever a camera is triggered, the MAVLink CAMERA_TRIGGER (opens new window) message is published containing a sequence number (i.e. the current session's image sequence number) and the corresponding timestamp. This timestamp can be used for several applications, including: timestamping photos for aerial surveying and reconstruction, synchronising a multi-camera system or visual-inertial navigation.
Cameras can also (optionally) signal PX4 at the exact moment that a photo/frame is taken using a camera capture pin. This allows more precise mapping of images to GPS position for geotagging, or the right IMU sample for VIO synchronization, etc.
# Trigger Configuration
Camera triggering is usually configured from the QGroundControl Vehicle Setup > Camera (opens new window) section.
The different trigger modes, backend interfaces and trigger output configuration are described below (these can also be set directly from parameters).
Note
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:
Mode | Description |
---|---|
0 | Camera triggering is disabled. |
1 | Works 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. |
2 | Switches the intervalometer constantly on. |
3 | Triggers 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. |
4 | triggers automatically when flying a survey in Mission mode. |
Note
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:
Number | Description |
---|---|
1 | Enables 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. |
2 | Enables the Seagull MAP2 interface. This allows the use of the Seagull MAP2 (opens new window) 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. |
3 | Enables the MAVLink interface. In this mode, no actual hardware output is used. Only the CAMERA_TRIGGER MAVLink message is sent by the autopilot (by default, if the MAVLink application is in onboard mode. Otherwise, a custom stream will need to be enabled). |
4 | Enables the generic PWM interface. This allows the use of infrared triggers (opens new window) 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 once an output has been used for camera triggering, the whole PWM group cannot be used for anything else (you can't use another output in the group for an actuator or motor, say).
Note
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
Parameter | Description |
---|---|
TRIG_POLARITY | Relevant 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_INTERVAL | Defines the time between two consecutive trigger events in milliseconds. |
TRIG_ACT_TIME | Defines 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
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
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 (opens new window) 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.
Note
PX4 emits the MAVLink CAMERA_TRIGGER (opens new window) 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.
# MAVLink Command Interface (Directly Connected Cameras)
When using a camera connected to the flight controller as described in this document (e.g. using the GPIO, PWM or seagull backend interfaces) the camera driver supports the following subset of MAVLink commands:
MAV_CMD_DO_TRIGGER_CONTROL (opens new window) - Accepted in "command controlled" mode (TRIG_MODE
1).
Command Parameter | Description |
---|---|
Param #1 | Trigger enable/disable. 1 : enable (start), 0 : disable. |
Param #2 | Reset trigger sequence. 1 : reset, any other value does nothing. |
Param #3 | Pause triggering, but without switching the camera off or retracting it. 1 : pause, 0 : restart. |
MAV_CMD_DO_DIGICAM_CONTROL (opens new window) - 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 Parameter | Description |
---|---|
Param #5 | Trigger one-shot command (set to 1 to trigger a single image frame). |
MAV_CMD_DO_SET_CAM_TRIGG_DIST (opens new window) - 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_OBLIQUE_SURVEY (opens new window) - 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.
# MAVLink Cameras
PX4 can also be configured to use a MAVLink trigger interface backend with a MAVLink camera.
In this case MAVLink camera messages are forwarded to a MAVLink camera for handling (although PX4 will still emit the CAMERA_TRIGGER
when a trigger command is received).
MAVLink cameras are recommended because directly connected cameras only support a small subset of the available MAVLink camera messages and commands. MAVLink cameras potentially offer much more control over a camera using the MAVLink Camera Protocol (opens new window).
# Testing Trigger Functionality
WARNING
The following sections are out of date and need retesting.
On the PX4 console:
camera_trigger test
From QGroundControl:
Click on Trigger Camera in the main instrument panel. These shots are not logged or counted for geotagging.
# Sony QX-1 example (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
# Geotagging
Download/copy the logfile and images from the flight and point QGroundControl to them. Then click on Start Tagging.
You can verify the geotagging using a free online service like Pic2Map (opens new window). Note that Pic2Map is limited to only 40 images.
# Reconstruction
We use Pix4D (opens new window) for 3D reconstruction.
# 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.
# 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 msTRIG_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 (opens new window) cameras and for IEEE1394 compliant (opens new window) cameras are available.