# Payloads and Cameras

PX4 supports a wide range of payloads and cameras.

# Mapping Drones

Mapping drones use cameras to capture images at time or distance intervals during surveys.

MAVLink cameras that support the MAVLink Camera Protocol (opens new window) provide the best integration with PX4 and QGroundControl. The MAVSDK provides simple APIs to use this protocol for both standalone camera operations (opens new window) and in missions (opens new window).

Cameras can also be connected directly to a flight controller using PWM or GPI outputs. PX4 supports the following set of MAVLink commands/mission items for cameras that are connected to the flight controller:

The following topics show how to connect your camera configure PX4:

# Cargo Drones ("Actuator" Payloads)

Cargo drones commonly use servos/actuators to trigger cargo release, control winches, etc. PX4 supports servo and GPIO triggering via both RC and MAVLink commands.

# RC Triggering

You can map up to three RC channels to control servos/actuators attached to the flight controller using the parameters RC_MAP_AUX1 to RC_MAP_AUX3.

The RC channels are usually mapped to the AUX1, AUX2, AUX3 outputs of your flight controller (using a mixer file defined in your airfame). You can confirm which outputs are used for RC AUX passthrough on your vehicle in the Airframe Reference. For example, Quadrotor-X has the normal mapping: "AUX1: feed-through of RC AUX1 channel", "AUX2: feed-through of RC AUX2 channel", "AUX3: feed-through of RC AUX3 channel".

If your vehicle doesn't specify RC AUX feed-through outputs, then you can add them using using a custom Mixer File that maps Control group 3 outputs 5-7 to your desired port(s). An example of such a mixer is the default passthrough mixer: pass.aux.mix (opens new window).

Note

The same outputs used for "feed-through of RC AUX" may also be set using a MAVLink command (see below). PX4 will use the last value set through either mechanism.

# Mission Triggering

You can use the MAV_CMD_DO_SET_ACTUATOR (opens new window) MAVLink command to set (up to) three actuators values at a time, either in a mission or as a command.

Command parameters param1, param2, and param3 are usually mapped to the AUX1, AUX2, AUX3 outputs of your flight controller, while command parameters param4 to param7 are unused/ignored by PX4. The parameters take normalised values in the range [-1, 1] (resulting in PWM outputs in the range [PWM_AUX_MINx, PWM_AUX_MAXx], where X is the output number). All params/actuators that are not being controlled should be set to NaN.

Note

MAVLink uses the same outputs as are configured for RC AUX passthrough (see prevous section). You can check which outputs are used in the Airframe Reference for your vehicle, and change them if needed using a custom mixer file.

# MAVSDK (Example script)

The following MAVSDK (opens new window) sample code shows how to trigger payload release.

The code uses the MAVSDK MavlinkPassthrough (opens new window) plugin to send the MAV_CMD_DO_SET_ACTUATOR (opens new window) MAVLink command, specifying the value of (up to) 3 actuators.

#include <mavsdk/mavsdk.h>
#include <mavsdk/plugins/mavlink_passthrough/mavlink_passthrough.h>
#include <mavsdk/plugins/info/info.h>
#include <chrono>
#include <cstdint>
#include <iostream>
#include <future>
#include <memory>
using namespace mavsdk;
void send_actuator(MavlinkPassthrough& mavlink_passthrough,
        float value1, float value2, float value3);
int main(int argc, char **argv)
{
    Mavsdk mavsdk;
    std::string connection_url;
    ConnectionResult connection_result;
    float value1, value2, value3;
    if (argc == 5) {
        connection_url = argv[1];
        connection_result = mavsdk.add_any_connection(connection_url);
        value1 = std::stof(argv[2]);
        value2 = std::stof(argv[3]);
        value3 = std::stof(argv[4]);
    } 
    if (connection_result != ConnectionResult::Success) {
        std::cout << "Connection failed: " << connection_result << std::endl;
        return 1;
    }
    bool discovered_system = false;
    mavsdk.subscribe_on_new_system([&mavsdk, &discovered_system]() {
        const auto system = mavsdk.systems().at(0);
        if (system->is_connected()) {
            std::cout << "Discovered system" << std::endl;
            discovered_system = true;
        }
    });
    std::this_thread::sleep_for(std::chrono::seconds(2));
    if (!discovered_system) {
        std::cout << "No device found, exiting." << std::endl;
        return 1;
    }
    std::shared_ptr<System> system = mavsdk.systems().at(0);
    for (auto& tsystem : mavsdk.systems()) {
        auto info = Info{tsystem};
        std::cout << info.get_identification().second.hardware_uid << std::endl;
        if (info.get_identification().second.hardware_uid == "3762846593019032885") {
            system = tsystem;
        }
    }
    auto mavlink_passthrough = MavlinkPassthrough{system};
    send_actuator(mavlink_passthrough, value1, value2, value3);
    return 0;
}
void send_actuator(MavlinkPassthrough& mavlink_passthrough,
        float value1, float value2, float value3)
{
    std::cout << "Sending message" << std::endl;
    mavlink_message_t message;
    mavlink_msg_command_long_pack(
            mavlink_passthrough.get_our_sysid(),
            mavlink_passthrough.get_our_compid(),
            &message,
            1, 1,
            MAV_CMD_DO_SET_ACTUATOR,
            0,
            value1, value2, value3,
            NAN, NAN, NAN, 0);
    mavlink_passthrough.send_message(message);
    std::cout << "Sent message" << std::endl;
}

# Surveillance, Search & Rescue

Surveillance and Search & Rescue drones have similar requirements to mapping drones. The main differences are that, in addition to flying a planned survey area, they typically need good standalone control over the camera for image and video capture, and they may need to be able to work during both day and night

Use a camera that supports the MAVLink Camera Protocol (opens new window) as this supports image and video capture, zooming, storage management, multiple cameras on the same vehicle and switching between them, etc. These cameras can be controlled either manually from QGroundControl or via MAVSDK (for both standalone camera operations (opens new window) and in missions (opens new window)). See Camera triggering for information on how to configure your camera to work with MAVLink.

Note

Cameras connected directly to the flight control only support camera triggering, and are unlikely to be suitable for most surveillance/search work.

A search and rescue drone may also need to carry cargo, for example, emergency supplies for a stranded hiker. See Cargo Drones above for information about payload delivery.