Adding a new Log Message

DataFlash Logs are stored on the flight controller’s onboard dataflash memory and can be downloaded after a flight. The logs provide detailed information about each flight which can be important especially when trying to diagnose why something went wrong.

This page explains how to write a new dataflash log message.

The Easy Way

Use AP::logger().Write(…):

void Write(const char *name, const char *labels, const char *fmt, ...);
void Write(const char *name, const char *labels, const char *units, const char *mults, const char *fmt, ...);

An example of the top function being used can be found in Compass_learn.cpp:

AP::logger().Write("COFS", "TimeUS,OfsX,OfsY,OfsZ,Var,Yaw,WVar,N", "QffffffI",
                                        AP_HAL::micros64(),
                                        best_offsets.x,
                                        best_offsets.y,
                                        best_offsets.z,
                                        best_error,
                                        best_yaw_deg,
                                        worst_error,
                                        num_samples);
  • the 1st argument is the message name. This should be 4 characters or less and be unique

  • the 2nd argument is a comma separated list of up to 16 field names; with a limit of 64 characters in total

  • the 3rd argument is a format string (maximum of 16 characters) with each letter holding the format for the corresponding field. The meaning of each letter can be found here in AP_Logger/LogStructure.h

  • the remaining arguments are the actual values that will be logged.

The 2nd Log_Write function is the same as the first except that it accepts two additional string arguments, “units” and “mults”. Similar to the “format” argument, each character in these arguments specifies the units (i.e. “d” for degrees) or multiplier (i.e. “2” for *100, “B” for *0.01) for the following fields. These help the graphing tools scale the output correctly when displaying to the user.

For example, below is a “TEST” log message which outputs the current system time and altitude.

AP::logger().Write("TEST", "TimeUS,Alt",
                   "sm", // units: seconds, meters
                   "FB", // mult: 1e-6, 1e-2
                   "Qf", // format: uint64_t, float
                   AP_HAL::micros64(),
                   alt_in_cm);
  • the time has units of seconds (“s”), multiplier of “F” to indicate the value should be divided by 1 million and format of “Q” to indicate it is output as a 64 bit unsigned integer.

  • the altitude has units of meters (“m”), multiplier of “B” to indicate the value should be divided by 100 (to convert from centimeters to meters) and format of “f” because the value is a float.

The Harder Way

For commonly used messages, especially those which are output at a relatively high rate (50hz or more) a slightly more efficient logging method can be used.