Skip to main content

Documentation Index

Fetch the complete documentation index at: https://mintlify.com/Ardupilot/ardupilot/llms.txt

Use this file to discover all available pages before exploring further.

AP_Mission manages the full lifecycle of autonomous mission execution in ArduPilot. It reads mission items from persistent storage (EEPROM or SD card), maintains separate queues for navigation and action commands, resolves DO_JUMP loops, and calls back into vehicle-specific code to start and verify each command. All mission items conform to the MAVLink mission protocol, so any MAVLink-compatible GCS (Mission Planner, QGroundControl, MAVProxy) can upload and download missions transparently.

Command categories

ArduPilot organizes mission items into three logical categories that the library processes in parallel:

NAV commands

Navigation commands that move the vehicle to a new location or set a flight profile. Only one NAV command executes at a time (_nav_cmd).

DO commands

Action commands that run concurrently with the active NAV command — camera triggers, servo outputs, speed changes, gimbal moves.

CONDITION commands

Commands that pause advancement to the next NAV command until a condition is met, such as a delay expiring or a distance threshold crossed.

Supported command types

CommandDescription
MAV_CMD_NAV_WAYPOINTFly to a position at a specified altitude, with optional loiter time on arrival
MAV_CMD_NAV_LOITER_UNLIMLoiter indefinitely at a point
MAV_CMD_NAV_LOITER_TURNSLoiter for a specified number of turns (supports fractional turns)
MAV_CMD_NAV_LOITER_TIMELoiter for a specified time in seconds
MAV_CMD_NAV_RETURN_TO_LAUNCHReturn to the home position and land
MAV_CMD_NAV_LANDLand at the current or specified position
MAV_CMD_NAV_TAKEOFFArm, take off, and climb to the specified altitude
MAV_CMD_NAV_SPLINE_WAYPOINTFly a smooth spline path through the waypoint
MAV_CMD_NAV_DELAYWait at the current position for a fixed time or until a UTC time

DO commands (actions)

CommandDescription
MAV_CMD_DO_CHANGE_SPEEDChange the target airspeed or ground speed
MAV_CMD_DO_SET_SERVOSet a servo output channel to a PWM value
MAV_CMD_DO_SET_RELAYSet a relay output high or low
MAV_CMD_DO_REPEAT_RELAYToggle a relay N times with a configurable cycle time
MAV_CMD_DO_JUMPJump to a mission index, optionally repeating N times or forever
MAV_CMD_DO_LAND_STARTMarks the start of a landing sequence for failsafe routing
MAV_CMD_DO_GRIPPEROpen or close a cargo gripper
MAV_CMD_DO_AUX_FUNCTIONTrigger any RC auxiliary function from the mission
MAV_CMD_DO_GIMBAL_MANAGER_PITCHYAWCommand gimbal pitch and yaw angles or rates
MAV_CMD_DO_SET_CAM_TRIGG_DISTTrigger a camera every N meters of travel

CONDITION commands

CommandDescription
MAV_CMD_CONDITION_DELAYWait N seconds before advancing to the next NAV command
MAV_CMD_CONDITION_DISTANCEWait until within N meters of the next waypoint
MAV_CMD_CONDITION_YAWWait until vehicle yaw reaches the target angle

Key methods

Checks the EEPROM version stamp and clears the stored mission if it does not match the current library version. Must be called once on boot before any other mission operation.
void init();
Controls mission execution state. start() resets to the first command; stop() halts execution (subsequent update() calls are no-ops); resume() re-initialises in-progress commands and continues from where execution stopped.
void start();
void stop();
void resume();
void start_or_resume(); // honours MIS_RESTART parameter
The main execution loop. Loads the next NAV or DO command into the active slots, calls the vehicle’s cmd_start_fn when a command begins, and calls cmd_verify_fn each loop to check completion. Should be called at 10 Hz or higher.
void update();
Jumps execution to the command at the given index. Used by the GCS to set the active mission item mid-flight and by internal logic such as DO_JUMP processing.
bool set_current_cmd(uint16_t index);
Returns a const reference to the currently executing navigation command. Vehicle code inspects the id and content fields to determine what to do.
const Mission_Command& get_current_nav_cmd() const;
Returns the total number of commands stored in the mission, including the implicit home position at index 0. Subtract 1 to get the number of user-defined items.
uint16_t num_commands() const;
Low-level storage access. GCS upload uses write_cmd_to_storage() internally; replace_cmd() lets vehicle code modify a specific slot without restarting the entire mission.
bool read_cmd_from_storage(uint16_t index, Mission_Command& cmd) const;
bool add_cmd(Mission_Command& cmd);
bool replace_cmd(uint16_t index, const Mission_Command& cmd);
clear() erases the entire mission from storage. truncate() removes all commands beyond the given index, useful for trimming a partial upload.
bool clear();
void truncate(uint16_t index);

Mission command structure

Each item in the mission list is a Mission_Command struct stored in 15 bytes of EEPROM. Location-bearing commands store their coordinates in the content.location field; non-location commands use command-specific sub-structs.
struct Mission_Command {
    uint16_t index;           // position in the command list (0 = home)
    uint16_t id;              // MAVLink command ID (MAV_CMD_*)
    uint16_t p1;              // general purpose parameter 1
    Content  content;         // union of all command payloads
    uint8_t  type_specific_bits;
};
The Content union holds a Location for NAV commands, or a command-specific struct for DO/CONDITION commands:
// Example: change-speed command payload
struct Change_Speed_Command {
    uint8_t speed_type;   // 0 = airspeed, 1 = ground speed
    float   target_ms;    // target speed in m/s (-1 = no change)
    float   throttle_pct; // throttle percentage (0 = no change)
};

// Example: DO_JUMP command payload
struct Jump_Command {
    uint16_t target;      // target command index
    int16_t  num_times;   // repeat count (-1 = infinite)
};

Mission storage

Missions are persisted to:
  • EEPROM / internal flash — on all supported boards via the StorageManager abstraction. The EEPROM slot is fixed-size; num_commands_max() reflects the available capacity.
  • SD card — on boards where AP_SDCARD_STORAGE_ENABLED is set, missions can alternatively be stored as APM/mission.stg. This removes the EEPROM size constraint.
The EEPROM format is versioned (AP_MISSION_EEPROM_VERSION = 0x65AE). Flashing a firmware with an incompatible version clears the stored mission automatically. Always re-upload your mission after a major firmware change.

Mission change detection

last_change_time_ms() returns the timestamp of the most recent modification to the mission. GCS code uses this to detect out-of-band changes (e.g. from a Lua script) and synchronize its local copy without polling the entire mission.
uint32_t last_change_time_ms() const;

DO_JUMP handling

Up to AP_MISSION_MAX_NUM_DO_JUMP_COMMANDS (15 on small boards, 100 on large boards) jump commands are tracked in _jump_tracking[]. Each entry stores the number of times the jump has been executed. When num_times == -1 (AP_MISSION_JUMP_REPEAT_FOREVER) the jump runs indefinitely.

Integration with AP_Rally

Rally points are managed by the separate AP_Rally library. When a failsafe triggers MAV_CMD_NAV_RETURN_TO_LAUNCH, the vehicle code queries AP_Rally for the nearest safe rally point and uses that as the RTL destination, bypassing the mission home stored at index 0.

Registering vehicle callbacks

AP_Mission does not know how to execute commands — it delegates to two vehicle-provided function pointers passed at construction time:
// Vehicle provides these two callbacks:
bool cmd_start_fn(const AP_Mission::Mission_Command& cmd);   // called once when command starts
bool cmd_verify_fn(const AP_Mission::Mission_Command& cmd);  // called each loop; return true when done

AP_Mission mission(cmd_start_fn, cmd_verify_fn, mission_complete_fn);
This design means all vehicle-specific navigation logic (calling AC_WPNav, managing landing gear, etc.) lives in the vehicle code, while AP_Mission handles only sequencing and storage.

Source location

libraries/AP_Mission/AP_Mission.h — mission manager class
libraries/AP_Mission/AP_Mission_Commands.cpp — command structure definitions and MAVLink conversion

Build docs developers (and LLMs) love