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_Logger is ArduPilot’s onboard logging system. It writes a continuous binary stream of structured messages to an SD card (or internal flash on boards without an SD slot), producing .bin files that can be analysed offline with MAVExplorer, Mission Planner, or the pymavlink toolchain. Logging is the primary way to diagnose flight problems, tune controllers, and replay EKF data after a flight.

Binary .bin Format

Log files use a compact binary format with self-describing format messages. Every message type is defined in the log itself, so no external schema is needed to parse it.

Custom Messages

Any library or vehicle code can define and write its own structured log messages using the AP::logger().Write() API with a format string that describes field types.

EKF Replay

When LOG_REPLAY = 1, raw sensor data is written alongside filtered outputs. The same log can then be fed back through the EKF offline for post-flight analysis and tuning.

MAVLink Log Download

Ground stations can download logs over MAVLink using the log-listing and log-transfer protocol, without removing the SD card from the vehicle.

Log file structure

Each .bin file begins with a series of FMT (format) messages that declare every message type used in that log. Subsequent messages are binary records whose layout is described by the corresponding FMT. This makes the format self-contained.
.bin file layout
├── FMT  (type=128, describes the FMT message itself)
├── FMT  (type=129, describes UNIT messages)
├── FMT  (type=130, describes MULT messages)
├── FMT  (type=N,   describes your custom MSG type)
├── PARM (parameter snapshot at arm time)
├── GPS  (GPS fix record)
├── IMU  (IMU sample)
├── ATT  (attitude estimate)
├── ...  (all other message types interleaved by time)
└── (file ends when logging stops or SD is full)
File names are sequential integers: 00000001.BIN, 00000002.BIN, and so on. A new file is started each time the vehicle arms (if LOG_FILE_DISARM_ROT = 1) or on every boot.

Format characters

The format string in a log message definition uses single characters to describe each field’s C type. All integers are stored little-endian.
CharC typeNotes
ffloat32-bit IEEE 754 float
ddouble64-bit IEEE 754 double
iint32_tSigned 32-bit integer
Iuint32_tUnsigned 32-bit integer
hint16_tSigned 16-bit integer
Huint16_tUnsigned 16-bit integer
bint8_tSigned 8-bit integer
Buint8_tUnsigned 8-bit integer
cint16_tValue is multiplied by 100 before storage (centiunits)
Cuint16_tValue is multiplied by 100 before storage
eint32_tValue is multiplied by 100 before storage
Euint32_tValue is multiplied by 100 before storage
Lint32_tLatitude or longitude (degrees × 10⁷)
Muint8_tFlight mode (vehicle-specific enum)
nchar[4]4-character string (not null-terminated)
Nchar[16]16-character string
Zchar[64]64-character string
qint64_tSigned 64-bit integer
Quint64_tUnsigned 64-bit integer
aint16_t[32]Array of 32 signed 16-bit integers
The c, C, e, E types store the value pre-scaled by 100. Log analysis tools automatically apply the inverse scaling, so you write (int16_t)(degrees * 100) but see degrees in the GCS.

Defining a custom log message

Log message types are defined using the LogStructure struct. The preferred approach for one-off messages is the AP::logger().Write() variadic API, which does not require a pre-registered struct.

Using AP::logger().Write()

// Write a one-off custom log entry.
// Name:    up to 4 characters.
// Labels:  comma-separated field names.
// Units:   one character per field (from the unit table in LogStructure.h).
// Mults:   one character per field (multiplier code, '-' for none).
// Format:  one character per field (see format table above).
AP::logger().Write(
    "MYMD",                     // message name (4 chars max)
    "TimeUS,Throttle,AltM,Mode",// field labels
    "s%-m",                     // units: seconds, none, none, metres
    "F---",                     // multipliers
    "QffM",                     // format: uint64, float, float, flight mode
    AP_HAL::micros64(),         // TimeUS
    throttle_pct,               // Throttle
    alt_m,                      // AltM
    (uint8_t)vehicle_mode       // Mode
);

Using a pre-registered struct

For high-rate messages (e.g. IMU-rate logging), register the message type at startup for efficiency:
// 1. Define the packed struct
struct PACKED log_MySensor {
    LOG_PACKET_HEADER;          // uint8_t head1, head2, msgid
    uint64_t time_us;
    float    accel_x;
    float    accel_y;
    float    accel_z;
    int16_t  temperature_cdeg;  // centidegrees
};

// 2. Declare the LogStructure entry (in your LogStructure.h include)
#define LOG_MYSENSOR_MSG 200    // unique message type ID

// 3. Add to the vehicle's log structure table
static const LogStructure log_structure[] = {
    // ... other entries ...
    { LOG_MYSENSOR_MSG, sizeof(log_MySensor),
      "MYSE", "QfffC",
      "TimeUS,AccX,AccY,AccZ,Temp",
      "s---O", "F---B" }
};

// 4. Write the message at runtime
void MySensor::log_data()
{
    struct log_MySensor pkt {
        LOG_PACKET_HEADER_INIT(LOG_MYSENSOR_MSG),
        time_us       : AP_HAL::micros64(),
        accel_x       : _accel.x,
        accel_y       : _accel.y,
        accel_z       : _accel.z,
        temperature_cdeg : (int16_t)(_temp_deg * 100),
    };
    AP::logger().WriteBlock(&pkt, sizeof(pkt));
}

The Write API

AP_Logger exposes three Write variants depending on criticality:
MethodBehaviour
Write(name, labels, units, mults, fmt, ...)Normal (rate-limited if _params.file_ratemax > 0)
WriteStreaming(name, labels, units, mults, fmt, ...)Rate-limited streaming; may be dropped under load
WriteCritical(name, labels, units, mults, fmt, ...)Never dropped; used for arm/disarm, mode changes, errors
WriteBlock(pkt, size)Raw block write using a pre-registered struct
WriteCriticalBlock(pkt, size)Critical raw block write
// Convenience high-level writers provided by AP_Logger:
AP::logger().Write_Event(LogEvent::ARMED);
AP::logger().Write_Mode(mode_number, reason);
AP::logger().Write_Parameter("SERVO1_MIN", 1000.0f);
AP::logger().Write_Error(LogErrorSubsystem::COMPASS,
                          LogErrorCode::UNHEALTHY);

Common built-in message types

These message types are written automatically by the core ArduPilot libraries:
NameSource libraryKey fields
ATTAHRSRoll, pitch, yaw (desired and actual)
POSAHRSLat, Lng, Alt (EKF estimate)
GPSAP_GPSFix type, satellites, lat/lng/alt, speed
BAROAP_BaroAltitude, pressure, temperature
IMUAP_InertialSensorAccX/Y/Z, GyrX/Y/Z, temperature
RCINAP_RCInputRC input channels 1–14
RCOUSRV_ChannelServo output channels 1–14
PARMAP_ParamParameter name and value snapshot
MODEVehicleFlight mode number and reason code
ERRAP_LoggerSubsystem error code and error value
EKF*AP_NavEKF3EKF state, innovations, variances
BATAP_BattMonitorVoltage, current, remaining capacity
ARSPAP_AirspeedIndicated and true airspeed

Key parameters

Bitmask controlling which subsystems are logged. Each bit enables a group of messages. Set to -1 (all bits) for full logging, or use Mission Planner’s Full Parameter List to enable individual subsystems. A value of 0 disables all logging.
Controls logging when the vehicle is disarmed.
ValueBehaviour
0 (NONE)Log only when armed
1Log continuously, including while disarmed
2Log while disarmed but not when connected via USB
3Log while disarmed but discard the log if not armed before shutdown
When set to 1, raw sensor data is additionally logged in a format that the Tools/Replay/ tool can consume. This allows the EKF to be re-run offline with different tuning parameters. Replay logs are significantly larger than standard logs.
Size of the in-memory write buffer in kilobytes (default 16 KB). Larger buffers reduce SD card write stalls on high-rate logging but consume RAM. Increase this if you see LOG: out of space messages in fast-loop vehicles.
Maximum log rate in Hz (0 = unlimited). Rate-limiting prevents the logger from consuming excessive CPU time during intensive manoeuvres.
When set to 1, a new log file is started each time the vehicle arms. When 0, a new file is only started on boot.

Reading .bin log files

MAVExplorer

MAVExplorer is the recommended command-line tool for graphing and analysing logs:
# Install via pip
pip install mavproxy

# Open a log file
mavproxy.py --master=log.bin
MAV> graph ATT.Roll ATT.DesRoll
MAV> graph VFR_HUD.airspeed

Mission Planner

In Mission Planner, go to DataFlash Logs → Load Log and select a .bin file. Use the Browse Log view to plot any combination of logged fields over time.
from pymavlink import mavutil

mlog = mavutil.mavlink_connection("00000001.BIN")
while True:
    msg = mlog.recv_match(type="ATT", blocking=True)
    if msg is None:
        break
    print(f"Roll={msg.Roll:.1f}  Pitch={msg.Pitch:.1f}")

EKF Replay

The Replay tool (Tools/Replay/Replay.cpp) reads a log file containing raw sensor data (requires LOG_REPLAY = 1) and re-runs the EKF, writing a new log with the same vehicle trajectory but potentially different EKF outputs.
# Build the replay tool (SITL board)
./waf configure --board sitl
./waf replay

# Run replay on a log
./build/sitl/tools/Replay 00000001.BIN
# Produces: logs/00000001.BIN with EKF replay output
Use Replay to test EKF parameter changes (filter tuning, process noise values) on a real flight log before deploying to a vehicle. This avoids the need for repeated test flights during EKF development.

Complete example: define and write a custom log message

// mymodule/MyModule.h
#include <AP_Logger/AP_Logger.h>

class MyModule {
public:
    void update();
private:
    float _speed_ms;
    float _temp_c;
    uint8_t _status;
    void log_data();
};

// mymodule/MyModule.cpp
void MyModule::log_data()
{
    // Check that logging is enabled for this bitmask bit
    if (!AP::logger().should_log(MASK_LOG_ANY)) {
        return;
    }

    // Write using the variadic API — no struct registration needed
    AP::logger().Write(
        "MYMO",                        // 4-char name
        "TimeUS,Speed,Temp,Status",    // labels
        "snO-",                        // units: s, m/s, degC, none
        "F--0",                        // multipliers
        "QffB",                        // format
        AP_HAL::micros64(),
        _speed_ms,
        _temp_c,
        _status
    );
}

void MyModule::update()
{
    // ... sensor reading logic ...
    log_data();
}

Build docs developers (and LLMs) love