From 55dc956fd7b2339b6730307a7d2183b198a19b00 Mon Sep 17 00:00:00 2001 From: Terran Gerratt Date: Sat, 17 Jan 2026 09:16:29 -0700 Subject: [PATCH 1/6] fix macos build (includes build with units) --- CMakeLists.txt | 23 +++++++++++++++++++++++ DataLoadAPBin/dataload_apbin.cpp | 2 +- 2 files changed, 24 insertions(+), 1 deletion(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 6701e9b..3f64fe6 100755 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,4 +1,9 @@ cmake_minimum_required(VERSION 3.7) +# Fix the warning and enable modern RPATH behavior +cmake_policy(SET CMP0068 NEW) + +# Force the library to use @rpath instead of absolute paths +set(CMAKE_MACOSX_RPATH ON) project(plotjuggler_apbin_plugins) @@ -83,6 +88,17 @@ else() endif() +# 1. Disable the default RPATH (which usually points to Homebrew) +set(CMAKE_SKIP_BUILD_RPATH FALSE) +set(CMAKE_BUILD_WITH_INSTALL_RPATH TRUE) + +# 2. Tell the plugin to look for Qt inside the PlotJuggler App bundle +# @executable_path/../Frameworks is where PlotJuggler keeps its Qt +set(CMAKE_INSTALL_RPATH "@executable_path/../Frameworks") + +# 3. Ensure the linker uses this path +set(CMAKE_INSTALL_RPATH_USE_LINK_PATH FALSE) + #------- Create the libraries ------- add_library(DataAPBin SHARED DataLoadAPBin/dataload_apbin.h @@ -95,6 +111,13 @@ if (COMPILING_WITH_AMENT) ament_target_dependencies(DataAPBin plotjuggler) endif() +# Ensure the library ID is set to @rpath +set_target_properties(DataAPBin PROPERTIES + INSTALL_NAME_DIR "@rpath" + BUILD_WITH_INSTALL_RPATH TRUE +) + + #------- Install the libraries ------- install( TARGETS diff --git a/DataLoadAPBin/dataload_apbin.cpp b/DataLoadAPBin/dataload_apbin.cpp index b1fa5eb..29ee830 100644 --- a/DataLoadAPBin/dataload_apbin.cpp +++ b/DataLoadAPBin/dataload_apbin.cpp @@ -32,7 +32,7 @@ // Config -//#define LABEL_WITH_UNIT +#define LABEL_WITH_UNIT bool is_nearly(double val, int val2) From dab5e49ca2746148c1df515c1e471f194318b527 Mon Sep 17 00:00:00 2001 From: Terran Gerratt Date: Mon, 19 Jan 2026 21:57:09 -0700 Subject: [PATCH 2/6] - fixed build to now be compatible with official plotjuggler .dmg release - required disabling the progress bar when loading a file, couldn't get the official build to allow external plugins to open new dialogs. - initial work on status_text and parameter series --- CMakeLists.txt | 146 ++++++++++++------------------- DataLoadAPBin/dataload_apbin.cpp | 88 +++++++++++-------- DataLoadAPBin/dataload_apbin.h | 3 + DataLoadAPBin/logformat.h | 39 ++++++++- 4 files changed, 151 insertions(+), 125 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 3f64fe6..27e588a 100755 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,126 +1,94 @@ cmake_minimum_required(VERSION 3.7) -# Fix the warning and enable modern RPATH behavior cmake_policy(SET CMP0068 NEW) - -# Force the library to use @rpath instead of absolute paths -set(CMAKE_MACOSX_RPATH ON) - project(plotjuggler_apbin_plugins) set(CMAKE_CXX_STANDARD 17) set(CMAKE_CXX_STANDARD_REQUIRED ON) -#------- Include Qt dependencies ------- -set(CMAKE_INCLUDE_CURRENT_DIR ON) +#--- Basic Qt setup set(CMAKE_AUTOMOC ON) -SET(CMAKE_AUTOUIC ON) - -find_package(Qt5 REQUIRED COMPONENTS - Core - Concurrent - Widgets - Xml - Svg) - -include_directories( - ${Qt5Core_INCLUDE_DIRS} - ${Qt5Widgets_INCLUDE_DIRS} - ${Qt5Xml_INCLUDE_DIRS} - ${Qt5Svg_INCLUDE_DIRS} ) - -set(QT_LIBRARIES - Qt5::Core - Qt5::Concurrent - Qt5::Widgets - Qt5::Xml - Qt5::Svg ) - -add_definitions( ${QT_DEFINITIONS} -DQT_PLUGIN ) -set( PJ_LIBRARIES ${QT_LIBRARIES} ) - -#-------------- Switch units support ---------------- -OPTION(ADD_UNITS "Add units support" OFF) -IF(ADD_UNITS) - add_compile_definitions("LABEL_WITH_UNIT") - message(STATUS "Enabling field units define.") -ENDIF(ADD_UNITS) +set(CMAKE_AUTOUIC ON) +set(CMAKE_INCLUDE_CURRENT_DIR ON) -#-------------------------------------------------------- -#-------------- Build with CATKIN (ROS1) ---------------- -if( CATKIN_DEVEL_PREFIX OR catkin_FOUND OR CATKIN_BUILD_BINARY_PACKAGE) +find_package(Qt5 REQUIRED COMPONENTS Core Concurrent Widgets Xml Svg) - set(COMPILING_WITH_CATKIN 1) +#--- Find PlotJuggler and its dependencies, and set paths +if(CATKIN_DEVEL_PREFIX OR catkin_FOUND OR CATKIN_BUILD_BINARY_PACKAGE) + # --- Build with CATKIN (ROS1) --- message(STATUS "COMPILING_WITH_CATKIN") - add_definitions(-DCOMPILED_WITH_CATKIN) - - find_package(catkin REQUIRED COMPONENTS plotjuggler ) - catkin_package( - CATKIN_DEPENDS plotjuggler - ) + find_package(catkin REQUIRED COMPONENTS plotjuggler) include_directories(${catkin_INCLUDE_DIRS}) - list(APPEND ${PJ_LIBRARIES} ${catkin_LIBRARIES} ) - set(PJ_PLUGIN_INSTALL_DIRECTORY ${CATKIN_PACKAGE_BIN_DESTINATION} ) - - #-------------------------------------------------------- - #-------------- Build with AMENT (ROS2) ----------------- -elseif( DEFINED ENV{AMENT_PREFIX_PATH}) + set(PJ_LIBS ${catkin_LIBRARIES}) - set(COMPILING_WITH_AMENT 1) +elseif(DEFINED ENV{AMENT_PREFIX_PATH}) + # --- Build with AMENT (ROS2) --- message(STATUS "COMPILING_WITH_AMENT") - add_definitions(-DCOMPILED_WITH_AMENT) - find_package(ament_cmake REQUIRED) find_package(plotjuggler REQUIRED) - set(PJ_PLUGIN_INSTALL_DIRECTORY lib/${PROJECT_NAME} ) - - #-------------------------------------------------------- - #------------- Build without any ROS support ------------ + include_directories(${plotjuggler_INCLUDE_DIR}) + set(PJ_LIBS ${plotjuggler_LIBRARIES}) else() - + # --- Build without any ROS support (standalone) --- + message(STATUS "COMPILING STANDALONE") find_package(plotjuggler REQUIRED) - message(STATUS "PlotJuggler FOUND") - message(STATUS "plotjuggler_INCLUDE_DIR: ${plotjuggler_INCLUDE_DIR}") - message(STATUS "plotjuggler_LIBRARIES: ${plotjuggler_LIBRARIES}") - + # This is the critical line for moc to find the PJ::DataLoader interface include_directories(${plotjuggler_INCLUDE_DIR}) - list(APPEND PJ_LIBRARIES ${plotjuggler_LIBRARIES} ) - set(PJ_PLUGIN_INSTALL_DIRECTORY bin ) - + set(PJ_LIBS ${plotjuggler_LIBRARIES}) endif() -# 1. Disable the default RPATH (which usually points to Homebrew) -set(CMAKE_SKIP_BUILD_RPATH FALSE) -set(CMAKE_BUILD_WITH_INSTALL_RPATH TRUE) -# 2. Tell the plugin to look for Qt inside the PlotJuggler App bundle -# @executable_path/../Frameworks is where PlotJuggler keeps its Qt -set(CMAKE_INSTALL_RPATH "@executable_path/../Frameworks") +#-------------- Switch units support ---------------- +OPTION(ADD_UNITS "Add units support" OFF) +IF(ADD_UNITS) + add_compile_definitions("LABEL_WITH_UNIT") + message(STATUS "Enabling field units define.") +ENDIF(ADD_UNITS) -# 3. Ensure the linker uses this path -set(CMAKE_INSTALL_RPATH_USE_LINK_PATH FALSE) -#------- Create the libraries ------- +#------- Create the library ------- add_library(DataAPBin SHARED DataLoadAPBin/dataload_apbin.h - DataLoadAPBin/dataload_apbin.cpp ) + DataLoadAPBin/dataload_apbin.cpp +) -target_link_libraries(DataAPBin - ${PJ_LIBRARIES}) +# Link against both plotjuggler libraries and the required Qt modules. +target_link_libraries(DataAPBin PRIVATE + ${PJ_LIBS} + Qt5::Core + Qt5::Concurrent + Qt5::Widgets + Qt5::Xml + Qt5::Svg +) if (COMPILING_WITH_AMENT) ament_target_dependencies(DataAPBin plotjuggler) endif() -# Ensure the library ID is set to @rpath -set_target_properties(DataAPBin PROPERTIES +# We need to tell Qt this is a plugin. +target_compile_definitions(DataAPBin PRIVATE QT_PLUGIN) + + +#------- Installation and RPATH for macOS ------- +set(CMAKE_MACOSX_RPATH ON) +set(CMAKE_SKIP_BUILD_RPATH FALSE) +set(CMAKE_BUILD_WITH_INSTALL_RPATH TRUE) +set(CMAKE_INSTALL_RPATH "@executable_path/../Frameworks") +set(CMAKE_INSTALL_RPATH_USE_LINK_PATH FALSE) + +set_target_properties(DataAPBin PROPERTIES INSTALL_NAME_DIR "@rpath" - BUILD_WITH_INSTALL_RPATH TRUE ) +if(CATKIN_DEVEL_PREFIX OR catkin_FOUND OR CATKIN_BUILD_BINARY_PACKAGE) + set(PJ_PLUGIN_INSTALL_DIRECTORY ${CATKIN_PACKAGE_BIN_DESTINATION}) +elseif(DEFINED ENV{AMENT_PREFIX_PATH}) + set(PJ_PLUGIN_INSTALL_DIRECTORY lib/${PROJECT_NAME}) +else() + set(PJ_PLUGIN_INSTALL_DIRECTORY bin) +endif() -#------- Install the libraries ------- install( - TARGETS - DataAPBin - DESTINATION - ${PJ_PLUGIN_INSTALL_DIRECTORY} ) + TARGETS DataAPBin + DESTINATION ${PJ_PLUGIN_INSTALL_DIRECTORY} +) diff --git a/DataLoadAPBin/dataload_apbin.cpp b/DataLoadAPBin/dataload_apbin.cpp index 29ee830..22b0f6e 100644 --- a/DataLoadAPBin/dataload_apbin.cpp +++ b/DataLoadAPBin/dataload_apbin.cpp @@ -13,15 +13,11 @@ #include "dataload_apbin.h" #include -#include -#include -#include -#include #include #include -#include #include -#include +#include +#include // Debugging @@ -52,6 +48,8 @@ bool is_nearly(double val, int val2) DataLoadAPBIN::DataLoadAPBIN() { extensions.push_back("BIN"); // TODO : this doesn't work for now as tolower() is hardcoded. + qRegisterMetaType>(); + qRegisterMetaType>(); } const std::vector& DataLoadAPBIN::compatibleFileExtensions() const @@ -74,18 +72,6 @@ bool DataLoadAPBIN::readDataFromFile(FileLoadInfo* info, PlotDataMapRef& plot_da const uint32_t len = file_array.size(); uint32_t total_bytes_used = 0; - // Progress box for large file - QProgressDialog progress_dialog; - progress_dialog.setLabelText("Loading ArduPilot logfile... please wait"); - progress_dialog.setWindowModality(Qt::ApplicationModal); - progress_dialog.setRange(0, 100); - progress_dialog.setAutoClose(true); - progress_dialog.setAutoReset(true); - progress_dialog.show(); - - int progress{ 0 }; - int progress_update{ 0 }; - uint32_t bytes_skipped{ 0 }; uint32_t msgs_skipped{ 0 }; uint32_t msgs_read{ 0 }; @@ -107,23 +93,9 @@ bool DataLoadAPBIN::readDataFromFile(FileLoadInfo* info, PlotDataMapRef& plot_da while (true) { - // update the progression dialog box - progress_update = static_cast((static_cast(total_bytes_used) / static_cast(file_size)) * 100.0); - if ( (progress_update - 4) > progress ) - { - progress = progress_update; - progress_dialog.setValue(progress); - QApplication::processEvents(); - if (progress_dialog.wasCanceled()) - { - return false; - } - } - // check if end of file is reached if (len - total_bytes_used < LOG_PACKET_HEADER_LEN) { - progress_dialog.setValue(100); bytes_skipped += len - total_bytes_used; break; } @@ -253,7 +225,6 @@ bool DataLoadAPBIN::readDataFromFile(FileLoadInfo* info, PlotDataMapRef& plot_da // - if we reached the end of the log, just end if (len - total_bytes_used < fmt.length) { - progress_dialog.setValue(100); bytes_skipped += len - total_bytes_used; break; } @@ -383,14 +354,28 @@ bool DataLoadAPBIN::readDataFromFile(FileLoadInfo* info, PlotDataMapRef& plot_da } if ( memcmp(fmt.name, "MSG", 3) == 0 ) { + const auto* msg = reinterpret_cast(&buf[total_bytes_used]); + _status_texts.push_back({msg->time_us, 0, msg->msg}); + total_bytes_used += fmt.length; - msgs_skipped++; + msgs_read++; continue; } if ( memcmp(fmt.name, "PARM", 4) == 0 ) { + const auto* param = reinterpret_cast(&buf[total_bytes_used]); + // std::string val = std::to_string(param->value) + " -> " + std::to_string(param->default_value); + // std::string val = "-> " + std::to_string(param->default_value); + + // char buffer[16]; + // std::snprintf(buffer, sizeof(buffer), "%.2f -> %.2f", param->default_value, param->value); + + std::stringstream ss; + ss << std::fixed << std::setprecision(2) << param->default_value << "(" << param->value << ") "; + _parameters.push_back({param->name, ss.str()}); + total_bytes_used += fmt.length; - msgs_skipped++; + msgs_read++; continue; } @@ -637,6 +622,39 @@ bool DataLoadAPBIN::readDataFromFile(FileLoadInfo* info, PlotDataMapRef& plot_da std::printf("\n Skipped messages:\t%d", msgs_skipped); std::printf("\n Skipped bytes:\t%d from %d bytes\n\n", bytes_skipped, len); + // Now, add the parameters as time series. + for (const auto& param : _parameters) + { + StringSeries& series = plot_data.addStringSeries(std::string("/1_Parameters/") + param.name)->second; + series.pushBack({0.0, param.default_and_value}); + } + + + #ifdef DEBUG_MESSAGES + std::printf("Message Log\n---------------"); + #endif + for(int i = 0; i < _status_texts.size(); i++) + { + #ifdef DEBUG_MESSAGES + std::printf("\n %llu: %s", _status_texts[i].timestamp, _status_texts[i].msg.c_str()); + #endif + + // change "/" to "\" if a status_text contains one so it doesn't create a child entry + std::string msg = _status_texts[i].msg; + size_t start_pos = 0; + while((start_pos = msg.find('/', start_pos)) != std::string::npos) { + msg.replace(start_pos, 1, "\\"); + start_pos += 2; // Handles cases where the replacement also contains the search string + } + + auto series = plot_data.addNumeric(std::string("/2_MessageLog/") + std::to_string(i) + ": " + msg); + series->second.pushBack({0.0, static_cast(_status_texts[i].timestamp)}); + } + + #ifdef DEBUG_MESSAGES + std::printf("\n---------------\n"); + #endif + return true; } diff --git a/DataLoadAPBin/dataload_apbin.h b/DataLoadAPBin/dataload_apbin.h index 69e986d..88f6dea 100644 --- a/DataLoadAPBin/dataload_apbin.h +++ b/DataLoadAPBin/dataload_apbin.h @@ -107,4 +107,7 @@ class DataLoadAPBIN : public DataLoader // apply time synchronization to the messages_map void apply_timesync(void); + + std::vector _parameters; + std::vector _status_texts; }; \ No newline at end of file diff --git a/DataLoadAPBin/logformat.h b/DataLoadAPBin/logformat.h index 21700cb..4738639 100644 --- a/DataLoadAPBin/logformat.h +++ b/DataLoadAPBin/logformat.h @@ -13,6 +13,8 @@ #pragma once #include +#include +#include // PACKED_STRUCT macro cross-platform #ifdef _MSC_VER @@ -158,4 +160,39 @@ struct log_Format_Units { uint8_t format_type; char units[MAX_UNITS_SIZE]; // units example: "s----------" char multipliers[MAX_MULTIPLIERS_SIZE]; // multipliers example: "F----------" -}); \ No newline at end of file +}); + + +PACKED_STRUCT( +struct log_param { + LOG_PACKET_HEADER; + uint64_t time_us; + char name[16]; + float value; + float default_value; +}); + +PACKED_STRUCT( +struct log_message { + LOG_PACKET_HEADER; + uint64_t time_us; + char msg[64]; +}); + +struct Parameter +{ + std::string name; + std::string default_and_value; +}; + +struct StatusText +{ + uint64_t timestamp; + uint8_t severity; + std::string msg; +}; + +Q_DECLARE_METATYPE(Parameter); +Q_DECLARE_METATYPE(StatusText); +Q_DECLARE_METATYPE(std::vector); +Q_DECLARE_METATYPE(std::vector); \ No newline at end of file From f534a04f554d48f669ac24982751b101f4c38b01 Mon Sep 17 00:00:00 2001 From: Terran Gerratt Date: Mon, 19 Jan 2026 23:39:55 -0700 Subject: [PATCH 3/6] - show default param values - add labels for configured RCOU functions --- DataLoadAPBin/dataload_apbin.cpp | 68 +++++++++--- DataLoadAPBin/dataload_apbin.h | 174 +++++++++++++++++++++++++++++++ DataLoadAPBin/logformat.h | 2 +- 3 files changed, 230 insertions(+), 14 deletions(-) diff --git a/DataLoadAPBin/dataload_apbin.cpp b/DataLoadAPBin/dataload_apbin.cpp index 22b0f6e..4b13652 100644 --- a/DataLoadAPBin/dataload_apbin.cpp +++ b/DataLoadAPBin/dataload_apbin.cpp @@ -16,7 +16,7 @@ #include #include #include -#include +#include #include @@ -364,15 +364,26 @@ bool DataLoadAPBIN::readDataFromFile(FileLoadInfo* info, PlotDataMapRef& plot_da if ( memcmp(fmt.name, "PARM", 4) == 0 ) { const auto* param = reinterpret_cast(&buf[total_bytes_used]); - // std::string val = std::to_string(param->value) + " -> " + std::to_string(param->default_value); - // std::string val = "-> " + std::to_string(param->default_value); - - // char buffer[16]; - // std::snprintf(buffer, sizeof(buffer), "%.2f -> %.2f", param->default_value, param->value); - - std::stringstream ss; - ss << std::fixed << std::setprecision(2) << param->default_value << "(" << param->value << ") "; - _parameters.push_back({param->name, ss.str()}); + std::string name = std::string(param->name); + _parameters.push_back({name + " Default: " + format_value(param->default_value) , param->value}); + + // save servo functions + QRegExp rx("SERVO(\\d+)_FUNCTION"); + if (rx.indexIn(QString::fromStdString(name)) != -1) { + bool is_int = false; + int servo_idx = rx.cap(1).toInt(&is_int); + + if (is_int && servo_idx > 0 && servo_idx <= 32) { + const int function_id = static_cast(param->value); + // skip over the "disabled" ones + if (function_id != 0) { + auto it = SERVO_FUNCTION_MAP.find(function_id); + if (it != SERVO_FUNCTION_MAP.end()) { + _servo_function_labels[servo_idx - 1] = it->second; + } + } + } + } total_bytes_used += fmt.length; msgs_read++; @@ -570,6 +581,19 @@ bool DataLoadAPBIN::readDataFromFile(FileLoadInfo* info, PlotDataMapRef& plot_da { series_name = "/" + msg_name + "/" + instance_name + "/" + field_name; } + + // label servo functions + if (msg_name == "RCOU" || msg_name == "RCO2") { + QRegExp re(R"(C(\d+))"); + if(re.indexIn(QString::fromStdString(field_name)) != -1) { + int label_idx = re.cap(1).toInt() - 1; // is 1-based + + if(label_idx >= 0 && label_idx < 32 && !_servo_function_labels[label_idx].empty()) { + series_name = series_name + " (" + _servo_function_labels[label_idx] + ")"; + } + } + } + #ifdef LABEL_WITH_UNIT std::string unit_str = get_unit(msg_name, field_name); @@ -622,11 +646,21 @@ bool DataLoadAPBIN::readDataFromFile(FileLoadInfo* info, PlotDataMapRef& plot_da std::printf("\n Skipped messages:\t%d", msgs_skipped); std::printf("\n Skipped bytes:\t%d from %d bytes\n\n", bytes_skipped, len); + #ifdef DEBUG_RUNTIME + for (int i = 0; i < 32; i++) { + if (i < 14) { + std::printf("\nRCOU.C%d: %s", i + 1, _servo_function_labels[i].c_str()); + } else { + std::printf("\nRCO2.C%d: %s", i + 1, _servo_function_labels[i].c_str()); + } + } + #endif + // Now, add the parameters as time series. for (const auto& param : _parameters) { - StringSeries& series = plot_data.addStringSeries(std::string("/1_Parameters/") + param.name)->second; - series.pushBack({0.0, param.default_and_value}); + auto series = plot_data.addNumeric(std::string("/1_Parameters/") + param.name); + series->second.pushBack({300, param.value}); } @@ -658,9 +692,17 @@ bool DataLoadAPBIN::readDataFromFile(FileLoadInfo* info, PlotDataMapRef& plot_da return true; } +std::string DataLoadAPBIN::format_value(float val) { + std::ostringstream ss; + ss << std::fixed << std::setprecision(2) << val; + std::string s = ss.str(); + // trim trailing zeros + s.erase(s.find_last_not_of('0') + 1); + if (!s.empty() && s.back() == '.') s.pop_back(); - + return s; +} void DataLoadAPBIN::handle_message_received(const struct log_Format& fmt, const uint8_t* msg) { diff --git a/DataLoadAPBin/dataload_apbin.h b/DataLoadAPBin/dataload_apbin.h index 88f6dea..7486a9d 100644 --- a/DataLoadAPBin/dataload_apbin.h +++ b/DataLoadAPBin/dataload_apbin.h @@ -86,6 +86,9 @@ class DataLoadAPBIN : public DataLoader std::map> field_name2idx; + // helper + std::string format_value(float val); + // fill the message_data for a message according to the message format void handle_message_received(const struct log_Format& fmt, const uint8_t* msg); @@ -110,4 +113,175 @@ class DataLoadAPBIN : public DataLoader std::vector _parameters; std::vector _status_texts; + std::string _servo_function_labels[32]; + + const std::map SERVO_FUNCTION_MAP = { + {-1, "GPIO"}, + {0, "Disabled"}, + {1, "RCPassThru"}, + {2, "Flap"}, + {3, "FlapAuto"}, + {4, "Aileron"}, + {6, "Mount1Yaw"}, + {7, "Mount1Pitch"}, + {8, "Mount1Roll"}, + {9, "Mount1Retract"}, + {10, "CameraTrigger"}, + {12, "Mount2Yaw"}, + {13, "Mount2Pitch"}, + {14, "Mount2Roll"}, + {15, "Mount2Retract"}, + {16, "DifferentialSpoilerLeft1"}, + {17, "DifferentialSpoilerRight1"}, + {19, "Elevator"}, + {21, "Rudder"}, + {22, "SprayerPump"}, + {23, "SprayerSpinner"}, + {24, "FlaperonLeft"}, + {25, "FlaperonRight"}, + {26, "GroundSteering"}, + {27, "Parachute"}, + {28, "Gripper"}, + {29, "LandingGear"}, + {30, "EngineRunEnable"}, + {31, "HeliRSC"}, + {32, "HeliTailRSC"}, + {33, "Motor1"}, + {34, "Motor2"}, + {35, "Motor3"}, + {36, "Motor4"}, + {37, "Motor5"}, + {38, "Motor6"}, + {39, "Motor7\\TailTiltServo"}, + {40, "Motor8"}, + {41, "TiltMotorsFront"}, + {45, "TiltMotorsRear"}, + {46, "TiltMotorRearLeft"}, + {47, "TiltMotorRearRight"}, + {51, "RCIN1\\Pitch"}, + {52, "RCIN2\\Roll"}, + {53, "RCIN3\\HeaveVertical"}, + {54, "RCIN4\\YawTurn"}, + {55, "RCIN5\\SurgeForward"}, + {56, "RCIN6\\SwayLateral"}, + {57, "RCIN7\\CameraPan"}, + {58, "RCIN8\\CameraTilt"}, + {59, "RCIN9"}, + {60, "RCIN10"}, + {61, "RCIN11"}, + {62, "RCIN12"}, + {63, "RCIN13"}, + {64, "RCIN14"}, + {65, "RCIN15"}, + {66, "RCIN16"}, + {67, "Ignition"}, + {69, "Starter"}, + {70, "Throttle"}, + {71, "TrackerYaw"}, + {72, "TrackerPitch"}, + {73, "ThrottleLeft"}, + {74, "ThrottleRight"}, + {75, "TiltMotorFrontLeft"}, + {76, "TiltMotorFrontRight"}, + {77, "ElevonLeft"}, + {78, "ElevonRight"}, + {79, "VTailLeft"}, + {80, "VTailRight"}, + {81, "BoostThrottle"}, + {82, "Motor9"}, + {83, "Motor10"}, + {84, "Motor11"}, + {85, "Motor12"}, + {86, "DifferentialSpoilerLeft2"}, + {87, "DifferentialSpoilerRight2"}, + {88, "Winch"}, + {89, "Main Sail"}, + {90, "CameraISO"}, + {91, "CameraAperture"}, + {92, "CameraFocus"}, + {93, "CameraShutterSpeed"}, + {94, "Script1"}, + {95, "Script2"}, + {96, "Script3"}, + {97, "Script4"}, + {98, "Script5"}, + {99, "Script6"}, + {100, "Script7"}, + {101, "Script8"}, + {102, "Script9"}, + {103, "Script10"}, + {104, "Script11"}, + {105, "Script12"}, + {106, "Script13"}, + {107, "Script14"}, + {108, "Script15"}, + {109, "Script16"}, + {110, "Airbrakes"}, + {120, "NeoPixel1"}, + {121, "NeoPixel2"}, + {122, "NeoPixel3"}, + {123, "NeoPixel4"}, + {124, "RateRoll"}, + {125, "RatePitch"}, + {126, "RateThrust"}, + {127, "RateYaw"}, + {128, "WingSailElevator"}, + {129, "ProfiLED1"}, + {130, "ProfiLED2"}, + {131, "ProfiLED3"}, + {132, "ProfiLEDClock"}, + {133, "Winch Clutch"}, + {134, "SERVOn_MIN"}, + {135, "SERVOn_TRIM"}, + {136, "SERVOn_MAX"}, + {137, "SailMastRotation"}, + {138, "Alarm"}, + {139, "Alarm Inverted"}, + {140, "RCIN1Scaled"}, + {141, "RCIN2Scaled"}, + {142, "RCIN3Scaled"}, + {143, "RCIN4Scaled"}, + {144, "RCIN5Scaled"}, + {145, "RCIN6Scaled"}, + {146, "RCIN7Scaled"}, + {147, "RCIN8Scaled"}, + {148, "RCIN9Scaled"}, + {149, "RCIN10Scaled"}, + {150, "RCIN11Scaled"}, + {151, "RCIN12Scaled"}, + {152, "RCIN13Scaled"}, + {153, "RCIN14Scaled"}, + {154, "RCIN15Scaled"}, + {155, "RCIN16Scaled"}, + {160, "Motor13"}, + {161, "Motor14"}, + {162, "Motor15"}, + {163, "Motor16"}, + {164, "Motor17"}, + {165, "Motor18"}, + {166, "Motor19"}, + {167, "Motor20"}, + {168, "Motor21"}, + {169, "Motor22"}, + {170, "Motor23"}, + {171, "Motor24"}, + {172, "Motor25"}, + {173, "Motor26"}, + {174, "Motor27"}, + {175, "Motor28"}, + {176, "Motor29"}, + {177, "Motor30"}, + {178, "Motor31"}, + {179, "Motor32"}, + {180, "CameraZoom"}, + {181, "Lights1"}, + {182, "Lights2"}, + {183, "VideoSwitch"}, + {184, "Actuator1"}, + {185, "Actuator2"}, + {186, "Actuator3"}, + {187, "Actuator4"}, + {188, "Actuator5"}, + {189, "Actuator6"} + }; }; \ No newline at end of file diff --git a/DataLoadAPBin/logformat.h b/DataLoadAPBin/logformat.h index 4738639..6f66a40 100644 --- a/DataLoadAPBin/logformat.h +++ b/DataLoadAPBin/logformat.h @@ -182,7 +182,7 @@ struct log_message { struct Parameter { std::string name; - std::string default_and_value; + double value; }; struct StatusText From ef2bdf9c2f5c1653f7088f615f222448a412a926 Mon Sep 17 00:00:00 2001 From: Terran Gerratt Date: Fri, 23 Jan 2026 15:27:33 -0700 Subject: [PATCH 4/6] sync message timeline and values to plot time --- DataLoadAPBin/dataload_apbin.cpp | 48 +++++++++++++++++++++++++------- DataLoadAPBin/dataload_apbin.h | 8 ++++-- 2 files changed, 44 insertions(+), 12 deletions(-) diff --git a/DataLoadAPBin/dataload_apbin.cpp b/DataLoadAPBin/dataload_apbin.cpp index 4b13652..39d30c2 100644 --- a/DataLoadAPBin/dataload_apbin.cpp +++ b/DataLoadAPBin/dataload_apbin.cpp @@ -18,6 +18,7 @@ #include #include #include +#include // Debugging @@ -365,7 +366,7 @@ bool DataLoadAPBIN::readDataFromFile(FileLoadInfo* info, PlotDataMapRef& plot_da { const auto* param = reinterpret_cast(&buf[total_bytes_used]); std::string name = std::string(param->name); - _parameters.push_back({name + " Default: " + format_value(param->default_value) , param->value}); + _parameters.push_back({name + " Default: " + format_default_value(param->default_value) , param->value}); // save servo functions QRegExp rx("SERVO(\\d+)_FUNCTION"); @@ -659,7 +660,7 @@ bool DataLoadAPBIN::readDataFromFile(FileLoadInfo* info, PlotDataMapRef& plot_da // Now, add the parameters as time series. for (const auto& param : _parameters) { - auto series = plot_data.addNumeric(std::string("/1_Parameters/") + param.name); + auto series = plot_data.addNumeric(std::string("/1. Parameters/") + param.name); series->second.pushBack({300, param.value}); } @@ -667,6 +668,7 @@ bool DataLoadAPBIN::readDataFromFile(FileLoadInfo* info, PlotDataMapRef& plot_da #ifdef DEBUG_MESSAGES std::printf("Message Log\n---------------"); #endif + for(int i = 0; i < _status_texts.size(); i++) { #ifdef DEBUG_MESSAGES @@ -681,8 +683,13 @@ bool DataLoadAPBIN::readDataFromFile(FileLoadInfo* info, PlotDataMapRef& plot_da start_pos += 2; // Handles cases where the replacement also contains the search string } - auto series = plot_data.addNumeric(std::string("/2_MessageLog/") + std::to_string(i) + ": " + msg); - series->second.pushBack({0.0, static_cast(_status_texts[i].timestamp)}); + auto time_s = static_cast(_status_texts[i].timestamp)/1e6; + + auto& timeline = plot_data.getOrCreateNumeric("/2. Message Timeline"); + timeline.pushBack({time_s + _time_offset, (double)(i + 1)}); + + auto series = plot_data.addNumeric(std::string("/3. Message Log/") + std::to_string(i + 1) + ". " + msg); + series->second.pushBack({0.0, time_s - _start_plot_time}); } #ifdef DEBUG_MESSAGES @@ -692,7 +699,7 @@ bool DataLoadAPBIN::readDataFromFile(FileLoadInfo* info, PlotDataMapRef& plot_da return true; } -std::string DataLoadAPBIN::format_value(float val) { +std::string DataLoadAPBIN::format_default_value(float val) { std::ostringstream ss; ss << std::fixed << std::setprecision(2) << val; std::string s = ss.str(); @@ -704,6 +711,29 @@ std::string DataLoadAPBIN::format_value(float val) { return s; } +std::string DataLoadAPBIN::format_time(double seconds) +{ + int minutes = static_cast(seconds / 60.0); + double rem = seconds - minutes * 60.0; + + int secs = static_cast(rem); + int tenths = static_cast(std::round((rem - secs) * 10.0)); + + // handle rounding overflow (e.g. 59.96 -> 1:00.0) + if (tenths == 10) { + tenths = 0; + secs++; + if (secs == 60) { + secs = 0; + minutes++; + } + } + + char buf[16]; + std::snprintf(buf, sizeof(buf), "%d:%02d.%d", minutes, secs, tenths); + return buf; +} + void DataLoadAPBIN::handle_message_received(const struct log_Format& fmt, const uint8_t* msg) { // message id @@ -1058,10 +1088,8 @@ void DataLoadAPBIN::apply_timesync(void) const double unix_time = gps_week * SECONDS_PER_WEEK + gps_week_seconds + GPS2UNIX_TIME_OFFSET + GPS2UNIX_LEAP_SECONDS; - const double& log_time = gps_msg_data[gps_time_idx].second[1]; - - const double time_offset = unix_time - log_time; - + _start_plot_time = gps_msg_data[gps_time_idx].second[1]; + _time_offset = unix_time - _start_plot_time; // iterate through messages for (auto& msg_it : messages_map) @@ -1083,7 +1111,7 @@ void DataLoadAPBIN::apply_timesync(void) message_data& msg_data = inst_it.second; std::vector& timestamps = msg_data[time_idx].second; - std::transform(timestamps.begin(), timestamps.end(), timestamps.begin(), std::bind(std::plus(), std::placeholders::_1, time_offset)); + std::transform(timestamps.begin(), timestamps.end(), timestamps.begin(), std::bind(std::plus(), std::placeholders::_1, _time_offset)); } } } \ No newline at end of file diff --git a/DataLoadAPBin/dataload_apbin.h b/DataLoadAPBin/dataload_apbin.h index 7486a9d..3e42eab 100644 --- a/DataLoadAPBin/dataload_apbin.h +++ b/DataLoadAPBin/dataload_apbin.h @@ -86,8 +86,9 @@ class DataLoadAPBIN : public DataLoader std::map> field_name2idx; - // helper - std::string format_value(float val); + // helpers + std::string format_default_value(float val); + std::string format_time(double seconds); // fill the message_data for a message according to the message format void handle_message_received(const struct log_Format& fmt, const uint8_t* msg); @@ -111,6 +112,9 @@ class DataLoadAPBIN : public DataLoader // apply time synchronization to the messages_map void apply_timesync(void); + double _start_plot_time; + double _time_offset; + std::vector _parameters; std::vector _status_texts; std::string _servo_function_labels[32]; From 80b8471f99453fc7278f8131ac6f83d2d3a0445a Mon Sep 17 00:00:00 2001 From: Terran Gerratt Date: Fri, 23 Jan 2026 19:31:51 -0700 Subject: [PATCH 5/6] add field description parser and tooltips --- CMakeLists.txt | 27 + .../LogMessageDescriptions/Copter.xml | 11928 +++++++++++++++ .../LogMessageDescriptions/Plane.xml | 12362 ++++++++++++++++ DataLoadAPBin/dataload_apbin.cpp | 107 + DataLoadAPBin/dataload_apbin.h | 7 + .../generate_LogMessageDescriptions_header.py | 86 + 6 files changed, 24517 insertions(+) create mode 100644 DataLoadAPBin/LogMessageDescriptions/Copter.xml create mode 100644 DataLoadAPBin/LogMessageDescriptions/Plane.xml create mode 100644 DataLoadAPBin/scripts/generate_LogMessageDescriptions_header.py diff --git a/CMakeLists.txt b/CMakeLists.txt index 27e588a..b3319db 100755 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -12,6 +12,24 @@ set(CMAKE_INCLUDE_CURRENT_DIR ON) find_package(Qt5 REQUIRED COMPONENTS Core Concurrent Widgets Xml Svg) +# Generate embedded log message descriptions header at build time +find_program(PYTHON3_EXECUTABLE python3 python) +if(NOT PYTHON3_EXECUTABLE) + message(STATUS "Python3 not found; logmessage header generation will create an empty header at build time") +else() + set(GEN_LOGMSG_HDR_OUT ${CMAKE_CURRENT_BINARY_DIR}/LogMessageDescriptions.h) + add_custom_command( + OUTPUT ${GEN_LOGMSG_HDR_OUT} + COMMAND ${PYTHON3_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/DataLoadAPBin/scripts/generate_LogMessageDescriptions_header.py + ${CMAKE_CURRENT_SOURCE_DIR}/DataLoadAPBin/LogMessageDescriptions + ${GEN_LOGMSG_HDR_OUT} + DEPENDS ${CMAKE_CURRENT_SOURCE_DIR}/DataLoadAPBin/scripts/generate_LogMessageDescriptions_header.py + COMMENT "Generating LogMessageDescriptions.h from available XML files" + VERBATIM + ) + add_custom_target(gen_logmsg_hdr DEPENDS ${GEN_LOGMSG_HDR_OUT}) +endif() + #--- Find PlotJuggler and its dependencies, and set paths if(CATKIN_DEVEL_PREFIX OR catkin_FOUND OR CATKIN_BUILD_BINARY_PACKAGE) # --- Build with CATKIN (ROS1) --- @@ -61,6 +79,15 @@ target_link_libraries(DataAPBin PRIVATE Qt5::Svg ) +# Ensure generated header is available and included +if(TARGET gen_logmsg_hdr) + add_dependencies(DataAPBin gen_logmsg_hdr) + target_include_directories(DataAPBin PRIVATE ${CMAKE_CURRENT_BINARY_DIR}) +else() + # still add build dir to include path so an empty autogenerated header may be placed there by other tooling + target_include_directories(DataAPBin PRIVATE ${CMAKE_CURRENT_BINARY_DIR}) +endif() + if (COMPILING_WITH_AMENT) ament_target_dependencies(DataAPBin plotjuggler) endif() diff --git a/DataLoadAPBin/LogMessageDescriptions/Copter.xml b/DataLoadAPBin/LogMessageDescriptions/Copter.xml new file mode 100644 index 0000000..5d766a3 --- /dev/null +++ b/DataLoadAPBin/LogMessageDescriptions/Copter.xml @@ -0,0 +1,11928 @@ + + + + + + IMU accelerometer data + + + Time since system startup + + + accelerometer sensor instance number + + + time since system startup this sample was taken + + + acceleration along X axis + + + acceleration along Y axis + + + acceleration along Z axis + + + + + Automatic Dependent Serveillance - Broadcast detected vehicle information + + + Time since system startup + + + Transponder address + + + Vehicle latitude + + + Vehicle longitude + + + Vehicle altitude + + + Vehicle heading + + + Vehicle horizontal velocity + + + Vehicle vertical velocity + + + Transponder squawk code + + + + + Backup AHRS data + + + Time since system startup + + + Estimated roll + + + Estimated pitch + + + Estimated yaw + + + Estimated altitude + + + Estimated latitude + + + Estimated longitude + + + Estimated attitude quaternion component 1 + + + Estimated attitude quaternion component 2 + + + Estimated attitude quaternion component 3 + + + Estimated attitude quaternion component 4 + + + + + Contents of 'position report' AIS message, see: https://gpsd.gitlab.io/gpsd/AIVDM.html#_types_1_2_and_3_position_report_class_a + + + Time since system startup + + + Message Type + + + Repeat Indicator + + + MMSI + + + Navigation Status + + + Rate of Turn (ROT) + + + Speed Over Ground (SOG) + + + Position Accuracy + + + Longitude + + + Latitude + + + Course Over Ground (COG) + + + True Heading (HDG) + + + Time Stamp + + + Maneuver Indicator + + + RAIM flag + + + Radio status + + + + + Contents of 'Base Station Report' AIS message, see: https://gpsd.gitlab.io/gpsd/AIVDM.html#_type_4_base_station_report + + + Time since system startup + + + Repeat Indicator + + + MMSI + + + Year (UTC) + + + Month (UTC) + + + Day (UTC) + + + Hour (UTC) + + + Minute (UTC) + + + Second (UTC) + + + Fix quality + + + Longitude + + + Latitude + + + Type of EPFD + + + RAIM flag + + + Radio status + + + + + Contents of 'static and voyage related data' AIS message, see: https://gpsd.gitlab.io/gpsd/AIVDM.html#_type_5_static_and_voyage_related_data + + + Time since system startup + + + Repeat Indicator + + + MMSI + + + AIS Version + + + IMO Number + + + Call Sign + + + Vessel Name + + + Ship Type + + + Dimension to Bow + + + Dimension to Stern + + + Dimension to Port + + + Dimension to Starboard + + + Position Fix Type + + + Draught + + + Destination + + + DTE + + + + + Raw AIS AVDIM messages contents, see: https://gpsd.gitlab.io/gpsd/AIVDM.html#_aivdmaivdo_sentence_layer + + + Time since system startup + + + count of fragments in the currently accumulating message + + + fragment number of this sentence + + + sequential message ID for multi-sentence messages + + + data payload + + + + + Attitude control attitude + + + Timestamp of the current Attitude loop + + + vehicle desired roll + + + achieved vehicle roll + + + vehicle desired pitch + + + achieved vehicle pitch + + + vehicle desired yaw + + + achieved vehicle yaw + + + attitude delta time + + + + + Angle of attack and Side Slip Angle values + + + Time since system startup + + + Angle of Attack calculated from airspeed, wind vector,velocity vector + + + Side Slip Angle calculated from airspeed, wind vector,velocity vector + + + + + helicopter AutoRotation Head Speed (ARHS) controller information + + + Time since system startup + + + Normalised target head speed + + + Normalised measured head speed + + + Head speed controller error + + + P-term for head speed controller response + + + FF-term for head speed controller response + + + + + Arming status changes + + + Time since system startup + + + true if vehicle is now armed + + + arming bitmask at time of arming + + + 2 + + + 4 + + + 8 + + + 16 + + + 32 + + + 64 + + + 128 + + + 256 + + + 512 + + + 1024 + + + 2048 + + + 4096 + + + 8192 + + + 16384 + + + 32768 + + + 65536 + + + 131072 + + + 262144 + + + 524288 + + + 1048576 + + + 2097152 + + + + + true if arm/disarm was forced + + + method used for arming + + + 0 + + + 1 + + + 2 + + + 3 + + + 4 + + + 5 + only disarm uses this... + + + 6 + only disarm uses this... + + + 7 + only disarm uses this... + + + 8 + only disarm uses this... + + + 9 + only disarm uses this... + + + 10 + only disarm uses this... + + + 11 + only disarm uses this... + + + 12 + only disarm uses this... + + + 13 + only disarm uses this... + + + 14 + only disarm uses this... + + + 15 + only disarm uses this... + + + 16 + only disarm uses this... + + + 17 + only disarm uses this... + + + 18 + only disarm uses this... + + + 19 + only disarm uses this... + + + 20 + only disarm uses this... + + + 21 + only disarm uses this... + + + 22 + only disarm uses this... + + + 23 + only disarm uses this... + + + 24 + only disarm uses this... + + + 25 + only disarm uses this... + + + 26 + only disarm uses this... + + + 27 + only disarm uses this... + + + 28 + only disarm uses this... + + + 29 + only disarm uses this... + + + 30 + only disarm uses this... + + + 31 + only disarm uses this... + + + 32 + only disarm uses this... + + + 33 + only disarm uses this... + + + 34 + + + 35 + + + 36 + + + 37 + + + 38 + + + 100 + + + + + + + Helicopter AutoROTation (AROT) information + + + Time since system startup + + + Landed Reason state flags + + + 1 + true if below 1 m/s + + + 2 + true if collective below land col min + + + 4 + passes inertial nav is_still() check + + + + + + + Helicopter AutoRotation Speed Controller (ARSC) information + + + Time since system startup + + + Desired forward velocity + + + Target forward velocity + + + Measured forward velocity + + + Velocity to acceleration P-term component + + + Velocity to acceleration I-term component + + + Velocity to acceleration D-term component + + + Velocity to acceleration feed forward component + + + Accel limit flag + + + Forward acceleration target + + + Lateral acceleration target + + + + + Airspeed sensor data + + + Time since system startup + + + Airspeed sensor instance number + + + Current airspeed + + + Pressure difference between static and dynamic port + + + Temperature used for calculation + + + Raw pressure less offset + + + Offset from parameter + + + True if sensor is being used + + + True if sensor is healthy + + + Probability sensor is healthy + + + innovation test ratio + + + Primary instance number. If equal to I then this sensor is primary sensor + + + + + AirSim simulation data + + + Time since system startup + + + Simulation's timestamp + + + Simulation's roll + + + Simulation's pitch + + + Simulation's yaw + + + Simulated gyroscope, X-axis + + + Simulated gyroscope, Y-axis + + + Simulated gyroscope, Z-axis + + + + + More AirSim simulation data + + + Time since system startup + + + simulation's acceleration, X-axis + + + simulation's acceleration, Y-axis + + + simulation's acceleration, Z-axis + + + simulation's velocity, X-axis + + + simulation's velocity, Y-axis + + + simulation's velocity, Z-axis + + + simulation's position, X-axis + + + simulation's position, Y-axis + + + simulation's position, Z-axis + + + simulation's gps altitude + + + simulation's earth-frame speed-down + + + + + AutoTune data packet + + + Time since system startup + + + current angle + + + current angular rate + + + + + Heli AutoTune data packet + + + Time since system startup + + + current motor command + + + current target angular rate + + + current angular rate + + + current target angle + + + current angle + + + + + Heli AutoTune + + + Time since system startup + + + which axis is currently being tuned + + + step in autotune process + + + target dwell frequency + + + measured gain of dwell + + + measured phase of dwell + + + new rate gain FF term + + + new rate gain P term + + + new rate gain D term + + + new angle P term + + + new max accel term + + + + + Scale factors for attitude controller + + + Time since system startup + + + Angle P scale X + + + Angle P scale Y + + + Angle P scale Z + + + PD scale X + + + PD scale Y + + + PD scale Z + + + I scale X + + + I scale Y + + + I scale Z + + + + + Heli AutoTune Sweep packet + + + Time since system startup + + + current frequency for motor input to rate + + + current response gain for motor input to rate + + + current response phase for motor input to rate + + + current frequency for target rate to rate + + + current response gain for target rate to rate + + + current response phase for target rate to rate + + + + + Canonical vehicle attitude + + + Time since system startup + + + vehicle desired roll + + + achieved vehicle roll + + + vehicle desired pitch + + + achieved vehicle pitch + + + vehicle desired yaw + + + achieved vehicle yaw + + + active EKF type + + + + + Copter/QuadPlane AutoTune + + + Time since system startup + + + which axis is currently being tuned + + + step in autotune process + + + target angle or rate, depending on tuning step + + + measured minimum target angle or rate + + + measured maximum target angle or rate + + + new rate gain P term + + + new rate gain D term + + + new angle P term + + + maximum measured twitching acceleration + + + + + Auxiliary function invocation information + + + Time since system startup + + + ID of triggered function + + + 0 + aux switch disabled + + + 2 + flip + + + 3 + change to simple mode + + + 4 + change to RTL flight mode + + + 5 + save current position as level + + + 7 + save mission waypoint or RTL if in auto mode + + + 9 + trigger camera servo or relay + + + 10 + allow enabling or disabling rangefinder in flight which helps avoid surface tracking when you are far above the ground + + + 11 + allow enabling or disabling fence in flight + + + 12 + UNUSED + + + 13 + change to simple mode in middle, super simple at top + + + 14 + low = disabled, middle = leveled, high = leveled and limited + + + 15 + enable/disable the crop sprayer + + + 16 + change to auto flight mode + + + 17 + auto tune + + + 18 + change to LAND flight mode + + + 19 + Operate cargo grippers low=off, middle=neutral, high=on + + + 21 + Parachute enable/disable + + + 22 + Parachute release + + + 23 + Parachute disable, enable, release with 3 position switch + + + 24 + Reset auto mission to start from first command + + + 25 + enable/disable the roll and pitch rate feed forward + + + 26 + enable/disable the roll, pitch and yaw accel limiting + + + 27 + Retract Mount1 + + + 28 + Relay pin on/off (only supports first relay) + + + 29 + Landing gear controller + + + 30 + Play lost vehicle sound + + + 31 + Emergency Stop Switch + + + 32 + Motor On/Off switch + + + 33 + Brake flight mode + + + 34 + Relay2 pin on/off + + + 35 + Relay3 pin on/off + + + 36 + Relay4 pin on/off + + + 37 + change to THROW flight mode + + + 38 + enable AP_Avoidance library + + + 39 + enable precision loiter + + + 40 + enable object avoidance using proximity sensors (ie. horizontal lidar) + + + 41 + UNUSED + + + 42 + change to SmartRTL flight mode + + + 43 + enable inverted flight + + + 44 + winch enable/disable + + + 45 + winch control + + + 46 + enable RC Override + + + 47 + user function #1 + + + 48 + user function #2 + + + 49 + user function #3 + + + 50 + learn cruise throttle (Rover) + + + 51 + manual mode + + + 52 + acro mode + + + 53 + steering mode + + + 54 + hold mode + + + 55 + guided mode + + + 56 + loiter mode + + + 57 + follow mode + + + 58 + clear waypoints + + + 59 + simple mode + + + 60 + zigzag mode + + + 61 + zigzag save waypoint + + + 62 + learn compass offsets + + + 63 + rover sailboat tack + + + 64 + reverse throttle input + + + 65 + disable GPS for testing + + + 66 + Relay5 pin on/off + + + 67 + Relay6 pin on/off + + + 68 + stabilize mode + + + 69 + poshold mode + + + 70 + althold mode + + + 71 + flowhold mode + + + 72 + circle mode + + + 73 + drift mode + + + 74 + Sailboat motoring 3pos + + + 75 + Surface tracking upwards or downwards + + + 76 + Standby mode + + + 77 + takeoff + + + 78 + control RunCam device + + + 79 + control RunCam OSD + + + 80 + align visual odometry camera's attitude to AHRS + + + 81 + disarm vehicle + + + 82 + disable, enable and force Q assist + + + 83 + zigzag auto switch + + + 84 + enable / disable airmode for copter + + + 85 + generator control + + + 86 + disable terrain following in CRUISE/FBWB modes + + + 87 + select CROW mode for diff spoilers;high disables,mid forces progressive + + + 88 + three-position switch to set soaring mode + + + 89 + force flare, throttle forced idle, pitch to LAND_PITCH_DEG, tilts up + + + 90 + change EKF data source set between primary, secondary and tertiary + + + 91 + calibrate airspeed ratio + + + 92 + Fly-By-Wire-A + + + 93 + used in separate branch MISSION_RELATIVE + + + 94 + VTX power level + + + 95 + enables FBWA taildragger takeoff mode. Once this feature is enabled it will stay enabled until the aircraft goes above TKOFF_TDRAG_SPD1 airspeed, changes mode, or the pitch goes above the initial pitch when this is engaged or goes below 0 pitch. When enabled the elevator will be forced to TKOFF_TDRAG_ELEV. This option allows for easier takeoffs on taildraggers in FBWA mode, and also makes it easier to test auto-takeoff steering handling in FBWA. + + + 96 + trigger re-reading of mode switch + + + 97 + flag for windvane direction offset input, used with windvane type 2 + + + 98 + mode training + + + 99 + AUTO RTL via DO_LAND_START + + + 100 + disable first IMU (for IMU failure testing) + + + 101 + disable second IMU (for IMU failure testing) + + + 102 + Momentary switch to cycle camera modes + + + 103 + trigger lane switch attempt + + + 104 + trigger yaw reset attempt + + + 105 + disable GPS yaw for testing + + + 106 + equivalent to AIRSPEED_USE 0 + + + 107 + fixed wing auto tune + + + 108 + QRTL mode + + + 109 + use Custom Controller + + + 110 + disable third IMU (for IMU failure testing) + + + 111 + allows for manually running starter + + + 112 + change AHRS_EKF_TYPE + + + 113 + Retract Mount2 + + + 150 + CRUISE mode + + + 151 + Turtle mode - flip over after crash + + + 152 + reset simple mode reference heading to current + + + 153 + arm or disarm vehicle + + + 154 + arm or disarm vehicle enabling airmode + + + 155 + trim to current servo and RC + + + 156 + clear torqeedo error + + + 157 + Force long FS action to FBWA for landing out of range + + + 158 + optical flow calibration + + + 159 + enable or disable land detection for GPS based manual modes preventing land detection and maintainting set_throttle_mix_max + + + 160 + enable/disable weathervaning + + + 161 + initialize turbine start sequence + + + 162 + FFT notch tuning function + + + 163 + Mount earth frame yaw lock forced on all axes, for all mounts + + + 164 + Pauses logging if under logging rate control + + + 165 + ARM on high, MOTOR_ESTOP on low + + + 166 + start recording on high, stop recording on low + + + 167 + camera zoom high = zoom in, middle = hold, low = zoom out + + + 168 + camera manual focus. high = long shot, middle = stop focus, low = close shot + + + 169 + camera auto focus + + + 170 + QuadPlane QStabilize mode + + + 171 + Calibrate compasses (disarmed only) + + + 172 + Battery MPPT Power enable. high = ON, mid = auto (controlled by mppt/batt driver), low = OFF. This effects all MPPTs. + + + 173 + Abort Glide-slope or VTOL landing during payload place or do_land type mission items + + + 174 + camera image tracking + + + 175 + camera lens selection + + + 176 + force enabled VTOL forward throttle method + + + 177 + mount LRF enable/disable + + + 178 + e.g. pause movement towards waypoint + + + 179 + AP_ICEngine start stop + + + 180 + auto tune tuning switch to test or revert gains + + + 181 + quicktune 3 position switch + + + 182 + in-flight AHRS autotrim + + + 183 + Fixed Wing AUTOLAND Mode + + + 184 + system ID as an aux switch + + + 185 + mount lock modes for roll and pitch axes, for all mounts that support it + + + 186 + Lock mount target to current ROI seen and switch mount to GPS Targeting mode + + + 201 + roll input + + + 202 + pitch input + + + 203 + throttle pilot input + + + 204 + yaw pilot input + + + 207 + mainsail input + + + 208 + flap input + + + 209 + VTOL manual forward throttle + + + 210 + manual airbrake control + + + 211 + walking robot height input + + + 212 + mount1 roll input + + + 213 + mount1 pitch input + + + 214 + mount1 yaw input + + + 215 + mount2 roll input + + + 216 + mount3 pitch input + + + 217 + mount4 yaw input + + + 218 + allows for throttle on slider + + + 219 + use a transmitter knob or slider for in-flight tuning + + + 220 + use another transmitter knob or slider for in-flight tuning + + + 300 + + + 301 + + + 302 + + + 303 + + + 304 + + + 305 + + + 306 + + + 307 + + + 308 + + + 309 + + + 310 + + + 311 + + + 312 + + + 313 + + + 314 + + + 315 + + + 316 + emergency scripting disablement + + + 317 + + + + + switch position when function triggered + + + 0 + indicates auxiliary switch is in the low position (pwm <1200) + + + 1 + indicates auxiliary switch is in the middle position (pwm >1200, <1800) + + + 2 + indicates auxiliary switch is in the high position (pwm >1800) + + + + + source of auxiliary function invocation + + + 0 + Source index is RC channel index + + + 1 + Source index is RC channel index + + + 2 + Source index is button index + + + 3 + Source index is MAVLink channel number + + + 4 + Source index is mission item index + + + 5 + Source index is not used (always 0) + + + + + index within source. 0 indexed. Invalid for scripting. + + + true if function was successful + + + + + Barometer dynamic data + + + Time since system startup + + + barometer sensor instance number + + + calculated dynamic pressure in the bodyframe X-axis + + + calculated dynamic pressure in the bodyframe Y-axis + + + calculated dynamic pressure in the bodyframe Z-axis + + + + + Gathered Barometer data + + + Time since system startup + + + barometer sensor instance number + + + calculated altitude + + + altitude AMSL + + + measured atmospheric pressure + + + measured atmospheric temperature + + + derived climb rate from primary barometer + + + time last sample was taken + + + raw adjustment of barometer altitude, zeroed on calibration, possibly set by GCS + + + temperature on ground, specified by parameter or measured while on ground + + + true if barometer is considered healthy + + + compensated atmospheric pressure + + + + + Gathered battery data + + + Time since system startup + + + battery instance number + + + measured voltage + + + estimated resting voltage + + + measured current + + + consumed Ah, current * time + + + consumed Wh, energy this battery has expended + + + measured temperature + + + estimated battery resistance + + + remaining percentage + + + health + + + state of health percentage. 0 if unknown + + + + + Battery cell voltage information + + + Time since system startup + + + battery instance number + + + battery voltage + + + first cell voltage + + + second cell voltage + + + third cell voltage + + + fourth cell voltage + + + fifth cell voltage + + + sixth cell voltage + + + seventh cell voltage + + + eighth cell voltage + + + ninth cell voltage + + + tenth cell voltage + + + eleventh cell voltage + + + twelfth cell voltage + + + + + Battery cell voltage information + + + Time since system startup + + + battery instance number + + + thirteenth cell voltage + + + fourteenth cell voltage + + + + + Beacon information + + + Time since system startup + + + True if beacon sensor is healthy + + + Number of beacons being used + + + Distance to first beacon + + + Distance to second beacon + + + Distance to third beacon + + + Distance to fourth beacon + + + Calculated beacon position, x-axis + + + Calculated beacon position, y-axis + + + Calculated beacon position, z-axis + + + + + CANFD Frame + + + Time since system startup + + + bus number + + + frame identifier + + + data length code + + + data 0 + + + data 1 + + + data 2 + + + data 3 + + + data 4 + + + data 5 + + + data 6 + + + data 7 + + + + + Camera shutter information + + + Time since system startup + + + Instance number + + + Image number + + + milliseconds since start of GPS week + + + weeks since 5 Jan 1980 + + + current latitude + + + current longitude + + + current altitude + + + current altitude relative to home + + + altitude as reported by GPS + + + current vehicle roll + + + current vehicle pitch + + + current vehicle yaw + + + + + Info from GetNodeInfo request + + + Time since system startup + + + Driver index + + + Node ID + + + Hardware ID, part 1 + + + Hardware ID, part 2 + + + Name string + + + major revision id + + + minor revision id + + + AP_Periph git hash + + + + + CAN Frame + + + Time since system startup + + + bus number + + + frame identifier + + + data length code + + + byte 0 + + + byte 1 + + + byte 2 + + + byte 3 + + + byte 4 + + + byte 5 + + + byte 6 + + + byte 7 + + + + + CAN Bus Statistics + + + Time since system startup + + + driver index + + + transmit success count + + + transmit request count + + + transmit reject count + + + transmit overflow count + + + transmit timeout count + + + transmit abort count + + + receive count + + + receive overflow count + + + receive error count + + + bus offset error count + + + ESC successful send count + + + Servo successful send count + + + ESC/Servo failed-to-send count + + + + + Custom Controller data + + + Time since system startup + + + controller type + + + 0 + + + 1 + + + 2 + + + + + true if controller is active + + + + + Uploaded mission command information + + + Time since system startup + + + Total number of mission commands + + + This command's offset in mission + + + Command type + + + Parameter 1 + + + Parameter 2 + + + Parameter 3 + + + Parameter 4 + + + Command latitude + + + Command longitude + + + Command altitude + + + Frame used for position + + + + + Servo feedback data + + + Time since system startup + + + Servo number this data relates to + + + Current servo position + + + Force being applied + + + Current servo movement speed + + + Amount of rated power being applied + + + commanded servo position + + + Voltage + + + Current + + + motor temperature + + + PCB temperature + + + error flags + + + + + Control Tuning information + + + Time since system startup + + + throttle input + + + angle boost + + + throttle output + + + calculated hover throttle + + + desired altitude + + + achieved altitude + + + barometric altitude + + + desired rangefinder altitude + + + achieved rangefinder altitude + + + terrain altitude + + + desired climb rate + + + climb rate + + + + + Generic 16-bit-signed-integer storage + + + Time since system startup + + + Data type identifier + + + Value + + + + + Generic 32-bit-signed-integer storage + + + Time since system startup + + + Data type identifier + + + Value + + + + + DCM Estimator Data + + + Time since system startup + + + estimated roll + + + estimated pitch + + + estimated yaw + + + lowest estimated gyro drift error + + + difference between measured yaw and DCM yaw estimate + + + wind velocity, to-the-North component + + + wind velocity, to-the-East component + + + wind velocity, Up-to-Down component + + + synthetic (equivalent) airspeed + + + + + Generic float storage + + + Time since system startup + + + Data type identifier + + + Value + + + + + DataFlash-Over-MAVLink statistics + + + Time since system startup + + + Current block number + + + Number of times we rejected a write to the backend + + + Number of blocks sent from the retry queue + + + Number of resends of unacknowledged data made + + + Average number of blocks on the free list + + + Minimum number of blocks on the free list + + + Maximum number of blocks on the free list + + + Average number of blocks on the pending list + + + Minimum number of blocks on the pending list + + + Maximum number of blocks on the pending list + + + Average number of blocks on the sent list + + + Minimum number of blocks on the sent list + + + Maximum number of blocks on the sent list + + + + + Onboard logging statistics + + + Time since system startup + + + Number of times we rejected a write to the backend + + + Current block number + + + Current write offset + + + Minimum free space in write buffer in last time period + + + Maximum free space in write buffer in last time period + + + Average free space in write buffer in last time period + + + + + Deepstall Landing data + + + Time since system startup + + + Deepstall landing stage + + + Target heading + + + Landing point latitude + + + Landing point longitude + + + Landing point altitude + + + Crosstrack error + + + Expected travel distance vehicle will travel from this point + + + L1 controller crosstrack integrator value + + + wind estimate loiter angle flown + + + Deepstall steering PID desired value + + + Deepstall steering PID Proportional response component + + + Deepstall steering PID Integral response component + + + Deepstall steering PID Derivative response component + + + + + Generic 16-bit-unsigned-integer storage + + + Time since system startup + + + Data type identifier + + + Value + + + + + Generic 32-bit-unsigned-integer storage + + + Time since system startup + + + Data type identifier + + + Value + + + + + External AHRS data + + + Time since system startup + + + euler roll + + + euler pitch + + + euler yaw + + + velocity north + + + velocity east + + + velocity down + + + latitude + + + longitude + + + altitude AMSL + + + nav status flags + + + + + External AHRS variances + + + Time since system startup + + + velocity variance + + + position variance + + + height variance + + + magnetic variance, X + + + magnetic variance, Y + + + magnetic variance, Z + + + true airspeed variance + + + + + EFI per-cylinder information + + + Time since system startup + + + Cylinder this data belongs to + + + Ignition timing + + + Injection time + + + Cylinder head temperature + + + Exhaust gas temperature + + + Estimated lambda coefficient (dimensionless ratio) + + + Cylinder2 head temperature + + + Cylinder2 Exhaust gas temperature + + + Index of the publishing ECU + + + + + Status received from ESCs via Extended DShot telemetry v2 + + + microseconds since system startup + + + ESC instance number + + + current stress level (commutation effort), scaled to [0..255] + + + maximum stress level (commutation effort) since arming, scaled to [0..15] + + + status bits + + + 1 + true if the message contains up-to-date stress data + + + 2 + true if the message contains up-to-date status data + + + 4 + true if the last status had the "alert" bit (e.g. demag) + + + 8 + true if the last status had the "warning" bit (e.g. desync) + + + 16 + true if the last status had the "error" bit (e.g. stall) + + + + + + + Electronic Fuel Injection system data + + + Time since system startup + + + Reported engine load + + + Reported engine RPM + + + Spark Dwell Time + + + Atmospheric pressure + + + Intake manifold pressure + + + Intake manifold temperature + + + Engine Coolant Temperature + + + Oil Pressure + + + Oil temperature + + + Fuel Pressure + + + Fuel Consumption Rate + + + Consumed fuel volume + + + Throttle Position + + + Index of the publishing ECU + + + + + Electronic Fuel Injection system data - redux + + + Time since system startup + + + True if EFI is healthy + + + Engine state + + + General error + + + Crankshaft sensor status + + + Temperature status + + + Fuel pressure status + + + Oil pressure status + + + Detonation status + + + Misfire status + + + Debris status + + + Spark plug usage + + + Index of the publishing ECU + + + + + Electronic Fuel Injection data - Hirth specific Status information + + + Time since system startup + + + Error Excess Temperature Bitfield + + + 1 + true if CHT1 is too low + + + 2 + true if CHT1 is too high + + + 4 + true if CHT1 Enrichment is active + + + 8 + true if CHT2 is too low + + + 16 + true if CHT2 is too high + + + 32 + true if CHT2 Enrichment is active + + + 64 + true if EGT1 is too low + + + 128 + true if EGT1 is too high + + + 256 + true if EGT1 Enrichment is active + + + 512 + true if EGT2 is too low + + + 1024 + true if EGT2 is too high + + + 2048 + true if EGT2 Enrichment is active + + + + + Sensor Status Bitfield + + + 2 + true if engine temperature sensor is OK + + + 4 + true if air temperature sensor is OK + + + 8 + true if intake air pressure sensor is OK + + + 16 + true if throttle sensor is OK + + + + + CRC failure count + + + ACK failure count + + + Uptime between 2 messages + + + Throttle output as received by the engine + + + Modified throttle_to_hirth output sent to the engine + + + + + Specifically coded error messages + + + Time since system startup + + + Subsystem in which the error occurred + + + 1 + + + 2 + + + 3 + + + 4 + not used + + + 5 + + + 6 + + + 7 + not used + + + 8 + + + 9 + + + 10 + + + 11 + + + 12 + + + 13 + + + 14 + not used + + + 15 + + + 16 + + + 17 + + + 18 + + + 19 + + + 20 + + + 21 + + + 22 + + + 23 + + + 24 + + + 25 + + + 26 + + + 27 + + + 28 + + + 29 + + + 30 + + + 31 + + + + + Subsystem-specific error code + + + + + Feedback received from ESCs + + + microseconds since system startup + + + ESC instance number + + + reported motor rotation rate + + + reported motor rotation rate without slew adjustment + + + Perceived input voltage for the ESC + + + Perceived current through the ESC + + + ESC temperature in centi-degrees C + + + current consumed total mAh + + + measured motor temperature in centi-degrees C + + + error rate + + + + + ESC extended telemetry data + + + Time since system startup + + + starts from 0 + + + input duty cycle in percent + + + output duty cycle in percent + + + manufacturer-specific status flags + + + Power percentage + + + + + Specifically coded event messages + + + Time since system startup + + + Event identifier + + + 10 + + + 11 + + + 15 + + + 17 + + + 18 + + + 19 + + + 21 + + + 22 + + + 25 + + + 26 + + + 27 + + + 28 + + + 29 + + + 30 + + + 31 + + + 32 + + + 33 + + + 34 + + + 35 + + + 36 + + + 37 + + + 38 + + + 39 + + + 41 + + + 42 + + + 43 + + + 44 + + + 45 + + + 46 + + + 47 + + + 49 + + + 50 + + + 51 + + + 52 + + + 53 + + + 54 + + + 55 + + + 56 + + + 57 + + + 58 + Heli only + + + 59 + Heli only + + + 60 + + + 61 + + + 62 + + + 63 + + + 64 + + + 65 + + + 66 + + + 67 + + + 71 + + + 72 + + + 73 + + + 74 + + + 75 + + + 76 + + + 77 + + + 78 + + + 79 + + + 80 + + + 81 + + + 82 + + + 83 + + + 85 + + + 86 + + + 87 + + + 90 + + + 163 + + + 164 + + + 165 + + + 166 + + + + + + + Filter Center Message - per motor + + + microseconds since system startup + + + instance + + + total number of active harmonic notches + + + First harmonic centre frequency for motor 1 + + + First harmonic centre frequency for motor 2 + + + First harmonic centre frequency for motor 3 + + + First harmonic centre frequency for motor 4 + + + First harmonic centre frequency for motor 5 + + + First harmonic centre frequency for motor 6 + + + Second harmonic centre frequency for motor 1 + + + Second harmonic centre frequency for motor 2 + + + Second harmonic centre frequency for motor 3 + + + Second harmonic centre frequency for motor 4 + + + Second harmonic centre frequency for motor 5 + + + Second harmonic centre frequency for motor 6 + + + + + Filter Center Message + + + microseconds since system startup + + + instance + + + notch centre frequency + + + 2nd harmonic frequency + + + + + Fence status - development diagnostic message + + + Time since system startup + + + bitmask of enabled fences + + + bitmask of automatically enabled fences + + + bitmask of configured-in-parameters fences + + + bitmask of enabled fences + + + bitmask of currently disabled fences + + + current vehicle altitude + + + + + https://ardupilot.org/copter/docs/flowhold-mode.html + FlowHold mode messages + + + Time since system startup + + + Filtered flow rate, X-Axis + + + Filtered flow rate, Y-Axis + + + Target lean angle, X-Axis + + + Target lean angle, Y-Axis + + + Flow sensor quality. If this value falls below FHLD_QUAL_MIN parameter, FlowHold will act just like AltHold. + + + Integral part of PI controller, X-Axis + + + Integral part of PI controller, Y-Axis + + + + + Height estimation using optical flow sensor + + + Time since system startup + + + Delta flow rate, X-Axis + + + Delta flow rate, Y-Axis + + + Integrated delta velocity rate, X-Axis + + + Integrated delta velocity rate, Y-Axis + + + Estimated Height + + + Delta Height + + + Height offset + + + Height estimate from inertial navigation library + + + Last used INS height in optical flow sensor height estimation calculations + + + Time between optical flow sensor updates. This should be less than 500ms for performing the height estimation calculations + + + + + File data + + + File name + + + Offset into the file of this block + + + Length of this data block + + + File data of this block + + + + + https://ardupilot.org/dev/docs/code-overview-adding-a-new-log-message.html + Message defining the format of messages in this file + + + unique-to-this-log identifier for message being defined + + + the number of bytes taken up by this message (including all headers) + + + name of the message being defined + + + character string defining the C-storage-type of the fields in this message + + + the labels of the message being defined + + + + + Message defining units and multipliers used for fields of other messages + + + Time since system startup + + + numeric reference to associated FMT message + + + each character refers to a UNIT message. The unit at an offset corresponds to the field at the same offset in FMT.Format + + + each character refers to a MULT message. The multiplier at an offset corresponds to the field at the same offset in FMT.Format + + + + + currently loaded Geo Fence points + + + Time since system startup + + + total number of stored items + + + index in current sequence + + + point type + + + point latitude + + + point longitude + + + vertex cound in polygon if applicable + + + radius of circle if applicable + + + + + Follow library diagnostic data + + + Time since system startup (microseconds) + + + Target latitude (degrees * 1E7) + + + Target longitude (degrees * 1E7) + + + Target absolute altitude (centimeters) + + + Target velocity, North (m/s) + + + Target velocity, East (m/s) + + + Target velocity, Down (m/s) + + + Vehicle estimated latitude (degrees * 1E7) + + + Vehicle estimated longitude (degrees * 1E7) + + + Vehicle estimated altitude (centimeters) + + + Vehicle estimated altitude Frame + + + + + Filter Tuning Message - per motor + + + microseconds since system startup + + + instance + + + number of active harmonic notches + + + desired harmonic notch centre frequency for motor 1 + + + desired harmonic notch centre frequency for motor 2 + + + desired harmonic notch centre frequency for motor 3 + + + desired harmonic notch centre frequency for motor 4 + + + desired harmonic notch centre frequency for motor 5 + + + desired harmonic notch centre frequency for motor 6 + + + desired harmonic notch centre frequency for motor 7 + + + desired harmonic notch centre frequency for motor 8 + + + desired harmonic notch centre frequency for motor 9 + + + desired harmonic notch centre frequency for motor 10 + + + desired harmonic notch centre frequency for motor 11 + + + desired harmonic notch centre frequency for motor 12 + + + + + FFT Filter Tuning + + + microseconds since system startup + + + peak noise frequency as an energy-weighted average of roll and pitch peak frequencies + + + bandwidth of weighted peak frequency where edges are determined by FFT_ATT_REF + + + signal-to-noise ratio on the roll axis + + + signal-to-noise ratio on the pitch axis + + + signal-to-noise ratio on the yaw axis + + + harmonic fit on roll of the highest noise peak to the second highest noise peak + + + harmonic fit on pitch of the highest noise peak to the second highest noise peak + + + harmonic fit on yaw of the highest noise peak to the second highest noise peak + + + FFT health, X-axis + + + FFT health, Y-axis + + + FFT health, Z-axis + + + FFT cycle time + + + + + FFT Noise Frequency Peak + + + microseconds since system startup + + + peak id where 0 is the centre peak, 1 is the lower shoulder and 2 is the upper shoulder + + + noise frequency of the peak on roll + + + noise frequency of the peak on pitch + + + noise frequency of the peak on yaw + + + bandwidth of the peak frequency on roll where edges are determined by FFT_ATT_REF + + + bandwidth of the peak frequency on pitch where edges are determined by FFT_ATT_REF + + + bandwidth of the peak frequency on yaw where edges are determined by FFT_ATT_REF + + + signal-to-noise ratio on the roll axis + + + signal-to-noise ratio on the pitch axis + + + signal-to-noise ratio on the yaw axis + + + power spectral density bin energy of the peak on roll + + + power spectral density bin energy of the peak on roll + + + power spectral density bin energy of the peak on roll + + + + + Additional FFT Noise Frequency Peak + + + microseconds since system startup + + + update axis + + + Peak 1 frequency + + + Peak 2 frequency + + + Peak 3 Frequency + + + Peak 1 noise bandwidth + + + Peak 2 noise bandwidth + + + Peak 3 noise bandwidth + + + Peak 1 Maximum energy + + + Peak 2 Maximum energy + + + Peak 3 Maximum energy + + + + + Filter Tuning Message + + + microseconds since system startup + + + instance + + + desired harmonic notch centre frequency + + + + + Simulated Glider Angles and coefficients + + + Time since system startup + + + alpha angle + + + beta angle + + + lift coefficent + + + roll coffecient + + + yaw coefficient + + + + + Solo Gimbal measurements + + + Time since system startup + + + sum of time across measurements in this packet + + + delta-angle sum, x-axis + + + delta-angle sum, y-axis + + + delta-angle sum, z-axis + + + delta-velocity sum, x-axis + + + delta-velocity sum, y-axis + + + delta-velocity sum, z-axis + + + joint angle, x + + + joint angle, y + + + joint angle, z + + + + + Solo Gimbal estimation and demands + + + Time since system startup + + + Solo Gimbal EKF status bits + + + Solo Gimbal EKF estimate of gimbal angle, x-axis + + + Solo Gimbal EKF estimate of gimbal angle, y-axis + + + Solo Gimbal EKF estimate of gimbal angle, y-axis + + + Angular velocity demand around x-axis + + + Angular velocity demand around y-axis + + + Angular velocity demand around z-axis + + + Angular position target around x-axis + + + Angular position target around y-axis + + + Angular position target around z-axis + + + + + GPS accuracy information + + + Time since system startup + + + GPS instance number + + + vertical dilution of precision + + + horizontal position accuracy + + + vertical position accuracy + + + speed accuracy + + + yaw accuracy + + + true if vertical velocity is available + + + time since system startup this sample was taken + + + system time delta between the last two reported positions + + + altitude above WGS-84 ellipsoid; INT32_MIN (-2147483648) if unknown + + + RTCM fragments used + + + RTCM fragments discarded + + + + + Information received from GNSS systems attached to the autopilot + + + Time since system startup + + + GPS instance number + + + GPS Fix type; 2D fix, 3D fix etc. + + + 0 + No GPS connected/detected + + + 1 + Receiving valid GPS messages but no lock + + + 2 + Receiving valid messages and 2D lock + + + 3 + Receiving valid messages and 3D lock + + + 4 + Receiving valid messages and 3D lock with differential improvements + + + 5 + Receiving valid messages and 3D RTK Float + + + 6 + Receiving valid messages and 3D RTK Fixed + + + + + milliseconds since start of GPS Week + + + weeks since 5 Jan 1980 + + + number of satellites visible + + + horizontal dilution of precision + + + latitude + + + longitude + + + altitude + + + ground speed + + + ground course + + + vertical speed + + + vehicle yaw + + + boolean value indicating whether this GPS is in use + + + + + GPS Yaw + + + Time since system startup + + + instance + + + reported heading,deg + + + antenna separation,m + + + vertical antenna separation,m + + + minimum tolerable vertical antenna separation,m + + + maximum tolerable vertical antenna separation,m + + + 1 if have yaw + + + + + Raw uBlox data + + + Time since system startup + + + receiver TimeOfWeek measurement + + + GPS week + + + number of space vehicles seen + + + space vehicle number of first vehicle + + + carrier phase measurement + + + pseudorange measurement + + + Doppler measurement + + + measurement quality index + + + carrier-to-noise density ratio + + + loss of lock indicator + + + + + Raw uBlox data - header + + + Time since system startup + + + receiver TimeOfWeek measurement + + + GPS week + + + GPS leap seconds + + + number of space-vehicle measurements to follow + + + receiver tracking status bitfield + + + + + Raw uBlox data - space-vehicle data + + + Time since system startup + + + Pseudorange measurement + + + Carrier phase measurement + + + Doppler measurement + + + GNSS identifier + + + Satellite identifier + + + GLONASS frequency slot + + + carrier phase locktime counter + + + carrier-to-noise density ratio + + + estimated pseudorange measurement standard deviation + + + estimated carrier phase measurement standard deviation + + + estimated Doppler measurement standard deviation + + + tracking status bitfield + + + + + Guided mode attitude target information + + + Time since system startup + + + Type of guided mode + + + Target attitude, Roll + + + Target attitude, Pitch + + + Target attitude, Yaw + + + Roll rate + + + Pitch rate + + + Yaw rate + + + Thrust + + + Climb rate + + + + + Guided mode position target information + + + Time since system startup + + + Type of guided mode + + + Target position, X-Axis + + + Target position, Y-Axis + + + Target position, Z-Axis + + + Target position, Z-Axis is alt above terrain + + + Target velocity, X-Axis + + + Target velocity, Y-Axis + + + Target velocity, Z-Axis + + + Target acceleration, X-Axis + + + Target acceleration, Y-Axis + + + Target acceleration, Z-Axis + + + + + IMU gyroscope data + + + Time since system startup + + + gyroscope sensor instance number + + + time since system startup this sample was taken + + + measured rotation rate about X axis + + + measured rotation rate about Y axis + + + measured rotation rate about Z axis + + + + + IMU Heater data + + + Time since system startup + + + Current IMU temperature + + + Target IMU temperature + + + Proportional portion of response + + + Integral portion of response + + + Controller output to heating element + + + + + Helicopter related messages + + + Time since system startup + + + Instance, 0=Main, 1=Tail + + + Desired rotor speed + + + Estimated rotor speed + + + Governor Output + + + Throttle output + + + throttle ramp up + + + RSC state + + + + + Hygrometer data + + + Time since system startup + + + sensor ID + + + percentage humidity + + + temperature in degrees C + + + + + ICM20789 diagnostics + + + Time since system startup + + + raw temperature from sensor + + + raw pressure from sensor + + + pressure + + + temperature + + + + + https://ardupilot.org/copter/docs/common-ie24-fuelcell.html + Intelligent Energy Fuel Cell generator (legacy protocol) + + + Time since system startup + + + Fuel remaining + + + stack power module power draw + + + output power + + + error codes + + + 1 + Minor internal error is to be ignored + + + 10 + + + 11 + + + 20 + + + 21 + + + 30 + + + 31 + + + 32 + + + 33 + + + 40 + + + + + + + https://ardupilot.org/copter/docs/common-ie24-fuelcell.html + Intelligent Energy Fuel Cell generator + + + Time since system startup + + + Fuel remaining + + + Inlet pressure + + + battery voltage + + + output power + + + stack power module power draw + + + fault number + + + battery power draw + + + generator state + + + 0 + + + 1 + + + 2 + + + 3 + + + 4 + + + + + error code + + + 1 + Minor internal error is to be ignored + + + 10 + + + 11 + + + 20 + + + 21 + + + 30 + + + 31 + + + 32 + + + 33 + + + 40 + + + + + sub-error code + + + + + InertialLabs AHRS data1 + + + Time since system startup + + + GPS INS time (round) + + + Gyro X + + + Gyro Y + + + Gyro z + + + Accelerometer X + + + Accelerometer Y + + + Accelerometer Z + + + + + InertialLabs AHRS data2 + + + Time since system startup + + + GPS INS time (round) + + + Magnetometer X + + + Magnetometer Y + + + Magnetometer Z + + + + + InertialLabs AHRS data3 + + + Time since system startup + + + GPS INS time (round) + + + Static pressure + + + Differential pressure + + + Temperature + + + Baro altitude + + + true airspeed + + + Wind velocity north + + + Wind velocity east + + + Wind velocity down + + + Air Data Unit status + + + + + InertialLabs AHRS data4 + + + Time since system startup + + + GNSS Position timestamp + + + GPS Week + + + Number of satellites + + + Indicator of new update of GPS data + + + GNSS Latitude + + + GNSS Longitude + + + GNSS Altitude + + + GNSS Track over ground + + + GNSS Horizontal speed + + + GNSS Vertical speed + + + + + InertialLabs AHRS data5 + + + Time since system startup + + + GNSS Position timestamp + + + fix type + + + GNSS spoofing status + + + GNSS jamming status + + + GNSS Info1 + + + GNSS Info2 + + + GNSS Angles position type + + + + + InertialLabs AHRS data6 + + + Time since system startup + + + GNSS Position timestamp + + + GNSS Heading timestamp + + + GNSS Heading + + + GNSS Pitch + + + GNSS GDOP + + + GNSS PDOP + + + GNSS HDOP + + + GNSS VDOP + + + GNSS TDOP + + + + + InertialLabs AHRS data7 + + + Time since system startup + + + GPS INS time (round) + + + euler roll + + + euler pitch + + + euler yaw + + + velocity north + + + velocity east + + + velocity down + + + latitude + + + longitude + + + altitude MSL + + + USW1 + + + USW2 + + + Supply voltage + + + + + InertialLabs AHRS data8 + + + Time since system startup + + + GPS INS time (round) + + + position variance north + + + position variance east + + + position variance down + + + velocity variance north + + + velocity variance east + + + velocity variance down + + + + + Inertial Measurement Unit data + + + Time since system startup + + + IMU sensor instance number + + + measured rotation rate about X axis + + + measured rotation rate about Y axis + + + measured rotation rate about Z axis + + + acceleration along X axis + + + acceleration along Y axis + + + acceleration along Z axis + + + gyroscope error count + + + accelerometer error count + + + IMU temperature + + + gyroscope health + + + accelerometer health + + + gyroscope measurement rate + + + accelerometer measurement rate + + + + + IOMCU diagnostic information + + + Time since system startup + + + Status Read error count (zeroed on successful read) + + + Free memory + + + IOMCU uptime + + + Number of packets received by IOMCU + + + Protocol failures on MCU side + + + Reported number of failures on IOMCU side + + + Number of delayed packets received by MCU + + + + + IMU Register unexpected value change + + + Time since system startup + + + bus ID + + + device register bank + + + device register + + + unexpected value + + + + + InertialSensor Batch Logging Data + + + Time since system startup + + + batch sequence number + + + sample sequence number + + + x-axis sample value + + + y-axis sample value + + + z-axis sample value + + + + + InertialSensor Batch Logging Header + + + Time since system startup + + + batch sequence number + + + indicates if this is accel or gyro data + + + IMU sensor instance + + + multiplier to be applied to samples in this batch + + + samples in this batch + + + timestamp of first sample + + + rate at which samples have been collected + + + + + Log data received from JSON simulator + + + Time since system startup (us) + + + Simulation's timestamp (s) + + + Simulation's roll (rad) + + + Simulation's pitch (rad) + + + Simulation's yaw (rad) + + + Simulated gyroscope, X-axis (rad/sec) + + + Simulated gyroscope, Y-axis (rad/sec) + + + Simulated gyroscope, Z-axis (rad/sec) + + + + + Log data received from JSON simulator + + + Time since system startup (us) + + + simulation's velocity, North-axis (m/s) + + + simulation's velocity, East-axis (m/s) + + + simulation's velocity, Down-axis (m/s) + + + simulation's acceleration, X-axis (m/s^2) + + + simulation's acceleration, Y-axis (m/s^2) + + + simulation's acceleration, Z-axis (m/s^2) + + + simulation's acceleration, North (m/s^2) + + + simulation's acceleration, East (m/s^2) + + + simulation's acceleration, Down (m/s^2) + + + + + Slope Landing data + + + Time since system startup + + + progress through landing sequence + + + Landing flags + + + Slope-specific landing flags + + + Slope to landing point + + + Initial slope to landing point + + + Rangefinder correction + + + Height for flare timing. + + + + + Land Detector State + + + Time since system startup + + + boolean state flags + + + 1 + + + 2 + + + 4 + + + 8 + + + 16 + + + 32 + + + 64 + + + 128 + + + 256 + + + 256 + + + 512 + + + 1024 + + + + + landing_detector pass count + + + + + Landing gear information + + + Time since system startup + + + Current landing gear state + + + -1 + + + 0 + + + 1 + + + 2 + + + 3 + + + + + Weight on wheels state + + + -1 + + + 0 + + + 1 + + + + + + + Gathered Loweheiser EFI/Governor telemetry + + + Time since system startup + + + target system ID + + + target component ID + + + command + + + efi index + + + desired engine state (0:EFI off 1:EFI on) + + + desired governor state (0:Governor off 1:Governor on) + + + manual throttle value + + + desired electric start + + + + + Gathered Loweheiser EFI/Governor telemetry + + + Time since system startup + + + EFI/Gov sensor instance number + + + battery voltage + + + battery current + + + generator current + + + throttle input + + + EFI battery voltage + + + generator RPM + + + EFI pulse-width + + + fuel flow + + + fuel consumed + + + EFI pressure + + + EFI manifold air temperature + + + cylinder head temperature + + + throttle position sensor + + + + + Information received from compasses + + + Time since system startup + + + magnetometer sensor instance number + + + magnetic field strength in body frame + + + magnetic field strength in body frame + + + magnetic field strength in body frame + + + magnetic field offset in body frame + + + magnetic field offset in body frame + + + magnetic field offset in body frame + + + motor interference magnetic field offset in body frame + + + motor interference magnetic field offset in body frame + + + motor interference magnetic field offset in body frame + + + true if the compass is considered healthy + + + time measurement was taken + + + + + Magnetometer high resolution data + + + Time since system startup + + + CAN node + + + sensor ID on node + + + CAN bus + + + X axis field + + + y axis field + + + z axis field + + + + + GCS MAVLink link statistics + + + Time since system startup + + + mavlink channel number + + + transmitted packet count + + + received packet count + + + perceived number of packets we never received + + + compact representation of some state of the channel + + + 1 + + + 2 + + + 4 + + + 8 + + + 16 + + + + + stream slowdown is the number of ms being added to each message to fit within bandwidth + + + times buffer was full when a message was going to be sent + + + time MAV_GCS_SYSID heartbeat (or manual control) last seen + + + + + MAVLink command we have just executed + + + Time since system startup + + + target system for command + + + target component for command + + + source system for command + + + source component for command + + + command frame + + + mavlink command enum value + + + first parameter from mavlink packet + + + second parameter from mavlink packet + + + third parameter from mavlink packet + + + fourth parameter from mavlink packet + + + X coordinate from mavlink packet + + + Y coordinate from mavlink packet + + + Z coordinate from mavlink packet + + + command result being returned from autopilot + + + true if this command arrived via a COMMAND_LONG rather than COMMAND_INT + + + + + MCU voltage and temprature monitering + + + Time since system startup + + + Temperature + + + Voltage + + + Voltage min + + + Voltage max + + + + + Executed mission command information; emitted when we start to run an item + + + Time since system startup + + + Total number of mission commands + + + This command's offset in mission + + + Command type + + + Parameter 1 + + + Parameter 2 + + + Parameter 3 + + + Parameter 4 + + + Command latitude + + + Command longitude + + + Command altitude + + + Frame used for position + + + + + MMC3416 compass data + + + Time since system startup + + + new measurement X axis + + + new measurement Y axis + + + new measurement Z axis + + + new offset X axis + + + new offset Y axis + + + new offset Z axis + + + + + Mount's desired and actual roll, pitch and yaw angles + + + Time since system startup + + + Instance number + + + Mount mode + + + Desired roll + + + Actual roll + + + Desired pitch + + + Actual pitch + + + Desired yaw in body frame + + + Actual yaw in body frame + + + Desired yaw in earth frame + + + Actual yaw in earth frame + + + Rangefinder distance + + + + + vehicle control mode information + + + Time since system startup + + + vehicle-specific mode number + + + alias for Mode + + + reason for entering this mode; enumeration value + + + 0 + + + 1 + + + 2 + + + 3 + + + 4 + + + 5 + + + 6 + + + 7 + + + 8 + + + 9 + + + 10 + + + 11 + + + 12 + + + 13 + + + 14 + + + 15 + + + 16 + + + 17 + + + 18 + + + 19 + + + 20 + + + 21 + + + 22 + + + 23 + + + 24 + + + 25 + general failsafes, prefer specific failsafes over this as much as possible + + + 26 + + + 27 + + + 28 + + + 29 + + + 30 + + + 31 + + + 32 + + + 33 + + + 34 + + + 35 + + + 36 + + + 37 + + + 38 + + + 39 + + + 40 + + + 41 + + + 42 + + + 43 + + + 44 + + + 45 + + + 46 + + + 47 + + + 48 + + + 49 + + + 50 + + + 51 + + + 52 + + + 53 + + + 54 + + + 55 + + + + + + + Main loop performance monitoring message. + + + Time since system startup + + + Loop delay so far + + + Current task + + + Internal error mask + + + Count of internal error occurances + + + Internal Error line + + + MAVLink message currently being processed + + + MAVLink command currently being processed + + + If semaphore taken, line of semaphore take call + + + count of SPI transactions + + + count of i2c transactions + + + + + Motor mixer information + + + Time since system startup + + + Maximum motor compensation gain + + + Ratio between detected battery voltage and maximum battery voltage + + + Throttle limit set due to battery current limitations + + + Maximum average throttle that can be used to maintain attitude control, derived from throttle mix params + + + Throttle output + + + bit 0 motor failed, bit 1 motors balanced, should be 2 in normal flight + + + + + Textual messages + + + Time since system startup + + + identifier for chunks making up a message + + + chunk sequence number within message identified by ID + + + message text + + + + + Message mapping from single character to numeric multiplier + + + Time since system startup + + + character referenced by FMTU + + + numeric multiplier + + + + + EKF2 beacon sensor diagnostics + + + Time since system startup + + + EKF2 core this data is for + + + Beacon sensor ID + + + Beacon range + + + Beacon range innovation + + + sqrt of beacon range innovation variance + + + Beacon range innovation consistency test ratio + + + Beacon north position + + + Beacon east position + + + Beacon down position + + + High estimate of vertical position offset of beacons rel to EKF origin + + + Low estimate of vertical position offset of beacons rel to EKF origin + + + always zero + + + always zero + + + always zero + + + + + EKF2 estimator outputs + + + Time since system startup + + + EKF2 core this data is for + + + Estimated roll + + + Estimated pitch + + + Estimated yaw + + + Estimated velocity (North component) + + + Estimated velocity (East component) + + + Estimated velocity (Down component) + + + Filtered derivative of vertical position (down) + + + Estimated distance from origin (North component) + + + Estimated distance from origin (East component) + + + Estimated distance from origin (Down component) + + + Estimated gyro bias, X axis + + + Estimated gyro bias, Y axis + + + Estimated gyro bias, Z axis + + + Height of origin above WGS-84 + + + + + EKF2 estimator secondary outputs + + + Time since system startup + + + EKF2 core this data is for + + + Estimated accelerometer Z bias + + + Gyro Scale Factor (X-axis) + + + Gyro Scale Factor (Y-axis) + + + Gyro Scale Factor (Z-axis) + + + Estimated wind velocity (moving-to-North component) + + + Estimated wind velocity (moving-to-East component) + + + Magnetic field strength (North component) + + + Magnetic field strength (East component) + + + Magnetic field strength (Down component) + + + Magnetic field strength (body X-axis) + + + Magnetic field strength (body Y-axis) + + + Magnetic field strength (body Z-axis) + + + Magnetometer used for data + + + + + EKF2 innovations + + + Time since system startup + + + EKF2 core this data is for + + + Innovation in velocity (North component) + + + Innovation in velocity (East component) + + + Innovation in velocity (Down component) + + + Innovation in position (North component) + + + Innovation in position (East component) + + + Innovation in position (Down component) + + + Innovation in magnetic field strength (X-axis component) + + + Innovation in magnetic field strength (Y-axis component) + + + Innovation in magnetic field strength (Z-axis component) + + + Innovation in vehicle yaw + + + Innovation in true-airspeed + + + Accumulated relative error of this core with respect to active primary core + + + A consolidated error score where higher numbers are less healthy + + + + + EKF2 variances SV, SP, SH and SM are probably best described as 'Squared Innovation Test Ratios' where values <1 tells us the measurement was accepted and >1 tells us it was rejected. They represent the square of the (innovation / maximum allowed innovation) where the innovation is the difference between predicted and measured value and the maximum allowed innovation is determined from the uncertainty of the measurement, uncertainty of the prediction and scaled using the number of standard deviations set by the innovation gate parameter for that measurement, eg EK2_MAG_I_GATE, EK2_HGT_I_GATE, etc + + + Time since system startup + + + EKF2 core this data is for + + + Square root of the velocity variance + + + Square root of the position variance + + + Square root of the height variance + + + Magnetic field variance + + + tilt error convergence metric + + + Filtered error in roll/pitch estimate + + + Most recent position reset (North component) + + + Most recent position reset (East component) + + + Filter fault status + + + Filter timeout status bitmask (0:position measurement, 1:velocity measurement, 2:height measurement, 3:magnetometer measurement, 4:airspeed measurement) + + + Filter solution status + + + 1 + attitude estimate valid + + + 2 + horizontal velocity estimate valid + + + 4 + vertical velocity estimate valid + + + 8 + relative horizontal position estimate valid + + + 16 + absolute horizontal position estimate valid + + + 32 + vertical position estimate valid + + + 64 + terrain height estimate valid + + + 128 + in constant position mode + + + 256 + expected good relative horizontal position estimate - used before takeoff + + + 512 + expected good absolute horizontal position estimate - used before takeoff + + + 1024 + optical flow takeoff has been detected + + + 2048 + compensating for baro errors during takeoff + + + 4096 + compensating for baro errors during touchdown + + + 8192 + using GPS position + + + 16384 + GPS glitching is affecting navigation accuracy + + + 32768 + can use GPS for navigation + + + 65536 + has ever been healthy + + + 131072 + rejecting airspeed data + + + 262144 + dead reckoning (e.g. no position or velocity source) + + + + + Filter GPS status + + + Primary core index + + + + + EKF2 Sensor innovations (primary core) and general dumping ground + + + Time since system startup + + + EKF2 core this data is for + + + Normalised flow variance + + + Optical flow LOS rate vector innovations from the main nav filter (X-axis) + + + Optical flow LOS rate vector innovations from the main nav filter (Y-axis) + + + Optical flow LOS rate innovation from terrain offset estimator + + + Height above ground level + + + Estimated vertical position of the terrain relative to the nav filter zero datum + + + Range finder innovations + + + Measured range + + + Filter ground offset state error + + + Magnitude of angular error + + + Magnitude of velocity error + + + Magnitude of position error + + + + + EKF2 quaternion defining the rotation from NED to XYZ (autopilot) axes + + + Time since system startup + + + EKF2 core this data is for + + + Quaternion a term + + + Quaternion b term + + + Quaternion c term + + + Quaternion d term + + + + + EKF2 timing information + + + Time since system startup + + + EKF core this message instance applies to + + + count of samples used to create this message + + + smallest IMU sample interval + + + largest IMU sample interval + + + low-passed achieved average time step rate for the EKF (minimum) + + + low-passed achieved average time step rate for the EKF (maximum) + + + accumulated measurement time interval for the delta angle (minimum) + + + accumulated measurement time interval for the delta angle (maximum) + + + accumulated measurement time interval for the delta velocity (minimum) + + + accumulated measurement time interval for the delta velocity (maximum) + + + + + EKF Yaw Estimator States + + + Time since system startup + + + EKF core this data is for + + + GSF yaw estimate (deg) + + + GSF yaw estimate 1-Sigma uncertainty (deg) + + + Yaw estimate from individual EKF filter 0 (deg) + + + Yaw estimate from individual EKF filter 1 (deg) + + + Yaw estimate from individual EKF filter 2 (deg) + + + Yaw estimate from individual EKF filter 3 (deg) + + + Yaw estimate from individual EKF filter 4 (deg) + + + Weighting applied to yaw estimate from individual EKF filter 0 + + + Weighting applied to yaw estimate from individual EKF filter 1 + + + Weighting applied to yaw estimate from individual EKF filter 2 + + + Weighting applied to yaw estimate from individual EKF filter 3 + + + Weighting applied to yaw estimate from individual EKF filter 4 + + + + + EKF Yaw Estimator Innovations + + + Time since system startup + + + EKF core this data is for + + + North velocity innovation from individual EKF filter 0 (m/s) + + + North velocity innovation from individual EKF filter 1 (m/s) + + + North velocity innovation from individual EKF filter 2 (m/s) + + + North velocity innovation from individual EKF filter 3 (m/s) + + + North velocity innovation from individual EKF filter 4 (m/s) + + + East velocity innovation from individual EKF filter 0 (m/s) + + + East velocity innovation from individual EKF filter 1 (m/s) + + + East velocity innovation from individual EKF filter 2 (m/s) + + + East velocity innovation from individual EKF filter 3 (m/s) + + + East velocity innovation from individual EKF filter 4 (m/s) + + + + + Named Value Float messages; messages sent to GCS via NAMED_VALUE_FLOAT + + + Time since system startup + + + Name of float + + + Value of float + + + + + Named Value String messages; messages sent to GCS via NAMED_VALUE_STRING + + + Time since system startup + + + Name of string + + + Value of string + + + + + Object avoidance (Bendy Ruler) diagnostics + + + Time since system startup + + + Type of BendyRuler currently active + + + True if Bendy Ruler avoidance is being used + + + Best yaw chosen to avoid obstacle + + + Current vehicle yaw + + + Desired pitch chosen to avoid obstacle + + + True if BendyRuler resisted changing bearing and continued in last calculated bearing + + + Margin from path to obstacle on best yaw chosen + + + Destination latitude + + + Destination longitude + + + Desired alt above EKF Origin + + + Intermediate location chosen for avoidance + + + Intermediate location chosen for avoidance + + + Intermediate alt chosen for avoidance above EKF origin + + + + + Object avoidance (Dijkstra) diagnostics + + + Time since system startup + + + Dijkstra avoidance library state + + + Dijkstra library error condition + + + Destination point in calculated path to destination + + + Number of points in path to destination + + + Destination latitude + + + Destination longitude + + + Object Avoidance chosen destination point latitude + + + Object Avoidance chosen destination point longitude + + + + + Object avoidance path planning visgraph points + + + Time since system startup + + + Visgraph version, increments each time the visgraph is re-generated + + + point number in visgraph + + + Latitude + + + longitude + + + + + Optical flow sensor data + + + Time since system startup + + + Estimated sensor data quality + + + Sensor flow rate, X-axis + + + Sensor flow rate,Y-axis + + + derived rotational velocity, X-axis + + + derived rotational velocity, Y-axis + + + + + Optical Flow Calibration sample + + + Time since system startup + + + Axis (X=0 Y=1) + + + Sample number + + + Flow rate + + + Body rate + + + Los pred + + + + + Vehicle navigation origin or other notable position + + + Time since system startup + + + Position type + + + 0 + + + 1 + + + + + Position latitude + + + Position longitude + + + Position altitude + + + + + parameter value + + + Time since system startup + + + parameter name + + + parameter value + + + default parameter value for this board and config + + + + + Proportional/Integral/Derivative gain values for vertical acceleration + + + Time since system startup + + + desired value + + + achieved value + + + error between target and achieved + + + proportional part of PID + + + integral part of PID + + + derivative part of PID + + + controller feed-forward portion of response + + + controller derivative feed-forward portion of response + + + scaler applied to D gain to reduce limit cycling + + + slew rate used in slew limiter + + + bitmask of PID state flags + + + 1 + true if the output is saturated, I term anti windup is active + + + 2 + true if the PD sum limit is active + + + 4 + true if the controller was reset + + + 8 + true if the I term has been set externally including reseting to 0 + + + + + + + Proportional/Integral/Derivative gain values for East/West velocity + + + Time since system startup + + + desired value + + + achieved value + + + error between target and achieved + + + proportional part of PID + + + integral part of PID + + + derivative part of PID + + + controller feed-forward portion of response + + + controller derivative feed-forward portion of response + + + scaler applied to D gain to reduce limit cycling + + + slew rate used in slew limiter + + + bitmask of PID state flags + + + 1 + true if the output is saturated, I term anti windup is active + + + 2 + true if the PD sum limit is active + + + 4 + true if the controller was reset + + + 8 + true if the I term has been set externally including reseting to 0 + + + + + + + Proportional/Integral/Derivative gain values for North/South velocity + + + Time since system startup + + + desired value + + + achieved value + + + error between target and achieved + + + proportional part of PID + + + integral part of PID + + + derivative part of PID + + + controller feed-forward portion of response + + + controller derivative feed-forward portion of response + + + scaler applied to D gain to reduce limit cycling + + + slew rate used in slew limiter + + + bitmask of PID state flags + + + 1 + true if the output is saturated, I term anti windup is active + + + 2 + true if the PD sum limit is active + + + 4 + true if the controller was reset + + + 8 + true if the I term has been set externally including reseting to 0 + + + + + + + Proportional/Integral/Derivative gain values for Pitch rate + + + Time since system startup + + + desired value + + + achieved value + + + error between target and achieved + + + proportional part of PID + + + integral part of PID + + + derivative part of PID + + + controller feed-forward portion of response + + + controller derivative feed-forward portion of response + + + scaler applied to D gain to reduce limit cycling + + + slew rate used in slew limiter + + + bitmask of PID state flags + + + 1 + true if the output is saturated, I term anti windup is active + + + 2 + true if the PD sum limit is active + + + 4 + true if the controller was reset + + + 8 + true if the I term has been set externally including reseting to 0 + + + + + + + Proportional/Integral/Derivative gain values for Roll rate + + + Time since system startup + + + desired value + + + achieved value + + + error between target and achieved + + + proportional part of PID + + + integral part of PID + + + derivative part of PID + + + controller feed-forward portion of response + + + controller derivative feed-forward portion of response + + + scaler applied to D gain to reduce limit cycling + + + slew rate used in slew limiter + + + bitmask of PID state flags + + + 1 + true if the output is saturated, I term anti windup is active + + + 2 + true if the PD sum limit is active + + + 4 + true if the controller was reset + + + 8 + true if the I term has been set externally including reseting to 0 + + + + + + + Proportional/Integral/Derivative gain values for ground steering yaw rate + + + Time since system startup + + + desired value + + + achieved value + + + error between target and achieved + + + proportional part of PID + + + integral part of PID + + + derivative part of PID + + + controller feed-forward portion of response + + + controller derivative feed-forward portion of response + + + scaler applied to D gain to reduce limit cycling + + + slew rate used in slew limiter + + + bitmask of PID state flags + + + 1 + true if the output is saturated, I term anti windup is active + + + 2 + true if the PD sum limit is active + + + 4 + true if the controller was reset + + + 8 + true if the I term has been set externally including reseting to 0 + + + + + + + Proportional/Integral/Derivative gain values for Yaw rate + + + Time since system startup + + + desired value + + + achieved value + + + error between target and achieved + + + proportional part of PID + + + integral part of PID + + + derivative part of PID + + + controller feed-forward portion of response + + + controller derivative feed-forward portion of response + + + scaler applied to D gain to reduce limit cycling + + + slew rate used in slew limiter + + + bitmask of PID state flags + + + 1 + true if the output is saturated, I term anti windup is active + + + 2 + true if the PD sum limit is active + + + 4 + true if the controller was reset + + + 8 + true if the I term has been set externally including reseting to 0 + + + + + + + Precision Landing messages + + + Time since system startup + + + True if Precision Landing is healthy + + + True if landing target is detected + + + Target position relative to vehicle, X-Axis (0 if target not found) + + + Target position relative to vehicle, Y-Axis (0 if target not found) + + + Target velocity relative to vehicle, X-Axis (0 if target not found) + + + Target velocity relative to vehicle, Y-Axis (0 if target not found) + + + Target's relative to origin position as 3-D Vector, X-Axis + + + Target's relative to origin position as 3-D Vector, Y-Axis + + + Target's relative to origin position as 3-D Vector, Z-Axis + + + Time when target was last detected + + + EKF's outlier count + + + Type of estimator used + + + + + autopilot system performance and general data dumping ground + + + Time since system startup + + + Main loop rate + + + Number of long loops detected + + + Number of measurement loops for this message + + + Maximum loop time + + + Free memory available + + + System processor load + + + Internal error line number; last line number on which a internal error was detected + + + Internal error mask; which internal errors have been detected + + + 1 + + + 2 + + + 4 + + + 8 + + + 16 + + + 32 + + + 64 + + + 128 + + + 256 + + + 512 + + + 1024 + + + 2048 + + + 4096 + + + 8192 + + + 16384 + + + 32768 + + + 65536 + + + 131072 + + + 262144 + + + 524288 + + + 1048576 + + + 2097152 + + + 4194304 + + + 8388608 + + + 16777216 + + + 33554432 + + + 67108864 + + + 134217728 + + + 268435456 + + + 536870912 + + + 1073741824 + + + + + Internal error count; how many internal errors have been detected + + + Number of SPI transactions processed + + + Number of i2c transactions processed + + + Number of i2c interrupts serviced + + + number of microseconds being added to each loop to address scheduler overruns + + + RTC time, time since Unix epoch + + + + + Canonical vehicle position + + + Time since system startup + + + Canonical vehicle latitude + + + Canonical vehicle longitude + + + Canonical vehicle altitude + + + Canonical vehicle altitude relative to home + + + Canonical vehicle altitude relative to navigation origin + + + + + System power information + + + Time since system startup + + + Flight board voltage + + + Servo rail voltage + + + System power flags + + + 1 + main brick power supply valid + + + 2 + main servo power supply valid for FMU + + + 4 + USB power is connected + + + 8 + peripheral supply is in over-current state + + + 16 + hi-power peripheral supply is in over-current state + + + 32 + Power status has changed since boot + + + + + Accumulated System power flags; all flags which have ever been set + + + 1 + main brick power supply valid + + + 2 + main servo power supply valid for FMU + + + 4 + USB power is connected + + + 8 + peripheral supply is in over-current state + + + 16 + hi-power peripheral supply is in over-current state + + + 32 + Power status has changed since boot + + + + + Hardware Safety Switch status + + + + + Plane Parameter Tuning data + + + Time since system startup + + + Parameter set being tuned + + + Parameter being tuned + + + Current parameter value + + + Center value (startpoint of current modifications) of parameter being tuned + + + + + Proximity Filtered sensor data + + + Time since system startup + + + Pitch(instance) at which the obstacle is at. 0th layer {-75,-45} degrees. 1st layer {-45,-15} degrees. 2nd layer {-15, 15} degrees. 3rd layer {15, 45} degrees. 4th layer {45,75} degrees. Minimum distance in each layer will be logged. + + + True if proximity sensor is healthy + + + Nearest object in sector surrounding 0-degrees + + + Nearest object in sector surrounding 45-degrees + + + Nearest object in sector surrounding 90-degrees + + + Nearest object in sector surrounding 135-degrees + + + Nearest object in sector surrounding 180-degrees + + + Nearest object in sector surrounding 225-degrees + + + Nearest object in sector surrounding 270-degrees + + + Nearest object in sector surrounding 315-degrees + + + Nearest object in upwards direction + + + Angle to closest object + + + Distance to closest object + + + + + Proximity Raw sensor data + + + Time since system startup + + + Pitch(instance) at which the obstacle is at. 0th layer {-75,-45} degrees. 1st layer {-45,-15} degrees. 2nd layer {-15, 15} degrees. 3rd layer {15, 45} degrees. 4th layer {45,75} degrees. Minimum distance in each layer will be logged. + + + Nearest object in sector surrounding 0-degrees + + + Nearest object in sector surrounding 45-degrees + + + Nearest object in sector surrounding 90-degrees + + + Nearest object in sector surrounding 135-degrees + + + Nearest object in sector surrounding 180-degrees + + + Nearest object in sector surrounding 225-degrees + + + Nearest object in sector surrounding 270-degrees + + + Nearest object in sector surrounding 315-degrees + + + + + Position Control Down + + + Time since system startup + + + Desired position relative to EKF origin + Offsets + + + Target position relative to EKF origin + + + Position relative to EKF origin + + + Desired velocity Down + + + Target velocity Down + + + Velocity Down + + + Desired acceleration Down + + + Target acceleration Down + + + Acceleration Down + + + + + Position Control East + + + Time since system startup + + + Desired position relative to EKF origin + Offsets + + + Target position relative to EKF origin + + + Position relative to EKF origin + + + Desired velocity East + + + Target velocity East + + + Velocity East + + + Desired acceleration East + + + Target acceleration East + + + Acceleration East + + + + + Position Control North + + + Time since system startup + + + Desired position relative to EKF origin + + + Target position relative to EKF origin + + + Position relative to EKF origin + + + Desired velocity North + + + Target velocity North + + + Velocity North + + + Desired acceleration North + + + Target acceleration North + + + Acceleration North + + + + + Position Control Offsets Down + + + Time since system startup + + + Target position offset Down + + + Position offset Down + + + Target velocity offset Down + + + Velocity offset Down + + + Target acceleration offset Down + + + Acceleration offset Down + + + + + Position Control Offsets East + + + Time since system startup + + + Target position offset East + + + Position offset East + + + Target velocity offset East + + + Velocity offset East + + + Target acceleration offset East + + + Acceleration offset East + + + + + Position Control Offsets North + + + Time since system startup + + + Target position offset North + + + Position offset North + + + Target velocity offset North + + + Velocity offset North + + + Target acceleration offset North + + + Acceleration offset North + + + + + Position Control Offsets Terrain (Down) + + + Time since system startup + + + Target position offset Terrain + + + Position offset Terrain + + + Target velocity offset Terrain + + + Velocity offset Terrain + + + Target acceleration offset Terrain + + + Acceleration offset Terrain + + + + + https://ardupilot.org/copter/docs/tuning.html#in-flight-tuning + Parameter Tuning information + + + Time since system startup + + + Parameter being tuned + + + Normalized value used inside tuning() function + + + Tuning minimum limit + + + Tuning maximum limit + + + normalaised control input (normalised -1 to 1 value) + + + + + Quicktune + + + Time since system startup + + + number of parameter being tuned + + + slew rate + + + test gain for current axis and PID element + + + name of parameter being being tuned + + + + + Telemetry radio statistics + + + Time since system startup + + + RSSI + + + RSSI reported from remote radio + + + number of bytes in radio ready to be sent + + + local noise floor + + + local noise floor reported from remote radio + + + damaged packet count + + + fixed damaged packet count + + + + + Rally point information + + + Time since system startup + + + total number of rally points onboard + + + this rally point's sequence number + + + latitude of rally point + + + longitude of rally point + + + altitude of rally point + + + altitude frame flags + + + + + Replay Airspeed Sensor Header + + + airspeed instance number + + + number of airspeed instances + + + + + Replay Airspeed Sensor Instance data + + + measured airspeed + + + timestamp of measured airspeed + + + indicator of airspeed sensor health + + + true if airspeed is configured to be used + + + airspeed instance number + + + + + Desired and achieved vehicle attitude rates. Not logged in Fixed Wing Plane modes. + + + Time since system startup + + + vehicle desired roll rate + + + achieved vehicle roll rate + + + normalized output for Roll + + + vehicle desired pitch rate + + + vehicle pitch rate + + + normalized output for Pitch + + + vehicle desired yaw rate + + + achieved vehicle yaw rate + + + normalized output for Yaw + + + desired vehicle vertical acceleration + + + achieved vehicle vertical acceleration + + + percentage of vertical thrust output current being used + + + vertical thrust output slew rate + + + + + Replay Data Beacon Header + + + zero, unused + + + zero, unused + + + zero, unused + + + zero, unused + + + origin latitude + + + origin longitude + + + origin altitude + + + vehicle_position_ned_returncode,get_origin_returncode,enabled + + + number of beacons + + + + + Replay Data Beacon Instance + + + last update from this beacon instance + + + beacon distance from origin, X-axis + + + beacon distance from origin, Y-axis + + + beacon distance from origin, Z-axis + + + distance to beacon + + + beacon data health + + + beacon instance number + + + + + Replay body odometry data + + + data quality measure + + + delta-position-X + + + delta-position-Y + + + delta-position-Z + + + delta-angle-X + + + delta-angle-Y + + + delta-angle-Z + + + delta-time + + + data timestamp + + + zero, unused + + + zero, unused + + + zero, unused + + + zero, unused + + + + + Replay Data Barometer Header + + + primary barometer instance number + + + number of barometer sensors + + + + + Replay Data Barometer Instance + + + timestamp of barometer data + + + barometer altitude estimate + + + barometer sensor health indication + + + barometer instance number + + + + + Raw RC data + + + Time since system startup + + + data arrival timestamp + + + Protocol currently being decoded + + + Number of valid bytes in message + + + first quartet of bytes + + + second quartet of bytes + + + third quartet of bytes + + + fourth quartet of bytes + + + fifth quartet of bytes + + + sixth quartet of bytes + + + seventh quartet of bytes + + + eight quartet of bytes + + + ninth quartet of bytes + + + tenth quartet of bytes + + + + + (More) RC input channels to vehicle + + + Time since system startup + + + channel 15 input + + + channel 16 input + + + bitmask of RC channels being overridden by mavlink input + + + bitmask of RC state flags + + + 1 + true if the system is receiving good RC values + + + 2 + true if the system is current in RC failsafe + + + 4 + true if the RC Protocol library is indicating the RC receiver is indicating failsafe via its protocol + + + + + + + RC input channels to vehicle + + + Time since system startup + + + channel 1 input + + + channel 2 input + + + channel 3 input + + + channel 4 input + + + channel 5 input + + + channel 6 input + + + channel 7 input + + + channel 8 input + + + channel 9 input + + + channel 10 input + + + channel 11 input + + + channel 12 input + + + channel 13 input + + + channel 14 input + + + + + Servo channel output values 15 to 18 + + + Time since system startup + + + channel 15 output + + + channel 16 output + + + channel 17 output + + + channel 18 output + + + + + Servo channel output values 19 to 32 + + + Time since system startup + + + channel 19 output + + + channel 20 output + + + channel 21 output + + + channel 22 output + + + channel 23 output + + + channel 24 output + + + channel 25 output + + + channel 26 output + + + channel 27 output + + + channel 28 output + + + channel 29 output + + + channel 30 output + + + channel 31 output + + + channel 32 output + + + + + Servo channel output values 1 to 14 + + + Time since system startup + + + channel 1 output + + + channel 2 output + + + channel 3 output + + + channel 4 output + + + channel 5 output + + + channel 6 output + + + channel 7 output + + + channel 8 output + + + channel 9 output + + + channel 10 output + + + channel 11 output + + + channel 12 output + + + channel 13 output + + + channel 14 output + + + + + Relay state + + + Time since system startup + + + relay instance number + + + current state + + + + + Replay external position data + + + external position estimate, X-axis + + + external position estimate, Y-axis + + + external position estimate, Z-axis + + + external attitude quaternion + + + external attitude quaternion + + + external attitude quaternion + + + external attitude quaternion + + + external position error estimate + + + external attitude error estimate + + + timestamp on external error estimate + + + timestamp of last external reset + + + delay on external data + + + + + Replay Event (EKF2) + + + external event injected into EKF + + + 0 + + + 1 + + + 9 + + + 10 + + + 11 + + + 12 + + + 13 + + + 14 + + + 15 + + + + + + + Replay Event (EKF3) + + + external event injected into EKF + + + 0 + + + 1 + + + 9 + + + 10 + + + 11 + + + 12 + + + 13 + + + 14 + + + 15 + + + + + + + Replay external velocity data + + + external velocity estimate, X-axis + + + external velocity estimate, Y-axis + + + external velocity estimate, Z-axis + + + error in velocity estimate + + + timestamp of velocity estimate + + + delay in external velocity data + + + + + Replay Euler Yaw event + + + externally supplied yaw angle + + + error in externally supplied yaw angle + + + timestamp associated with yaw angle and yaw angle error + + + number that needs documenting + + + + + RealFlight mode messages + + + Time since system startup + + + delta time between this frame and the previous frame + + + frames-per-second implied by the current delta time + + + + + Rangefinder sensor information + + + Time since system startup + + + rangefinder instance number this data is from + + + Reported distance from sensor + + + Sensor state + + + 0 + + + 1 + + + 2 + + + 3 + + + 4 + + + + + Sensor orientation + + + 0 + + + 1 + + + 2 + + + 3 + + + 4 + + + 5 + + + 6 + + + 7 + + + 8 + + + 9 + + + 10 + + + 11 + + + 12 + + + 13 + + + 14 + + + 15 + + + 16 + + + 17 + + + 18 + + + 19 + + + 20 + + + 21 + + + 22 + + + 23 + + + 24 + + + 25 + + + 26 + same as ROTATION_ROLL_180_YAW_270 + + + 27 + same as ROTATION_ROLL_180_YAW_90 + + + 28 + + + 29 + + + 30 + + + 31 + + + 32 + + + 33 + + + 34 + + + 35 + + + 36 + + + 37 + + + 38 + this is actually, roll 90, pitch 68.8, yaw 293.3 + + + 39 + + + 40 + + + 41 + + + 42 + + + 43 + + + 44 + + + 100 + + + 101 + + + 102 + + + 103 + + + + + Signal quality. -1 means invalid, 0 is no signal, 100 is perfect signal + + + + + Replay FRame data - Finished frame + + + accumulated method calls made during frame + + + 1 + + + 2 + + + 4 + + + 8 + + + 16 + + + 32 + + + + + true if we are not keeping up with IMU loop rate + + + + + Replay FRame Header + + + Time since system startup + + + Time flying + + + + + Replay FRame - aNother frame header + + + home latitude + + + home latitude + + + home altitude AMSL + + + EAS to TAS factor + + + available memory + + + AHRS trim X + + + AHRS trim Y + + + AHRS trim Z + + + AHRS Vehicle Class + + + configured EKF type + + + 0 + + + 1 + + + + + bitmask of boolean state + + + 1 + + + 2 + + + 4 + + + 8 + + + 16 + + + 32 + + + 64 + + + 128 + + + + + + + Replay Data GPS Header + + + number of GPS sensors + + + instance number of primary sensor + + + + + Replay Data GPS Instance, infrequently changing data + + + antenna body-frame offset, X-axis + + + antenna body-frame offset, Y-axis + + + antenna body-frame offset, Z-axis + + + GPS time lag + + + various GPS flags + + + 1 + + + 2 + + + 4 + + + 8 + + + 16 + + + 32 + + + + + GPS fix status + + + number of satellites GPS is using + + + GPS sensor instance number + + + + + Replay Data GPS Instance - rapidly changing data + + + GPS data timestamp + + + GPS velocity, North + + + GPS velocity, East + + + GPS velocity, Down + + + speed accuracy + + + GPS yaw + + + GPS yaw accuracy + + + timestamp of GPS yaw estimate + + + latitude + + + longitude + + + altitude + + + horizontal accuracy + + + vertical accuracy + + + HDOP + + + GPS sensor instance number + + + + + Richenpower generator telemetry + + + Time since system startup + + + total generator runtime + + + time until generator requires maintenance + + + bitmask of error received from generator + + + current generator RPM + + + output voltage + + + output current + + + generator mode; idle/run/charge/balance + + + + + Replay Inertial Sensor header + + + INS loop rate + + + primary gyro index + + + primary accel index + + + INS loop-delta-t + + + accel count + + + gyro count + + + + + Replay Inertial Sensor instance data + + + x-axis delta-velocity + + + y-axis delta-velocity + + + z-axis delta-velocity + + + x-axis delta-angle + + + y-axis delta-angle + + + z-axis delta-angle + + + delta-velocity-delta-time + + + delta-angle-delta-time + + + use-accel, use-gyro, delta-vel-valid, delta-accel-valid + + + IMU instance + + + + + Replay Data Magnetometer Header + + + vehicle declination + + + true if the compass library is marking itself as available + + + number of compass instances + + + true if compass autodeclination is enabled + + + number of enabled compass instances + + + true if compass learning of offsets is enabled + + + true if compasses are consistent + + + index of first usable compass + + + + + Replay Data Magnetometer Instance + + + last update time for magnetometer data + + + mag sensor offset, X-axis + + + mag sensor offset, Y-axis + + + mag sensor offset, Z-axis + + + field strength, X-axis + + + field strength, Y-axis + + + field strength, Z-axis + + + true if compass is being used for yaw + + + sensor health + + + compass has scale factor + + + magnetometer instance number + + + + + Replay optical flow data + + + raw flow rate, X-axis + + + raw flow rate, Y-axis + + + gyro rate, X-axis + + + gyro rate, Y-axis + + + measurement timestamp + + + gyro rate, X-axis + + + body-frame offset, Y-axis + + + body-frame offset, Z-axis + + + sensor height override + + + flow quality measurement + + + + + Data from RPM sensors + + + Time since system startup + + + Instance + + + Sensor's rpm measurement + + + Signal quality + + + Sensor Health (Bool) + + + + + Replay Data Rangefinder Header + + + rangefinder ground clearance for downward-facing rangefinders + + + rangefinder maximum distance for downward-facing rangefinders + + + number of rangefinder instances + + + + + Replay Data Rangefinder Instance + + + rangefinder body-frame offset, X-axis + + + rangefinder body-frame offset, Y-axis + + + rangefinder body-frame offset, Z-axis + + + Measured rangefinder distance + + + orientation + + + status + + + rangefinder instance number + + + + + Replay Set Lat Lng event + + + latitude + + + longitude + + + position accuracy, 1-StD + + + timestamp of latitude/longitude + + + + + Replay Set Origin event (EKF2) + + + origin latitude + + + origin longitude + + + origin altitude + + + + + Replay Set Origin event (EKF3) + + + origin latitude + + + origin longitude + + + origin altitude + + + + + Received Signal Strength Indicator for RC receiver + + + Time since system startup + + + RSSI + + + RX Link Quality + + + + + Information about RTC clock resets + + + Time since system startup + + + old time + + + new time + + + + + GPS atmospheric perturbation data + + + Time since system startup + + + mavlink channel number this data was received on + + + ID field from RTCM packet + + + RTCM packet length + + + calculated crc32 for the packet + + + + + Attitude controller time deltas + + + Time since system startup + + + current time delta + + + current time delta average + + + Max time delta since last log output + + + Min time delta since last log output + + + + + Replay Terrain SRTM Altitude + + + altitude above origin in meters + + + + + Replay Data Visual Odometry data + + + offset, x-axis + + + offset, y-axis + + + offset, z-axis + + + data delay + + + sensor health + + + sensor enabled + + + + + Replay set-default-airspeed event (EKF2) + + + default airspeed + + + uncertainty in default airspeed + + + + + Replay set-default-airspeed event (EKF3) + + + default airspeed + + + uncertainty in default airspeed + + + + + Replay wheel odometry data + + + delta-angle + + + delta-time + + + data timestamp + + + sensor body-frame offset, x-axis + + + sensor body-frame offset, y-axis + + + sensor body-frame offset, z-axis + + + wheel radius + + + + + Simple Avoidance messages + + + Time since system startup + + + True if Simple Avoidance is active + + + Desired velocity, X-Axis (Velocity before Avoidance) + + + Desired velocity, Y-Axis (Velocity before Avoidance) + + + Desired velocity, Z-Axis (Velocity before Avoidance) + + + Modified velocity, X-Axis (Velocity after Avoidance) + + + Modified velocity, Y-Axis (Velocity after Avoidance) + + + Modified velocity, Z-Axis (Velocity after Avoidance) + + + True if vehicle is backing away + + + + + Simulated Blimp Sin-Angles + + + Time since system startup + + + sin(x angle) + + + sin(y angle) + + + sin(z angle) + + + + + Simulated Blimp Angles + + + Time since system startup + + + x angle + + + y angle + + + z angle + + + + + Simulated Blimp Angles + + + Time since system startup + + + x earth-frame angle + + + y earth-frame angle + + + z earth-frame angle + + + + + Simulated Blimp Body-Frame accelerations + + + Time since system startup + + + x-axis acceleration + + + y-axis acceleration + + + z-axis acceleration + + + + + Simulated Blimp Rotational Accelerations + + + Time since system startup + + + acceleration around X axis + + + acceleration around Y axis + + + acceleration around Z axis + + + + + Swift Health Data + + + Time since system startup + + + Number of packet CRC errors on serial connection + + + Timestamp of last raw data injection to GPS + + + Current number of integer ambiguity hypotheses + + + + + Swift Time Data + + + Time since system startup + + + GPS week number + + + Milliseconds through GPS week + + + residual of milliseconds rounding in ns + + + GPIO pin levels + + + time quality + + + + + Scripting runtime stats + + + Time since system startup + + + script name + + + run time + + + total memory usage of all scripts + + + run memory usage + + + + + Simulated Glider Drop control outputs + + + Time since system startup + + + aileron output + + + elevator output + + + rudder output + + + + + Debug message for SCurve internal error + + + Time since system startup + + + duration of the raised cosine jerk profile + + + maximum value of the raised cosine jerk profile + + + initial velocity magnitude + + + maximum constant acceleration + + + maximum constant velocity + + + Length of the path + + + maximum value of the raised cosine jerk profile + + + segment duration + + + segment duration + + + segment duration + + + segment duration + + + + + Simulated Blimp Fin Angles + + + Time since system startup + + + fin 0 angle + + + fin 1 angle + + + fin 2 angle + + + fin 3 angle + + + + + Simulated Blimp Servo Angles + + + Time since system startup + + + fin 0 servo angle + + + fin 1 servo angle + + + fin 2 servo angle + + + fin 3 servo angle + + + + + Simulated Blimp Fin Forces + + + Time since system startup + + + Fin 0 normal force + + + Fin 1 normal force + + + Fin 2 normal force + + + Fin 3 normal force + + + + + Simulated Blimp Fin Thrust + + + Time since system startup + + + Fin 0 tangential thrust + + + Fin 1 tangential thrust + + + Fin 2 tangential thrust + + + Fin 3 tangential thrust + + + + + Simulated Blimp Fin Velocities + + + Time since system startup + + + fin 0 velocity + + + fin 1 velocity + + + fin 2 velocity + + + fin 3 velocity + + + + + System ID data + + + Time since system startup + + + Time reference for waveform + + + Current waveform sample + + + Instantaneous waveform frequency + + + Delta angle, X-Axis + + + Delta angle, Y-Axis + + + Delta angle, Z-Axis + + + Delta velocity, X-Axis + + + Delta velocity, Y-Axis + + + Delta velocity, Z-Axis + + + + + System ID settings + + + Time since system startup + + + The axis which is being excited + + + Magnitude of the chirp waveform + + + Frequency at the start of chirp + + + Frequency at the end of chirp + + + Time to reach maximum amplitude of chirp + + + Time at constant frequency before chirp starts + + + Time taken to complete chirp waveform + + + Time to reach zero amplitude after chirp finishes + + + + + SITL simulator state + + + Time since system startup + + + Simulated roll + + + Simulated pitch + + + Simulated yaw + + + Simulated altitude + + + Simulated latitude + + + Simulated longitude + + + Attitude quaternion component 1 + + + Attitude quaternion component 2 + + + Attitude quaternion component 3 + + + Attitude quaternion component 4 + + + + + Additional simulator state + + + Time since system startup + + + North position from home + + + East position from home + + + Down position from home + + + Velocity north + + + Velocity east + + + Velocity down + + + Airspeed + + + Achieved simulation speedup value + + + Number of times simulation paused for serial0 output + + + + + Simulation data + + + Time since system startup + + + Velocity - North component + + + Velocity - East component + + + Velocity - Down component + + + Acceleration - North component + + + Acceleration - East component + + + Acceleration - Down component + + + Position - North component + + + Position - East component + + + Position - Down component + + + + + More Simulated Glider Dropped Calculations + + + Time since system startup + + + altitude in feet + + + equivalent airspeed in knots + + + true airspeed in knots + + + air density + + + lift + + + drag + + + lift/drag ratio + + + elevator output + + + aileron output + + + rudder output + + + Angle of Attack + + + Side Slip Angle + + + air pressire + + + z-axis body-frame acceleration + + + + + Simulated Glider Dropped Calculations + + + Time since system startup + + + altitude in feet + + + altitude in metres + + + equivalent airspeed + + + true airspeed + + + air density + + + lift + + + drag + + + lift/drag ratio + + + elevator output + + + angle of attack + + + X-axis force + + + Y-axis force + + + Z-axis force + + + air pressure + + + + + Slung payload + + + Time since system startup + + + 1 if payload is landed, 0 otherwise + + + Tension ratio, 1 if line is taut, 0 if slack + + + Line length + + + Payload position as offset from vehicle in North direction + + + Payload position as offset from vehicle in East direction + + + Payload position as offset from vehicle in Down direction + + + Payload velocity in North direction + + + Payload velocity in East direction + + + Payload velocity in Down direction + + + Payload acceleration in North direction + + + Payload acceleration in East direction + + + Payload acceleration in Down direction + + + Force on vehicle in North direction + + + Force on vehicle in East direction + + + Force on vehicle in Down direction + + + + + Log data received from JSON simulator 1 + + + Time since system startup (us) + + + Slave instance + + + magic JSON protocol key + + + Slave instance's desired frame rate + + + Slave instance's current frame count + + + 1 if the servo outputs are being used from this instance + + + + + Log data received from JSON simulator 2 + + + Time since system startup + + + Slave instance + + + channel 1 output + + + channel 2 output + + + channel 3 output + + + channel 4 output + + + channel 5 output + + + channel 6 output + + + channel 7 output + + + channel 8 output + + + channel 9 output + + + channel 10 output + + + channel 11 output + + + channel 12 output + + + channel 13 output + + + channel 14 output + + + + + Simulated Blimp Mass and COG + + + Time since system startup + + + mass + + + gravity + + + centre-of-gravity, z-axis + + + + + Smoothed sensor data fed to EKF to avoid inconsistencies + + + Time since system startup + + + Angular Velocity (around x-axis) + + + Angular Velocity (around y-axis) + + + Angular Velocity (around z-axis) + + + Velocity (along x-axis) + + + Velocity (along y-axis) + + + Velocity (along z-axis) + + + Roll + + + Pitch + + + Yaw + + + DCM Roll + + + DCM Pitch + + + DCM Yaw + + + + + Simulated Volz servo information + + + Time since system startup + + + Volz servo ID + + + Current Simulated Position + + + Desired Simulated Position + + + simulated servo voltage + + + simulated servo current + + + simulated PCB Temperature + + + simulated motor Temperature + + + + + Simulated Blimp Rotational forces + + + Time since system startup + + + zero + + + zero + + + zero + + + + + Transformed Simulated Blimp Rotational forces + + + Time since system startup + + + x-axis wobble rotational force + + + y-axis wobble rotational force + + + z-axis wobble rotational force + + + + + Simulated Blimp Torques + + + Time since system startup + + + torque around x axis + + + torque around y axis + + + torque around z axis + + + + + SmartRTL statistics + + + Time since system startup + + + true if SmartRTL could be used right now + + + number of points currently in use + + + maximum number of points that could be used + + + most recent internal action taken by SRTL library + + + 0 + + + 1 + + + 2 + + + 3 + + + 4 + + + 5 + + + 6 + + + 7 + + + 9 + + + 10 + + + 11 + + + + + point associated with most recent action (North component) + + + point associated with most recent action (East component) + + + point associated with most recent action (Down component) + + + + + Simulated Blimp Servo Inputs + + + Time since system startup + + + fin 0 servo angle input + + + fin 1 servo angle input + + + fin 2 servo angle input + + + fin 3 servo angle input + + + + + Stack information + + + Time since system startup + + + thread ID + + + thread priority + + + total stack + + + free stack + + + thread name + + + + + Surface distance measurement + + + Time since system startup + + + Instance + + + Surface distance status + + + 1 + true if rangefinder has been set to enable by vehicle + + + 2 + true if rangefinder is considered unhealthy + + + 4 + true if the last healthy rangefinder reading is no longer valid + + + 8 + true if a measurement glitch detected + + + + + Raw Distance + + + Filtered Distance + + + Terrain Offset + + + + + Helicopter swashplate logging + + + Time since system startup + + + Swashplate instance + + + Blade pitch angle contribution from collective + + + Total blade pitch angle contribution from cyclic + + + Blade pitch angle contribution from pitch cyclic + + + Blade pitch angle contribution from roll cyclic + + + + + Temperature Calibration Information + + + Time since system startup + + + temperature calibration instance number + + + sensor type (0==accel, 1==gyro) + + + current temperature + + + x-axis sample sum + + + y-axis sample sum + + + z-axis sample sum + + + sample count + + + + + Temperature Sensor Data + + + Time since system startup + + + temperature sensor instance + + + temperature + + + + + Terrain database information + + + Time since system startup + + + Terrain database status + + + 0 + not enabled + + + 1 + no terrain data for current location + + + 2 + terrain data available + + + + + Current vehicle latitude + + + Current vehicle longitude + + + terrain Tile spacing + + + current Terrain height + + + Vehicle height above terrain + + + Number of tile requests outstanding + + + Number of tiles in memory + + + terrain reference offset for arming altitude + + + + + Tether state + + + Time since system startup + + + Tether length + + + Force on vehicle in North direction + + + Force on vehicle in East direction + + + Force on vehicle in Down direction + + + + + https://ardupilot.org/copter/docs/throw-mode.html + Throw Mode messages + + + Time since system startup + + + Current stage of the Throw Mode + + + Magnitude of the velocity vector + + + Vertical Velocity + + + Magnitude of the vector of the current acceleration + + + Vertical earth frame accelerometer value + + + True if a throw has been detected since entering this mode + + + True if the vehicle is upright + + + True if the vehicle is within 0.5 m of the demanded height + + + True if the vehicle is within 0.5 m of the demanded horizontal position + + + + + Maximum thrust limitation based on battery voltage in Toy Mode + + + Time since system startup + + + Filtered battery voltage + + + Thrust multiplier between 0 and 1 to limit the output thrust based on battery voltage + + + Motor 1 pwm output + + + Motor 2 pwm output + + + Motor 3 pwm output + + + Motor 4 pwm output + + + + + Camera shutter information + + + Time since system startup + + + Instance number + + + Image number + + + milliseconds since start of GPS week + + + weeks since 5 Jan 1980 + + + current latitude + + + current longitude + + + current altitude + + + current altitude relative to home + + + altitude as reported by GPS + + + current vehicle roll + + + current vehicle pitch + + + current vehicle yaw + + + + + Torqeedo Motor Param + + + Time since system startup + + + instance + + + Motor RPM + + + Motor power + + + Motor voltage + + + Motor current + + + ESC Temp + + + Motor Temp + + + + + Torqeedo Motor Status + + + Time since system startup + + + instance + + + Motor status flags + + + Motor error flags + + + + + Torqeedo Status + + + Time since system startup + + + instance + + + Health + + + Desired Motor Speed (-1000 to 1000) + + + Motor Speed (-1000 to 1000) + + + Success Count + + + Error Count + + + + + Torqeedo System Setup + + + Time since system startup + + + instance + + + Flags + + + Motor type + + + Motor software version + + + Battery capacity + + + Battery charge percentage + + + Battery type + + + Master software version + + + + + Torqeedo System State + + + Time since system startup + + + instance + + + Flags bitmask + + + Master error code + + + Motor voltage + + + Motor current + + + Motor power + + + Motor RPM + + + Motor Temp (higher of pcb or stator) + + + Battery charge percentage + + + Battery voltage + + + Battery current + + + + + Time synchronisation response information + + + Time since system startup + + + system ID this data is for + + + round trip time for this system + + + + + UART stats + + + Time since system startup + + + instance + + + transmitted data rate bytes per second + + + received data rate bytes per second, this is all incoming data, it may not all be processed by the driver using this port. + + + Data rate of dropped received bytes, ideally should be 0. This is the difference between the received data rate and the processed data rate. + + + + + uBlox-specific GPS information (part 1) + + + Time since system startup + + + GPS instance number + + + noise level as measured by GPS + + + jamming indicator; higher is more likely jammed + + + antenna power indicator; 2 is don't know + + + automatic gain control monitor + + + bitmask for messages which haven't been seen + + + + + uBlox-specific GPS information (part 2) + + + Time since system startup + + + GPS instance number + + + imbalance of I part of complex signal + + + magnitude of I part of complex signal + + + imbalance of Q part of complex signal + + + magnitude of Q part of complex signal + + + + + uBlox specific UBX-TIM-TM2 logging, see uBlox interface description + + + Time since system startup + + + GPS instance number + + + Channel (i.e. EXTINT) upon which the pulse was measured + + + Bitmask + + + Rising edge counter + + + Week number of last rising edge + + + Tow of rising edge + + + Millisecond fraction of tow of rising edge in nanoseconds + + + Week number of last falling edge + + + Tow of falling edge + + + Millisecond fraction of tow of falling edge in nanoseconds + + + Accuracy estimate + + + + + Message mapping from single character to SI unit + + + Time since system startup + + + character referenced by FMTU + + + Unit - SI where available + + + + + Ardupilot version + + + Time since system startup + + + Board type + + + 3 + + + 7 + + + 10 + + + 12 + + + 13 + + + 99 + + + + + Board subtype + + + -1 + + + 1000 + + + 1001 + + + 1002 + + + 1003 + + + 1005 + + + 1006 + + + 1009 + + + 1010 + + + 1012 + + + 1013 + + + 1014 + + + 1015 + + + 1016 + + + 1018 + + + 1020 + + + 1022 + + + 1023 + + + 1024 + + + 1025 + + + 1026 + + + 1027 + + + 1028 + + + 1029 + + + 1030 + + + + + Major version number + + + Minor version number + + + Patch number + + + Firmware type + + + Github commit + + + Firmware version string + + + Board ID + + + Build vehicle type + + + 1 + + + 2 + + + 3 + + + 4 + + + 5 + + + 6 + + + 7 + + + 8 + + + 9 + + + 10 + + + 11 + + + 12 + + + 13 + + + + + Filter version + + + IOMCU MCU ID + + + IOMCU CPU ID + + + + + Processed (acceleration) vibration information + + + Time since system startup + + + Vibration instance number + + + Primary accelerometer filtered vibration, x-axis + + + Primary accelerometer filtered vibration, y-axis + + + Primary accelerometer filtered vibration, z-axis + + + Number of clipping events on 1st accelerometer + + + + + Visual Odometry + + + System time + + + Time period this data covers + + + Angular change for body-frame roll axis + + + Angular change for body-frame pitch axis + + + Angular change for body-frame z axis + + + Position change for body-frame X axis (Forward-Back) + + + Position change for body-frame Y axis (Right-Left) + + + Position change for body-frame Z axis (Down-Up) + + + Confidence + + + + + Vision Position + + + System time + + + Remote system time + + + Corrected system time + + + Position X-axis (North-South) + + + Position Y-axis (East-West) + + + Position Z-axis (Down-Up) + + + Roll lean angle + + + Pitch lean angle + + + Yaw angle + + + Position estimate error + + + Attitude estimate error + + + Position reset counter + + + Ignored + + + Quality + + + + + Vision Velocity + + + System time + + + Remote system time + + + Corrected system time + + + Velocity X-axis (North-South) + + + Velocity Y-axis (East-West) + + + Velocity Z-axis (Down-Up) + + + Velocity estimate error + + + Velocity reset counter + + + Ignored + + + Quality + + + + + VectorNav Attitude data + + + Time since system startup + + + Attitude quaternion 1 + + + Attitude quaternion 2 + + + Attitude quaternion 3 + + + Attitude quaternion 4 + + + Yaw + + + Pitch + + + Roll + + + Yaw unceratainty + + + Pitch uncertainty + + + Roll uncertainty + + + + + VectorNav IMU data + + + Time since system startup + + + Temprature + + + Pressure + + + Magnetic feild X-axis + + + Magnetic feild Y-axis + + + Magnetic feild Z-axis + + + Acceleration X-axis + + + Acceleration Y-axis + + + Acceleration Z-axis + + + Rotation rate X-axis + + + Rotation rate Y-axis + + + Rotation rate Z-axis + + + + + VectorNav INS Kalman Filter data + + + Time since system startup + + + VectorNav INS health status + + + Latitude + + + Longitude + + + Altitude + + + Velocity Northing + + + Velocity Easting + + + Velocity Downing + + + Filter estimated position uncertainty + + + Filter estimated Velocity uncertainty + + + + + Log message for video stabilisation software such as Gyroflow + + + Time since system startup + + + measured rotation rate about X axis + + + measured rotation rate about Y axis + + + measured rotation rate about Z axis + + + acceleration along X axis + + + acceleration along Y axis + + + acceleration along Z axis + + + Estimated attitude quaternion component 1 + + + Estimated attitude quaternion component 2 + + + Estimated attitude quaternion component 3 + + + Estimated attitude quaternion component 4 + + + + + Watchdog diagnostics + + + Time since system startup + + + current task number + + + internal error mast + + + internal error count + + + line internal error was raised on + + + mavlink message being acted on + + + mavlink command being acted on + + + line semaphore was taken on + + + fault_line + + + fault_type + + + fault address + + + fault thread priority + + + ICS regiuster + + + long return address + + + Thread name + + + + + Wheel encoder measurements + + + Time since system startup + + + First wheel distance travelled + + + Quality measurement of Dist0 + + + Second wheel distance travelled + + + Quality measurement of Dist1 + + + + + Winch + + + Time since system startup + + + Healthy + + + Reached end of thread + + + Motor is moving + + + Clutch is engaged (motor can move freely) + + + 0 is Relaxed, 1 is Position Control, 2 is Rate Control + + + Desired Length + + + Estimated Length + + + Desired Rate + + + Tension on line + + + Voltage to Motor + + + Motor temperature + + + + + Windvane readings + + + Time since system startup + + + raw apparent wind direction direct from sensor, in body-frame + + + Apparent wind direction, in body-frame + + + True wind direction + + + raw wind speed direct from sensor + + + Apparent wind Speed + + + True wind speed + + + + + EKF3 beacon sensor diagnostics + + + Time since system startup + + + EKF3 core this data is for + + + Beacon sensor ID + + + Beacon range + + + Beacon range innovation + + + sqrt of beacon range innovation variance + + + Beacon range innovation consistency test ratio + + + Beacon north position + + + Beacon east position + + + Beacon down position + + + High estimate of vertical position offset of beacons rel to EKF origin + + + Low estimate of vertical position offset of beacons rel to EKF origin + + + North position of receiver rel to EKF origin + + + East position of receiver rel to EKF origin + + + Down position of receiver rel to EKF origin + + + + + EKF3 estimator outputs + + + Time since system startup + + + EKF3 core this data is for + + + Estimated roll + + + Estimated pitch + + + Estimated yaw + + + Estimated velocity (North component) + + + Estimated velocity (East component) + + + Estimated velocity (Down component) + + + Filtered derivative of vertical position (down) + + + Estimated distance from origin (North component) + + + Estimated distance from origin (East component) + + + Estimated distance from origin (Down component) + + + Estimated gyro bias, X axis + + + Estimated gyro bias, Y axis + + + Estimated gyro bias, Z axis + + + Height of origin above WGS-84 + + + + + EKF3 estimator secondary outputs + + + Time since system startup + + + EKF3 core this data is for + + + Estimated accelerometer X bias + + + Estimated accelerometer Y bias + + + Estimated accelerometer Z bias + + + Estimated wind velocity (moving-to-North component) + + + Estimated wind velocity (moving-to-East component) + + + Magnetic field strength (North component) + + + Magnetic field strength (East component) + + + Magnetic field strength (Down component) + + + Magnetic field strength (body X-axis) + + + Magnetic field strength (body Y-axis) + + + Magnetic field strength (body Z-axis) + + + Innovation in vehicle drag acceleration (X-axis component) + + + Innovation in vehicle drag acceleration (Y-axis component) + + + Innovation in vehicle sideslip + + + + + EKF3 innovations + + + Time since system startup + + + EKF3 core this data is for + + + Innovation in velocity (North component) + + + Innovation in velocity (East component) + + + Innovation in velocity (Down component) + + + Innovation in position (North component) + + + Innovation in position (East component) + + + Innovation in position (Down component) + + + Innovation in magnetic field strength (X-axis component) + + + Innovation in magnetic field strength (Y-axis component) + + + Innovation in magnetic field strength (Z-axis component) + + + Innovation in vehicle yaw + + + Innovation in true-airspeed + + + Accumulated relative error of this core with respect to active primary core + + + A consolidated error score where higher numbers are less healthy + + + + + EKF3 variances. SV, SP, SH and SM are probably best described as 'Squared Innovation Test Ratios' where values <1 tells us the measurement was accepted and >1 tells us it was rejected. They represent the square of the (innovation / maximum allowed innovation) where the innovation is the difference between predicted and measured value and the maximum allowed innovation is determined from the uncertainty of the measurement, uncertainty of the prediction and scaled using the number of standard deviations set by the innovation gate parameter for that measurement, eg EK3_MAG_I_GATE, EK3_HGT_I_GATE, etc + + + Time since system startup + + + EKF3 core this data is for + + + Square root of the velocity variance + + + Square root of the position variance + + + Square root of the height variance + + + Magnetic field variance + + + Square root of the total airspeed variance + + + Filtered error in roll/pitch estimate + + + Most recent position reset (North component) + + + Most recent position reset (East component) + + + Filter fault status + + + Filter timeout status bitmask (0:position measurement, 1:velocity measurement, 2:height measurement, 3:magnetometer measurement, 4:airspeed measurement, 5:drag measurement) + + + Filter solution status + + + 1 + attitude estimate valid + + + 2 + horizontal velocity estimate valid + + + 4 + vertical velocity estimate valid + + + 8 + relative horizontal position estimate valid + + + 16 + absolute horizontal position estimate valid + + + 32 + vertical position estimate valid + + + 64 + terrain height estimate valid + + + 128 + in constant position mode + + + 256 + expected good relative horizontal position estimate - used before takeoff + + + 512 + expected good absolute horizontal position estimate - used before takeoff + + + 1024 + optical flow takeoff has been detected + + + 2048 + compensating for baro errors during takeoff + + + 4096 + compensating for baro errors during touchdown + + + 8192 + using GPS position + + + 16384 + GPS glitching is affecting navigation accuracy + + + 32768 + can use GPS for navigation + + + 65536 + has ever been healthy + + + 131072 + rejecting airspeed data + + + 262144 + dead reckoning (e.g. no position or velocity source) + + + + + Filter GPS status + + + Primary core index + + + + + EKF3 Sensor innovations (primary core) and general dumping ground + + + Time since system startup + + + EKF3 core this data is for + + + Normalised flow variance + + + Optical flow LOS rate vector innovations from the main nav filter (X-axis) + + + Optical flow LOS rate vector innovations from the main nav filter (Y-axis) + + + Optical flow LOS rate innovation from terrain offset estimator + + + Height above ground level + + + Estimated vertical position of the terrain relative to the nav filter zero datum + + + Range finder innovations + + + Measured range + + + Filter ground offset state error + + + Magnitude of angular error + + + Magnitude of velocity error + + + Magnitude of position error + + + + + EKF3 Body Frame Odometry errors + + + Time since system startup + + + EKF3 core this data is for + + + Innovation in velocity (X-axis) + + + Innovation in velocity (Y-axis) + + + Innovation in velocity (Z-axis) + + + Variance in velocity (X-axis) + + + Variance in velocity (Y-axis) + + + Variance in velocity (Z-axis) + + + + + EKF3 diagnostic data for on-ground-and-not-moving check + + + Time since system startup + + + EKF core this message instance applies to + + + True of on ground and not moving + + + Gyroscope length ratio + + + Accelerometer length ratio + + + Gyroscope rate of change ratio + + + Accelerometer rate of change ratio + + + + + EKF3 sensor selection + + + Time since system startup + + + EKF3 core this data is for + + + compass selection index + + + barometer selection index + + + GPS selection index + + + airspeed selection index + + + Source Set (primary=0/secondary=1/tertiary=2) + + + GPS good to align + + + Waiting for GPS checks to pass + + + Magnetometer fusion (0=not fusing/1=fuse yaw/2=fuse mag) + + + + + EKF3 quaternion defining the rotation from NED to XYZ (autopilot) axes + + + Time since system startup + + + EKF3 core this data is for + + + Quaternion a term + + + Quaternion b term + + + Quaternion c term + + + Quaternion d term + + + + + EKF3 timing information + + + Time since system startup + + + EKF core this message instance applies to + + + count of samples used to create this message + + + smallest IMU sample interval + + + largest IMU sample interval + + + low-passed achieved average time step rate for the EKF (minimum) + + + low-passed achieved average time step rate for the EKF (maximum) + + + accumulated measurement time interval for the delta angle (minimum) + + + accumulated measurement time interval for the delta angle (maximum) + + + accumulated measurement time interval for the delta velocity (minimum) + + + accumulated measurement time interval for the delta velocity (maximum) + + + + + EKF3 Yaw Estimator States + + + Time since system startup + + + EKF3 core this data is for + + + Tilt Error Variance from symbolic equations (rad^2) + + + Tilt Error Variance from difference method (rad^2) + + + + + EKF3 State variances (primary core) + + + Time since system startup + + + EKF3 core this data is for + + + Variance for state 0 (attitude quaternion) + + + Variance for state 1 (attitude quaternion) + + + Variance for state 2 (attitude quaternion) + + + Variance for state 3 (attitude quaternion) + + + Variance for state 4 (velocity-north) + + + Variance for state 5 (velocity-east) + + + Variance for state 6 (velocity-down) + + + Variance for state 7 (position-north) + + + Variance for state 8 (position-east) + + + Variance for state 9 (position-down) + + + Variance for state 10 (delta-angle-bias-x) + + + Variance for state 11 (delta-angle-bias-y) + + + + + more EKF3 State Variances (primary core) + + + Time since system startup + + + EKF3 core this data is for + + + Variance for state 12 (delta-angle-bias-z) + + + Variance for state 13 (delta-velocity-bias-x) + + + Variance for state 14 (delta-velocity-bias-y) + + + Variance for state 15 (delta-velocity-bias-z) + + + Variance for state 16 (Earth-frame mag-field-bias-x) + + + Variance for state 17 (Earth-frame mag-field-bias-y) + + + Variance for state 18 (Earth-frame mag-field-bias-z) + + + Variance for state 19 (body-frame mag-field-bias-x) + + + Variance for state 20 (body-frame mag-field-bias-y) + + + Variance for state 21 (body-frame mag-field-bias-z) + + + Variance for state 22 (wind-north) + + + Variance for state 23 (wind-east) + + + + + EKF Yaw Estimator States + + + Time since system startup + + + EKF core this data is for + + + GSF yaw estimate (deg) + + + GSF yaw estimate 1-Sigma uncertainty (deg) + + + Yaw estimate from individual EKF filter 0 (deg) + + + Yaw estimate from individual EKF filter 1 (deg) + + + Yaw estimate from individual EKF filter 2 (deg) + + + Yaw estimate from individual EKF filter 3 (deg) + + + Yaw estimate from individual EKF filter 4 (deg) + + + Weighting applied to yaw estimate from individual EKF filter 0 + + + Weighting applied to yaw estimate from individual EKF filter 1 + + + Weighting applied to yaw estimate from individual EKF filter 2 + + + Weighting applied to yaw estimate from individual EKF filter 3 + + + Weighting applied to yaw estimate from individual EKF filter 4 + + + + + EKF Yaw Estimator Innovations + + + Time since system startup + + + EKF core this data is for + + + North velocity innovation from individual EKF filter 0 (m/s) + + + North velocity innovation from individual EKF filter 1 (m/s) + + + North velocity innovation from individual EKF filter 2 (m/s) + + + North velocity innovation from individual EKF filter 3 (m/s) + + + North velocity innovation from individual EKF filter 4 (m/s) + + + East velocity innovation from individual EKF filter 0 (m/s) + + + East velocity innovation from individual EKF filter 1 (m/s) + + + East velocity innovation from individual EKF filter 2 (m/s) + + + East velocity innovation from individual EKF filter 3 (m/s) + + + East velocity innovation from individual EKF filter 4 (m/s) + + + + diff --git a/DataLoadAPBin/LogMessageDescriptions/Plane.xml b/DataLoadAPBin/LogMessageDescriptions/Plane.xml new file mode 100644 index 0000000..54770c7 --- /dev/null +++ b/DataLoadAPBin/LogMessageDescriptions/Plane.xml @@ -0,0 +1,12362 @@ + + + + + + IMU accelerometer data + + + Time since system startup + + + accelerometer sensor instance number + + + time since system startup this sample was taken + + + acceleration along X axis + + + acceleration along Y axis + + + acceleration along Z axis + + + + + Automatic Dependent Serveillance - Broadcast detected vehicle information + + + Time since system startup + + + Transponder address + + + Vehicle latitude + + + Vehicle longitude + + + Vehicle altitude + + + Vehicle heading + + + Vehicle horizontal velocity + + + Vehicle vertical velocity + + + Transponder squawk code + + + + + Normalised pre-mixer control surface outputs + + + Time since system startup + + + Pre-mixer value for aileron output (between -4500 and 4500) + + + Pre-mixer value for elevator output (between -4500 and 4500) + + + Pre-mixer value for throttle output (between -100 and 100) + + + Pre-mixer value for rudder output (between -4500 and 4500) + + + Pre-mixer value for flaps output (between 0 and 100) + + + Pre-mixer value for steering output (between -4500 and 4500) + + + Surface movement / airspeed scaling value + + + + + Backup AHRS data + + + Time since system startup + + + Estimated roll + + + Estimated pitch + + + Estimated yaw + + + Estimated altitude + + + Estimated latitude + + + Estimated longitude + + + Estimated attitude quaternion component 1 + + + Estimated attitude quaternion component 2 + + + Estimated attitude quaternion component 3 + + + Estimated attitude quaternion component 4 + + + + + Contents of 'position report' AIS message, see: https://gpsd.gitlab.io/gpsd/AIVDM.html#_types_1_2_and_3_position_report_class_a + + + Time since system startup + + + Message Type + + + Repeat Indicator + + + MMSI + + + Navigation Status + + + Rate of Turn (ROT) + + + Speed Over Ground (SOG) + + + Position Accuracy + + + Longitude + + + Latitude + + + Course Over Ground (COG) + + + True Heading (HDG) + + + Time Stamp + + + Maneuver Indicator + + + RAIM flag + + + Radio status + + + + + Contents of 'Base Station Report' AIS message, see: https://gpsd.gitlab.io/gpsd/AIVDM.html#_type_4_base_station_report + + + Time since system startup + + + Repeat Indicator + + + MMSI + + + Year (UTC) + + + Month (UTC) + + + Day (UTC) + + + Hour (UTC) + + + Minute (UTC) + + + Second (UTC) + + + Fix quality + + + Longitude + + + Latitude + + + Type of EPFD + + + RAIM flag + + + Radio status + + + + + Contents of 'static and voyage related data' AIS message, see: https://gpsd.gitlab.io/gpsd/AIVDM.html#_type_5_static_and_voyage_related_data + + + Time since system startup + + + Repeat Indicator + + + MMSI + + + AIS Version + + + IMO Number + + + Call Sign + + + Vessel Name + + + Ship Type + + + Dimension to Bow + + + Dimension to Stern + + + Dimension to Port + + + Dimension to Starboard + + + Position Fix Type + + + Draught + + + Destination + + + DTE + + + + + Raw AIS AVDIM messages contents, see: https://gpsd.gitlab.io/gpsd/AIVDM.html#_aivdmaivdo_sentence_layer + + + Time since system startup + + + count of fragments in the currently accumulating message + + + fragment number of this sentence + + + sequential message ID for multi-sentence messages + + + data payload + + + + + Attitude control attitude + + + Timestamp of the current Attitude loop + + + vehicle desired roll + + + achieved vehicle roll + + + vehicle desired pitch + + + achieved vehicle pitch + + + vehicle desired yaw + + + achieved vehicle yaw + + + attitude delta time + + + + + Angle of attack and Side Slip Angle values + + + Time since system startup + + + Angle of Attack calculated from airspeed, wind vector,velocity vector + + + Side Slip Angle calculated from airspeed, wind vector,velocity vector + + + + + Arming status changes + + + Time since system startup + + + true if vehicle is now armed + + + arming bitmask at time of arming + + + 2 + + + 4 + + + 8 + + + 16 + + + 32 + + + 64 + + + 128 + + + 256 + + + 512 + + + 1024 + + + 2048 + + + 4096 + + + 8192 + + + 16384 + + + 32768 + + + 65536 + + + 131072 + + + 262144 + + + 524288 + + + 1048576 + + + 2097152 + + + + + true if arm/disarm was forced + + + method used for arming + + + 0 + + + 1 + + + 2 + + + 3 + + + 4 + + + 5 + only disarm uses this... + + + 6 + only disarm uses this... + + + 7 + only disarm uses this... + + + 8 + only disarm uses this... + + + 9 + only disarm uses this... + + + 10 + only disarm uses this... + + + 11 + only disarm uses this... + + + 12 + only disarm uses this... + + + 13 + only disarm uses this... + + + 14 + only disarm uses this... + + + 15 + only disarm uses this... + + + 16 + only disarm uses this... + + + 17 + only disarm uses this... + + + 18 + only disarm uses this... + + + 19 + only disarm uses this... + + + 20 + only disarm uses this... + + + 21 + only disarm uses this... + + + 22 + only disarm uses this... + + + 23 + only disarm uses this... + + + 24 + only disarm uses this... + + + 25 + only disarm uses this... + + + 26 + only disarm uses this... + + + 27 + only disarm uses this... + + + 28 + only disarm uses this... + + + 29 + only disarm uses this... + + + 30 + only disarm uses this... + + + 31 + only disarm uses this... + + + 32 + only disarm uses this... + + + 33 + only disarm uses this... + + + 34 + + + 35 + + + 36 + + + 37 + + + 38 + + + 100 + + + + + + + Airspeed sensor data + + + Time since system startup + + + Airspeed sensor instance number + + + Current airspeed + + + Pressure difference between static and dynamic port + + + Temperature used for calculation + + + Raw pressure less offset + + + Offset from parameter + + + True if sensor is being used + + + True if sensor is healthy + + + Probability sensor is healthy + + + innovation test ratio + + + Primary instance number. If equal to I then this sensor is primary sensor + + + + + AirSim simulation data + + + Time since system startup + + + Simulation's timestamp + + + Simulation's roll + + + Simulation's pitch + + + Simulation's yaw + + + Simulated gyroscope, X-axis + + + Simulated gyroscope, Y-axis + + + Simulated gyroscope, Z-axis + + + + + More AirSim simulation data + + + Time since system startup + + + simulation's acceleration, X-axis + + + simulation's acceleration, Y-axis + + + simulation's acceleration, Z-axis + + + simulation's velocity, X-axis + + + simulation's velocity, Y-axis + + + simulation's velocity, Z-axis + + + simulation's position, X-axis + + + simulation's position, Y-axis + + + simulation's position, Z-axis + + + simulation's gps altitude + + + simulation's earth-frame speed-down + + + + + AutoTune data packet + + + Time since system startup + + + current angle + + + current angular rate + + + + + Plane AutoTune + + + Time since system startup + + + tuning axis + + + tuning state + + + control surface deflection + + + P slew rate + + + D slew rate + + + FF value single sample + + + FF value + + + P value + + + I value + + + D value + + + action taken + + + Rate maximum + + + time constant + + + + + Scale factors for attitude controller + + + Time since system startup + + + Angle P scale X + + + Angle P scale Y + + + Angle P scale Z + + + PD scale X + + + PD scale Y + + + PD scale Z + + + I scale X + + + I scale Y + + + I scale Z + + + + + Canonical vehicle attitude + + + Time since system startup + + + vehicle desired roll + + + achieved vehicle roll + + + vehicle desired pitch + + + achieved vehicle pitch + + + vehicle desired yaw + + + achieved vehicle yaw + + + active EKF type + + + + + Copter/QuadPlane AutoTune + + + Time since system startup + + + which axis is currently being tuned + + + step in autotune process + + + target angle or rate, depending on tuning step + + + measured minimum target angle or rate + + + measured maximum target angle or rate + + + new rate gain P term + + + new rate gain D term + + + new angle P term + + + maximum measured twitching acceleration + + + + + Auxiliary function invocation information + + + Time since system startup + + + ID of triggered function + + + 0 + aux switch disabled + + + 2 + flip + + + 3 + change to simple mode + + + 4 + change to RTL flight mode + + + 5 + save current position as level + + + 7 + save mission waypoint or RTL if in auto mode + + + 9 + trigger camera servo or relay + + + 10 + allow enabling or disabling rangefinder in flight which helps avoid surface tracking when you are far above the ground + + + 11 + allow enabling or disabling fence in flight + + + 12 + UNUSED + + + 13 + change to simple mode in middle, super simple at top + + + 14 + low = disabled, middle = leveled, high = leveled and limited + + + 15 + enable/disable the crop sprayer + + + 16 + change to auto flight mode + + + 17 + auto tune + + + 18 + change to LAND flight mode + + + 19 + Operate cargo grippers low=off, middle=neutral, high=on + + + 21 + Parachute enable/disable + + + 22 + Parachute release + + + 23 + Parachute disable, enable, release with 3 position switch + + + 24 + Reset auto mission to start from first command + + + 25 + enable/disable the roll and pitch rate feed forward + + + 26 + enable/disable the roll, pitch and yaw accel limiting + + + 27 + Retract Mount1 + + + 28 + Relay pin on/off (only supports first relay) + + + 29 + Landing gear controller + + + 30 + Play lost vehicle sound + + + 31 + Emergency Stop Switch + + + 32 + Motor On/Off switch + + + 33 + Brake flight mode + + + 34 + Relay2 pin on/off + + + 35 + Relay3 pin on/off + + + 36 + Relay4 pin on/off + + + 37 + change to THROW flight mode + + + 38 + enable AP_Avoidance library + + + 39 + enable precision loiter + + + 40 + enable object avoidance using proximity sensors (ie. horizontal lidar) + + + 41 + UNUSED + + + 42 + change to SmartRTL flight mode + + + 43 + enable inverted flight + + + 44 + winch enable/disable + + + 45 + winch control + + + 46 + enable RC Override + + + 47 + user function #1 + + + 48 + user function #2 + + + 49 + user function #3 + + + 50 + learn cruise throttle (Rover) + + + 51 + manual mode + + + 52 + acro mode + + + 53 + steering mode + + + 54 + hold mode + + + 55 + guided mode + + + 56 + loiter mode + + + 57 + follow mode + + + 58 + clear waypoints + + + 59 + simple mode + + + 60 + zigzag mode + + + 61 + zigzag save waypoint + + + 62 + learn compass offsets + + + 63 + rover sailboat tack + + + 64 + reverse throttle input + + + 65 + disable GPS for testing + + + 66 + Relay5 pin on/off + + + 67 + Relay6 pin on/off + + + 68 + stabilize mode + + + 69 + poshold mode + + + 70 + althold mode + + + 71 + flowhold mode + + + 72 + circle mode + + + 73 + drift mode + + + 74 + Sailboat motoring 3pos + + + 75 + Surface tracking upwards or downwards + + + 76 + Standby mode + + + 77 + takeoff + + + 78 + control RunCam device + + + 79 + control RunCam OSD + + + 80 + align visual odometry camera's attitude to AHRS + + + 81 + disarm vehicle + + + 82 + disable, enable and force Q assist + + + 83 + zigzag auto switch + + + 84 + enable / disable airmode for copter + + + 85 + generator control + + + 86 + disable terrain following in CRUISE/FBWB modes + + + 87 + select CROW mode for diff spoilers;high disables,mid forces progressive + + + 88 + three-position switch to set soaring mode + + + 89 + force flare, throttle forced idle, pitch to LAND_PITCH_DEG, tilts up + + + 90 + change EKF data source set between primary, secondary and tertiary + + + 91 + calibrate airspeed ratio + + + 92 + Fly-By-Wire-A + + + 93 + used in separate branch MISSION_RELATIVE + + + 94 + VTX power level + + + 95 + enables FBWA taildragger takeoff mode. Once this feature is enabled it will stay enabled until the aircraft goes above TKOFF_TDRAG_SPD1 airspeed, changes mode, or the pitch goes above the initial pitch when this is engaged or goes below 0 pitch. When enabled the elevator will be forced to TKOFF_TDRAG_ELEV. This option allows for easier takeoffs on taildraggers in FBWA mode, and also makes it easier to test auto-takeoff steering handling in FBWA. + + + 96 + trigger re-reading of mode switch + + + 97 + flag for windvane direction offset input, used with windvane type 2 + + + 98 + mode training + + + 99 + AUTO RTL via DO_LAND_START + + + 100 + disable first IMU (for IMU failure testing) + + + 101 + disable second IMU (for IMU failure testing) + + + 102 + Momentary switch to cycle camera modes + + + 103 + trigger lane switch attempt + + + 104 + trigger yaw reset attempt + + + 105 + disable GPS yaw for testing + + + 106 + equivalent to AIRSPEED_USE 0 + + + 107 + fixed wing auto tune + + + 108 + QRTL mode + + + 109 + use Custom Controller + + + 110 + disable third IMU (for IMU failure testing) + + + 111 + allows for manually running starter + + + 112 + change AHRS_EKF_TYPE + + + 113 + Retract Mount2 + + + 150 + CRUISE mode + + + 151 + Turtle mode - flip over after crash + + + 152 + reset simple mode reference heading to current + + + 153 + arm or disarm vehicle + + + 154 + arm or disarm vehicle enabling airmode + + + 155 + trim to current servo and RC + + + 156 + clear torqeedo error + + + 157 + Force long FS action to FBWA for landing out of range + + + 158 + optical flow calibration + + + 159 + enable or disable land detection for GPS based manual modes preventing land detection and maintainting set_throttle_mix_max + + + 160 + enable/disable weathervaning + + + 161 + initialize turbine start sequence + + + 162 + FFT notch tuning function + + + 163 + Mount earth frame yaw lock forced on all axes, for all mounts + + + 164 + Pauses logging if under logging rate control + + + 165 + ARM on high, MOTOR_ESTOP on low + + + 166 + start recording on high, stop recording on low + + + 167 + camera zoom high = zoom in, middle = hold, low = zoom out + + + 168 + camera manual focus. high = long shot, middle = stop focus, low = close shot + + + 169 + camera auto focus + + + 170 + QuadPlane QStabilize mode + + + 171 + Calibrate compasses (disarmed only) + + + 172 + Battery MPPT Power enable. high = ON, mid = auto (controlled by mppt/batt driver), low = OFF. This effects all MPPTs. + + + 173 + Abort Glide-slope or VTOL landing during payload place or do_land type mission items + + + 174 + camera image tracking + + + 175 + camera lens selection + + + 176 + force enabled VTOL forward throttle method + + + 177 + mount LRF enable/disable + + + 178 + e.g. pause movement towards waypoint + + + 179 + AP_ICEngine start stop + + + 180 + auto tune tuning switch to test or revert gains + + + 181 + quicktune 3 position switch + + + 182 + in-flight AHRS autotrim + + + 183 + Fixed Wing AUTOLAND Mode + + + 184 + system ID as an aux switch + + + 185 + mount lock modes for roll and pitch axes, for all mounts that support it + + + 186 + Lock mount target to current ROI seen and switch mount to GPS Targeting mode + + + 201 + roll input + + + 202 + pitch input + + + 203 + throttle pilot input + + + 204 + yaw pilot input + + + 207 + mainsail input + + + 208 + flap input + + + 209 + VTOL manual forward throttle + + + 210 + manual airbrake control + + + 211 + walking robot height input + + + 212 + mount1 roll input + + + 213 + mount1 pitch input + + + 214 + mount1 yaw input + + + 215 + mount2 roll input + + + 216 + mount3 pitch input + + + 217 + mount4 yaw input + + + 218 + allows for throttle on slider + + + 219 + use a transmitter knob or slider for in-flight tuning + + + 220 + use another transmitter knob or slider for in-flight tuning + + + 300 + + + 301 + + + 302 + + + 303 + + + 304 + + + 305 + + + 306 + + + 307 + + + 308 + + + 309 + + + 310 + + + 311 + + + 312 + + + 313 + + + 314 + + + 315 + + + 316 + emergency scripting disablement + + + 317 + + + + + switch position when function triggered + + + 0 + indicates auxiliary switch is in the low position (pwm <1200) + + + 1 + indicates auxiliary switch is in the middle position (pwm >1200, <1800) + + + 2 + indicates auxiliary switch is in the high position (pwm >1800) + + + + + source of auxiliary function invocation + + + 0 + Source index is RC channel index + + + 1 + Source index is RC channel index + + + 2 + Source index is button index + + + 3 + Source index is MAVLink channel number + + + 4 + Source index is mission item index + + + 5 + Source index is not used (always 0) + + + + + index within source. 0 indexed. Invalid for scripting. + + + true if function was successful + + + + + Barometer dynamic data + + + Time since system startup + + + barometer sensor instance number + + + calculated dynamic pressure in the bodyframe X-axis + + + calculated dynamic pressure in the bodyframe Y-axis + + + calculated dynamic pressure in the bodyframe Z-axis + + + + + Gathered Barometer data + + + Time since system startup + + + barometer sensor instance number + + + calculated altitude + + + altitude AMSL + + + measured atmospheric pressure + + + measured atmospheric temperature + + + derived climb rate from primary barometer + + + time last sample was taken + + + raw adjustment of barometer altitude, zeroed on calibration, possibly set by GCS + + + temperature on ground, specified by parameter or measured while on ground + + + true if barometer is considered healthy + + + compensated atmospheric pressure + + + + + Gathered battery data + + + Time since system startup + + + battery instance number + + + measured voltage + + + estimated resting voltage + + + measured current + + + consumed Ah, current * time + + + consumed Wh, energy this battery has expended + + + measured temperature + + + estimated battery resistance + + + remaining percentage + + + health + + + state of health percentage. 0 if unknown + + + + + BlackBox data1 + + + Time since system startup + + + Latitude + + + Longitude + + + altitude above sea level + + + euler roll + + + euler pitch + + + euler yaw + + + velocity north + + + velocity east + + + velocity down + + + + + BlackBox data2 + + + Time since system startup + + + X axis gyro + + + Y axis gyro + + + Z axis gyro + + + accel X axis (front) + + + accel Y axis (right) + + + accel Z axis (down) + + + + + Battery cell voltage information + + + Time since system startup + + + battery instance number + + + battery voltage + + + first cell voltage + + + second cell voltage + + + third cell voltage + + + fourth cell voltage + + + fifth cell voltage + + + sixth cell voltage + + + seventh cell voltage + + + eighth cell voltage + + + ninth cell voltage + + + tenth cell voltage + + + eleventh cell voltage + + + twelfth cell voltage + + + + + Battery cell voltage information + + + Time since system startup + + + battery instance number + + + thirteenth cell voltage + + + fourteenth cell voltage + + + + + Beacon information + + + Time since system startup + + + True if beacon sensor is healthy + + + Number of beacons being used + + + Distance to first beacon + + + Distance to second beacon + + + Distance to third beacon + + + Distance to fourth beacon + + + Calculated beacon position, x-axis + + + Calculated beacon position, y-axis + + + Calculated beacon position, z-axis + + + + + CANFD Frame + + + Time since system startup + + + bus number + + + frame identifier + + + data length code + + + data 0 + + + data 1 + + + data 2 + + + data 3 + + + data 4 + + + data 5 + + + data 6 + + + data 7 + + + + + Camera shutter information + + + Time since system startup + + + Instance number + + + Image number + + + milliseconds since start of GPS week + + + weeks since 5 Jan 1980 + + + current latitude + + + current longitude + + + current altitude + + + current altitude relative to home + + + altitude as reported by GPS + + + current vehicle roll + + + current vehicle pitch + + + current vehicle yaw + + + + + Info from GetNodeInfo request + + + Time since system startup + + + Driver index + + + Node ID + + + Hardware ID, part 1 + + + Hardware ID, part 2 + + + Name string + + + major revision id + + + minor revision id + + + AP_Periph git hash + + + + + CAN Frame + + + Time since system startup + + + bus number + + + frame identifier + + + data length code + + + byte 0 + + + byte 1 + + + byte 2 + + + byte 3 + + + byte 4 + + + byte 5 + + + byte 6 + + + byte 7 + + + + + CAN Bus Statistics + + + Time since system startup + + + driver index + + + transmit success count + + + transmit request count + + + transmit reject count + + + transmit overflow count + + + transmit timeout count + + + transmit abort count + + + receive count + + + receive overflow count + + + receive error count + + + bus offset error count + + + ESC successful send count + + + Servo successful send count + + + ESC/Servo failed-to-send count + + + + + Custom Controller data + + + Time since system startup + + + controller type + + + 0 + + + 1 + + + 2 + + + + + true if controller is active + + + + + Uploaded mission command information + + + Time since system startup + + + Total number of mission commands + + + This command's offset in mission + + + Command type + + + Parameter 1 + + + Parameter 2 + + + Parameter 3 + + + Parameter 4 + + + Command latitude + + + Command longitude + + + Command altitude + + + Frame used for position + + + + + Servo feedback data + + + Time since system startup + + + Servo number this data relates to + + + Current servo position + + + Force being applied + + + Current servo movement speed + + + Amount of rated power being applied + + + commanded servo position + + + Voltage + + + Current + + + motor temperature + + + PCB temperature + + + error flags + + + + + Control Tuning information + + + Time since system startup + + + desired roll + + + achieved roll + + + desired pitch assuming pitch trims are already applied + + + achieved pitch assuming pitch trims are already applied,ie "0deg" is level flight trimmed pitch attitude as shown on artificial horizon level line. + + + scaled output throttle + + + scaled output rudder + + + demanded speed-height-controller throttle + + + airspeed estimate (or measurement if airspeed sensor healthy and ARSPD_USE>0) + + + airspeed type ( old estimate or source of new estimate) + + + 0 + + + 1 + + + 2 + + + 3 + + + 4 + + + + + equivalent to true airspeed ratio + + + groundspeed undershoot when flying with minimum groundspeed + + + + + DCM Estimator Data + + + Time since system startup + + + estimated roll + + + estimated pitch + + + estimated yaw + + + lowest estimated gyro drift error + + + difference between measured yaw and DCM yaw estimate + + + wind velocity, to-the-North component + + + wind velocity, to-the-East component + + + wind velocity, Up-to-Down component + + + synthetic (equivalent) airspeed + + + + + DataFlash-Over-MAVLink statistics + + + Time since system startup + + + Current block number + + + Number of times we rejected a write to the backend + + + Number of blocks sent from the retry queue + + + Number of resends of unacknowledged data made + + + Average number of blocks on the free list + + + Minimum number of blocks on the free list + + + Maximum number of blocks on the free list + + + Average number of blocks on the pending list + + + Minimum number of blocks on the pending list + + + Maximum number of blocks on the pending list + + + Average number of blocks on the sent list + + + Minimum number of blocks on the sent list + + + Maximum number of blocks on the sent list + + + + + Onboard logging statistics + + + Time since system startup + + + Number of times we rejected a write to the backend + + + Current block number + + + Current write offset + + + Minimum free space in write buffer in last time period + + + Maximum free space in write buffer in last time period + + + Average free space in write buffer in last time period + + + + + Deepstall Landing data + + + Time since system startup + + + Deepstall landing stage + + + Target heading + + + Landing point latitude + + + Landing point longitude + + + Landing point altitude + + + Crosstrack error + + + Expected travel distance vehicle will travel from this point + + + L1 controller crosstrack integrator value + + + wind estimate loiter angle flown + + + Deepstall steering PID desired value + + + Deepstall steering PID Proportional response component + + + Deepstall steering PID Integral response component + + + Deepstall steering PID Derivative response component + + + + + External AHRS data + + + Time since system startup + + + euler roll + + + euler pitch + + + euler yaw + + + velocity north + + + velocity east + + + velocity down + + + latitude + + + longitude + + + altitude AMSL + + + nav status flags + + + + + External AHRS variances + + + Time since system startup + + + velocity variance + + + position variance + + + height variance + + + magnetic variance, X + + + magnetic variance, Y + + + magnetic variance, Z + + + true airspeed variance + + + + + EFI per-cylinder information + + + Time since system startup + + + Cylinder this data belongs to + + + Ignition timing + + + Injection time + + + Cylinder head temperature + + + Exhaust gas temperature + + + Estimated lambda coefficient (dimensionless ratio) + + + Cylinder2 head temperature + + + Cylinder2 Exhaust gas temperature + + + Index of the publishing ECU + + + + + Status received from ESCs via Extended DShot telemetry v2 + + + microseconds since system startup + + + ESC instance number + + + current stress level (commutation effort), scaled to [0..255] + + + maximum stress level (commutation effort) since arming, scaled to [0..15] + + + status bits + + + 1 + true if the message contains up-to-date stress data + + + 2 + true if the message contains up-to-date status data + + + 4 + true if the last status had the "alert" bit (e.g. demag) + + + 8 + true if the last status had the "warning" bit (e.g. desync) + + + 16 + true if the last status had the "error" bit (e.g. stall) + + + + + + + Electronic Fuel Injection system data + + + Time since system startup + + + Reported engine load + + + Reported engine RPM + + + Spark Dwell Time + + + Atmospheric pressure + + + Intake manifold pressure + + + Intake manifold temperature + + + Engine Coolant Temperature + + + Oil Pressure + + + Oil temperature + + + Fuel Pressure + + + Fuel Consumption Rate + + + Consumed fuel volume + + + Throttle Position + + + Index of the publishing ECU + + + + + Electronic Fuel Injection system data - redux + + + Time since system startup + + + True if EFI is healthy + + + Engine state + + + General error + + + Crankshaft sensor status + + + Temperature status + + + Fuel pressure status + + + Oil pressure status + + + Detonation status + + + Misfire status + + + Debris status + + + Spark plug usage + + + Index of the publishing ECU + + + + + Electronic Fuel Injection data - Hirth specific Status information + + + Time since system startup + + + Error Excess Temperature Bitfield + + + 1 + true if CHT1 is too low + + + 2 + true if CHT1 is too high + + + 4 + true if CHT1 Enrichment is active + + + 8 + true if CHT2 is too low + + + 16 + true if CHT2 is too high + + + 32 + true if CHT2 Enrichment is active + + + 64 + true if EGT1 is too low + + + 128 + true if EGT1 is too high + + + 256 + true if EGT1 Enrichment is active + + + 512 + true if EGT2 is too low + + + 1024 + true if EGT2 is too high + + + 2048 + true if EGT2 Enrichment is active + + + + + Sensor Status Bitfield + + + 2 + true if engine temperature sensor is OK + + + 4 + true if air temperature sensor is OK + + + 8 + true if intake air pressure sensor is OK + + + 16 + true if throttle sensor is OK + + + + + CRC failure count + + + ACK failure count + + + Uptime between 2 messages + + + Throttle output as received by the engine + + + Modified throttle_to_hirth output sent to the engine + + + + + Specifically coded error messages + + + Time since system startup + + + Subsystem in which the error occurred + + + 1 + + + 2 + + + 3 + + + 4 + not used + + + 5 + + + 6 + + + 7 + not used + + + 8 + + + 9 + + + 10 + + + 11 + + + 12 + + + 13 + + + 14 + not used + + + 15 + + + 16 + + + 17 + + + 18 + + + 19 + + + 20 + + + 21 + + + 22 + + + 23 + + + 24 + + + 25 + + + 26 + + + 27 + + + 28 + + + 29 + + + 30 + + + 31 + + + + + Subsystem-specific error code + + + + + Feedback received from ESCs + + + microseconds since system startup + + + ESC instance number + + + reported motor rotation rate + + + reported motor rotation rate without slew adjustment + + + Perceived input voltage for the ESC + + + Perceived current through the ESC + + + ESC temperature in centi-degrees C + + + current consumed total mAh + + + measured motor temperature in centi-degrees C + + + error rate + + + + + ESC extended telemetry data + + + Time since system startup + + + starts from 0 + + + input duty cycle in percent + + + output duty cycle in percent + + + manufacturer-specific status flags + + + Power percentage + + + + + Specifically coded event messages + + + Time since system startup + + + Event identifier + + + 10 + + + 11 + + + 15 + + + 17 + + + 18 + + + 19 + + + 21 + + + 22 + + + 25 + + + 26 + + + 27 + + + 28 + + + 29 + + + 30 + + + 31 + + + 32 + + + 33 + + + 34 + + + 35 + + + 36 + + + 37 + + + 38 + + + 39 + + + 41 + + + 42 + + + 43 + + + 44 + + + 45 + + + 46 + + + 47 + + + 49 + + + 50 + + + 51 + + + 52 + + + 53 + + + 54 + + + 55 + + + 56 + + + 57 + + + 58 + Heli only + + + 59 + Heli only + + + 60 + + + 61 + + + 62 + + + 63 + + + 64 + + + 65 + + + 66 + + + 67 + + + 71 + + + 72 + + + 73 + + + 74 + + + 75 + + + 76 + + + 77 + + + 78 + + + 79 + + + 80 + + + 81 + + + 82 + + + 83 + + + 85 + + + 86 + + + 87 + + + 90 + + + 163 + + + 164 + + + 165 + + + 166 + + + + + + + Filter Center Message - per motor + + + microseconds since system startup + + + instance + + + total number of active harmonic notches + + + First harmonic centre frequency for motor 1 + + + First harmonic centre frequency for motor 2 + + + First harmonic centre frequency for motor 3 + + + First harmonic centre frequency for motor 4 + + + First harmonic centre frequency for motor 5 + + + First harmonic centre frequency for motor 6 + + + Second harmonic centre frequency for motor 1 + + + Second harmonic centre frequency for motor 2 + + + Second harmonic centre frequency for motor 3 + + + Second harmonic centre frequency for motor 4 + + + Second harmonic centre frequency for motor 5 + + + Second harmonic centre frequency for motor 6 + + + + + Filter Center Message + + + microseconds since system startup + + + instance + + + notch centre frequency + + + 2nd harmonic frequency + + + + + Fence status - development diagnostic message + + + Time since system startup + + + bitmask of enabled fences + + + bitmask of automatically enabled fences + + + bitmask of configured-in-parameters fences + + + bitmask of enabled fences + + + bitmask of currently disabled fences + + + current vehicle altitude + + + + + File data + + + File name + + + Offset into the file of this block + + + Length of this data block + + + File data of this block + + + + + https://ardupilot.org/dev/docs/code-overview-adding-a-new-log-message.html + Message defining the format of messages in this file + + + unique-to-this-log identifier for message being defined + + + the number of bytes taken up by this message (including all headers) + + + name of the message being defined + + + character string defining the C-storage-type of the fields in this message + + + the labels of the message being defined + + + + + Message defining units and multipliers used for fields of other messages + + + Time since system startup + + + numeric reference to associated FMT message + + + each character refers to a UNIT message. The unit at an offset corresponds to the field at the same offset in FMT.Format + + + each character refers to a MULT message. The multiplier at an offset corresponds to the field at the same offset in FMT.Format + + + + + currently loaded Geo Fence points + + + Time since system startup + + + total number of stored items + + + index in current sequence + + + point type + + + point latitude + + + point longitude + + + vertex cound in polygon if applicable + + + radius of circle if applicable + + + + + Follow library diagnostic data + + + Time since system startup (microseconds) + + + Target latitude (degrees * 1E7) + + + Target longitude (degrees * 1E7) + + + Target absolute altitude (centimeters) + + + Target velocity, North (m/s) + + + Target velocity, East (m/s) + + + Target velocity, Down (m/s) + + + Vehicle estimated latitude (degrees * 1E7) + + + Vehicle estimated longitude (degrees * 1E7) + + + Vehicle estimated altitude (centimeters) + + + Vehicle estimated altitude Frame + + + + + Filter Tuning Message - per motor + + + microseconds since system startup + + + instance + + + number of active harmonic notches + + + desired harmonic notch centre frequency for motor 1 + + + desired harmonic notch centre frequency for motor 2 + + + desired harmonic notch centre frequency for motor 3 + + + desired harmonic notch centre frequency for motor 4 + + + desired harmonic notch centre frequency for motor 5 + + + desired harmonic notch centre frequency for motor 6 + + + desired harmonic notch centre frequency for motor 7 + + + desired harmonic notch centre frequency for motor 8 + + + desired harmonic notch centre frequency for motor 9 + + + desired harmonic notch centre frequency for motor 10 + + + desired harmonic notch centre frequency for motor 11 + + + desired harmonic notch centre frequency for motor 12 + + + + + FFT Filter Tuning + + + microseconds since system startup + + + peak noise frequency as an energy-weighted average of roll and pitch peak frequencies + + + bandwidth of weighted peak frequency where edges are determined by FFT_ATT_REF + + + signal-to-noise ratio on the roll axis + + + signal-to-noise ratio on the pitch axis + + + signal-to-noise ratio on the yaw axis + + + harmonic fit on roll of the highest noise peak to the second highest noise peak + + + harmonic fit on pitch of the highest noise peak to the second highest noise peak + + + harmonic fit on yaw of the highest noise peak to the second highest noise peak + + + FFT health, X-axis + + + FFT health, Y-axis + + + FFT health, Z-axis + + + FFT cycle time + + + + + FFT Noise Frequency Peak + + + microseconds since system startup + + + peak id where 0 is the centre peak, 1 is the lower shoulder and 2 is the upper shoulder + + + noise frequency of the peak on roll + + + noise frequency of the peak on pitch + + + noise frequency of the peak on yaw + + + bandwidth of the peak frequency on roll where edges are determined by FFT_ATT_REF + + + bandwidth of the peak frequency on pitch where edges are determined by FFT_ATT_REF + + + bandwidth of the peak frequency on yaw where edges are determined by FFT_ATT_REF + + + signal-to-noise ratio on the roll axis + + + signal-to-noise ratio on the pitch axis + + + signal-to-noise ratio on the yaw axis + + + power spectral density bin energy of the peak on roll + + + power spectral density bin energy of the peak on roll + + + power spectral density bin energy of the peak on roll + + + + + Additional FFT Noise Frequency Peak + + + microseconds since system startup + + + update axis + + + Peak 1 frequency + + + Peak 2 frequency + + + Peak 3 Frequency + + + Peak 1 noise bandwidth + + + Peak 2 noise bandwidth + + + Peak 3 noise bandwidth + + + Peak 1 Maximum energy + + + Peak 2 Maximum energy + + + Peak 3 Maximum energy + + + + + Filter Tuning Message + + + microseconds since system startup + + + instance + + + desired harmonic notch centre frequency + + + + + Forward Throttle calculations + + + Time since system startup + + + forward throttle scaler + + + quadplane forward pitch limit + + + navigation pitch lower limit + + + demanded navigation pitch + + + quadplane forward throttle + + + upper limit for navigation pitch + + + + + Simulated Glider Angles and coefficients + + + Time since system startup + + + alpha angle + + + beta angle + + + lift coefficent + + + roll coffecient + + + yaw coefficient + + + + + GPS accuracy information + + + Time since system startup + + + GPS instance number + + + vertical dilution of precision + + + horizontal position accuracy + + + vertical position accuracy + + + speed accuracy + + + yaw accuracy + + + true if vertical velocity is available + + + time since system startup this sample was taken + + + system time delta between the last two reported positions + + + altitude above WGS-84 ellipsoid; INT32_MIN (-2147483648) if unknown + + + RTCM fragments used + + + RTCM fragments discarded + + + + + Information received from GNSS systems attached to the autopilot + + + Time since system startup + + + GPS instance number + + + GPS Fix type; 2D fix, 3D fix etc. + + + 0 + No GPS connected/detected + + + 1 + Receiving valid GPS messages but no lock + + + 2 + Receiving valid messages and 2D lock + + + 3 + Receiving valid messages and 3D lock + + + 4 + Receiving valid messages and 3D lock with differential improvements + + + 5 + Receiving valid messages and 3D RTK Float + + + 6 + Receiving valid messages and 3D RTK Fixed + + + + + milliseconds since start of GPS Week + + + weeks since 5 Jan 1980 + + + number of satellites visible + + + horizontal dilution of precision + + + latitude + + + longitude + + + altitude + + + ground speed + + + ground course + + + vertical speed + + + vehicle yaw + + + boolean value indicating whether this GPS is in use + + + + + GPS Yaw + + + Time since system startup + + + instance + + + reported heading,deg + + + antenna separation,m + + + vertical antenna separation,m + + + minimum tolerable vertical antenna separation,m + + + maximum tolerable vertical antenna separation,m + + + 1 if have yaw + + + + + Raw uBlox data + + + Time since system startup + + + receiver TimeOfWeek measurement + + + GPS week + + + number of space vehicles seen + + + space vehicle number of first vehicle + + + carrier phase measurement + + + pseudorange measurement + + + Doppler measurement + + + measurement quality index + + + carrier-to-noise density ratio + + + loss of lock indicator + + + + + Raw uBlox data - header + + + Time since system startup + + + receiver TimeOfWeek measurement + + + GPS week + + + GPS leap seconds + + + number of space-vehicle measurements to follow + + + receiver tracking status bitfield + + + + + Raw uBlox data - space-vehicle data + + + Time since system startup + + + Pseudorange measurement + + + Carrier phase measurement + + + Doppler measurement + + + GNSS identifier + + + Satellite identifier + + + GLONASS frequency slot + + + carrier phase locktime counter + + + carrier-to-noise density ratio + + + estimated pseudorange measurement standard deviation + + + estimated carrier phase measurement standard deviation + + + estimated Doppler measurement standard deviation + + + tracking status bitfield + + + + + IMU gyroscope data + + + Time since system startup + + + gyroscope sensor instance number + + + time since system startup this sample was taken + + + measured rotation rate about X axis + + + measured rotation rate about Y axis + + + measured rotation rate about Z axis + + + + + IMU Heater data + + + Time since system startup + + + Current IMU temperature + + + Target IMU temperature + + + Proportional portion of response + + + Integral portion of response + + + Controller output to heating element + + + + + Helicopter related messages + + + Time since system startup + + + Instance, 0=Main, 1=Tail + + + Desired rotor speed + + + Estimated rotor speed + + + Governor Output + + + Throttle output + + + throttle ramp up + + + RSC state + + + + + Hygrometer data + + + Time since system startup + + + sensor ID + + + percentage humidity + + + temperature in degrees C + + + + + ICM20789 diagnostics + + + Time since system startup + + + raw temperature from sensor + + + raw pressure from sensor + + + pressure + + + temperature + + + + + https://ardupilot.org/copter/docs/common-ie24-fuelcell.html + Intelligent Energy Fuel Cell generator (legacy protocol) + + + Time since system startup + + + Fuel remaining + + + stack power module power draw + + + output power + + + error codes + + + 1 + Minor internal error is to be ignored + + + 10 + + + 11 + + + 20 + + + 21 + + + 30 + + + 31 + + + 32 + + + 33 + + + 40 + + + + + + + https://ardupilot.org/copter/docs/common-ie24-fuelcell.html + Intelligent Energy Fuel Cell generator + + + Time since system startup + + + Fuel remaining + + + Inlet pressure + + + battery voltage + + + output power + + + stack power module power draw + + + fault number + + + battery power draw + + + generator state + + + 0 + + + 1 + + + 2 + + + 3 + + + 4 + + + + + error code + + + 1 + Minor internal error is to be ignored + + + 10 + + + 11 + + + 20 + + + 21 + + + 30 + + + 31 + + + 32 + + + 33 + + + 40 + + + + + sub-error code + + + + + InertialLabs AHRS data1 + + + Time since system startup + + + GPS INS time (round) + + + Gyro X + + + Gyro Y + + + Gyro z + + + Accelerometer X + + + Accelerometer Y + + + Accelerometer Z + + + + + InertialLabs AHRS data2 + + + Time since system startup + + + GPS INS time (round) + + + Magnetometer X + + + Magnetometer Y + + + Magnetometer Z + + + + + InertialLabs AHRS data3 + + + Time since system startup + + + GPS INS time (round) + + + Static pressure + + + Differential pressure + + + Temperature + + + Baro altitude + + + true airspeed + + + Wind velocity north + + + Wind velocity east + + + Wind velocity down + + + Air Data Unit status + + + + + InertialLabs AHRS data4 + + + Time since system startup + + + GNSS Position timestamp + + + GPS Week + + + Number of satellites + + + Indicator of new update of GPS data + + + GNSS Latitude + + + GNSS Longitude + + + GNSS Altitude + + + GNSS Track over ground + + + GNSS Horizontal speed + + + GNSS Vertical speed + + + + + InertialLabs AHRS data5 + + + Time since system startup + + + GNSS Position timestamp + + + fix type + + + GNSS spoofing status + + + GNSS jamming status + + + GNSS Info1 + + + GNSS Info2 + + + GNSS Angles position type + + + + + InertialLabs AHRS data6 + + + Time since system startup + + + GNSS Position timestamp + + + GNSS Heading timestamp + + + GNSS Heading + + + GNSS Pitch + + + GNSS GDOP + + + GNSS PDOP + + + GNSS HDOP + + + GNSS VDOP + + + GNSS TDOP + + + + + InertialLabs AHRS data7 + + + Time since system startup + + + GPS INS time (round) + + + euler roll + + + euler pitch + + + euler yaw + + + velocity north + + + velocity east + + + velocity down + + + latitude + + + longitude + + + altitude MSL + + + USW1 + + + USW2 + + + Supply voltage + + + + + InertialLabs AHRS data8 + + + Time since system startup + + + GPS INS time (round) + + + position variance north + + + position variance east + + + position variance down + + + velocity variance north + + + velocity variance east + + + velocity variance down + + + + + Inertial Measurement Unit data + + + Time since system startup + + + IMU sensor instance number + + + measured rotation rate about X axis + + + measured rotation rate about Y axis + + + measured rotation rate about Z axis + + + acceleration along X axis + + + acceleration along Y axis + + + acceleration along Z axis + + + gyroscope error count + + + accelerometer error count + + + IMU temperature + + + gyroscope health + + + accelerometer health + + + gyroscope measurement rate + + + accelerometer measurement rate + + + + + IOMCU diagnostic information + + + Time since system startup + + + Status Read error count (zeroed on successful read) + + + Free memory + + + IOMCU uptime + + + Number of packets received by IOMCU + + + Protocol failures on MCU side + + + Reported number of failures on IOMCU side + + + Number of delayed packets received by MCU + + + + + IMU Register unexpected value change + + + Time since system startup + + + bus ID + + + device register bank + + + device register + + + unexpected value + + + + + InertialSensor Batch Logging Data + + + Time since system startup + + + batch sequence number + + + sample sequence number + + + x-axis sample value + + + y-axis sample value + + + z-axis sample value + + + + + InertialSensor Batch Logging Header + + + Time since system startup + + + batch sequence number + + + indicates if this is accel or gyro data + + + IMU sensor instance + + + multiplier to be applied to samples in this batch + + + samples in this batch + + + timestamp of first sample + + + rate at which samples have been collected + + + + + Log data received from JSON simulator + + + Time since system startup (us) + + + Simulation's timestamp (s) + + + Simulation's roll (rad) + + + Simulation's pitch (rad) + + + Simulation's yaw (rad) + + + Simulated gyroscope, X-axis (rad/sec) + + + Simulated gyroscope, Y-axis (rad/sec) + + + Simulated gyroscope, Z-axis (rad/sec) + + + + + Log data received from JSON simulator + + + Time since system startup (us) + + + simulation's velocity, North-axis (m/s) + + + simulation's velocity, East-axis (m/s) + + + simulation's velocity, Down-axis (m/s) + + + simulation's acceleration, X-axis (m/s^2) + + + simulation's acceleration, Y-axis (m/s^2) + + + simulation's acceleration, Z-axis (m/s^2) + + + simulation's acceleration, North (m/s^2) + + + simulation's acceleration, East (m/s^2) + + + simulation's acceleration, Down (m/s^2) + + + + + Slope Landing data + + + Time since system startup + + + progress through landing sequence + + + Landing flags + + + Slope-specific landing flags + + + Slope to landing point + + + Initial slope to landing point + + + Rangefinder correction + + + Height for flare timing. + + + + + Landing gear information + + + Time since system startup + + + Current landing gear state + + + -1 + + + 0 + + + 1 + + + 2 + + + 3 + + + + + Weight on wheels state + + + -1 + + + 0 + + + 1 + + + + + + + Gathered Loweheiser EFI/Governor telemetry + + + Time since system startup + + + target system ID + + + target component ID + + + command + + + efi index + + + desired engine state (0:EFI off 1:EFI on) + + + desired governor state (0:Governor off 1:Governor on) + + + manual throttle value + + + desired electric start + + + + + Gathered Loweheiser EFI/Governor telemetry + + + Time since system startup + + + EFI/Gov sensor instance number + + + battery voltage + + + battery current + + + generator current + + + throttle input + + + EFI battery voltage + + + generator RPM + + + EFI pulse-width + + + fuel flow + + + fuel consumed + + + EFI pressure + + + EFI manifold air temperature + + + cylinder head temperature + + + throttle position sensor + + + + + Information received from compasses + + + Time since system startup + + + magnetometer sensor instance number + + + magnetic field strength in body frame + + + magnetic field strength in body frame + + + magnetic field strength in body frame + + + magnetic field offset in body frame + + + magnetic field offset in body frame + + + magnetic field offset in body frame + + + motor interference magnetic field offset in body frame + + + motor interference magnetic field offset in body frame + + + motor interference magnetic field offset in body frame + + + true if the compass is considered healthy + + + time measurement was taken + + + + + Magnetometer high resolution data + + + Time since system startup + + + CAN node + + + sensor ID on node + + + CAN bus + + + X axis field + + + y axis field + + + z axis field + + + + + GCS MAVLink link statistics + + + Time since system startup + + + mavlink channel number + + + transmitted packet count + + + received packet count + + + perceived number of packets we never received + + + compact representation of some state of the channel + + + 1 + + + 2 + + + 4 + + + 8 + + + 16 + + + + + stream slowdown is the number of ms being added to each message to fit within bandwidth + + + times buffer was full when a message was going to be sent + + + time MAV_GCS_SYSID heartbeat (or manual control) last seen + + + + + MAVLink command we have just executed + + + Time since system startup + + + target system for command + + + target component for command + + + source system for command + + + source component for command + + + command frame + + + mavlink command enum value + + + first parameter from mavlink packet + + + second parameter from mavlink packet + + + third parameter from mavlink packet + + + fourth parameter from mavlink packet + + + X coordinate from mavlink packet + + + Y coordinate from mavlink packet + + + Z coordinate from mavlink packet + + + command result being returned from autopilot + + + true if this command arrived via a COMMAND_LONG rather than COMMAND_INT + + + + + MCU voltage and temprature monitering + + + Time since system startup + + + Temperature + + + Voltage + + + Voltage min + + + Voltage max + + + + + Executed mission command information; emitted when we start to run an item + + + Time since system startup + + + Total number of mission commands + + + This command's offset in mission + + + Command type + + + Parameter 1 + + + Parameter 2 + + + Parameter 3 + + + Parameter 4 + + + Command latitude + + + Command longitude + + + Command altitude + + + Frame used for position + + + + + MMC3416 compass data + + + Time since system startup + + + new measurement X axis + + + new measurement Y axis + + + new measurement Z axis + + + new offset X axis + + + new offset Y axis + + + new offset Z axis + + + + + Mount's desired and actual roll, pitch and yaw angles + + + Time since system startup + + + Instance number + + + Mount mode + + + Desired roll + + + Actual roll + + + Desired pitch + + + Actual pitch + + + Desired yaw in body frame + + + Actual yaw in body frame + + + Desired yaw in earth frame + + + Actual yaw in earth frame + + + Rangefinder distance + + + + + vehicle control mode information + + + Time since system startup + + + vehicle-specific mode number + + + alias for Mode + + + reason for entering this mode; enumeration value + + + 0 + + + 1 + + + 2 + + + 3 + + + 4 + + + 5 + + + 6 + + + 7 + + + 8 + + + 9 + + + 10 + + + 11 + + + 12 + + + 13 + + + 14 + + + 15 + + + 16 + + + 17 + + + 18 + + + 19 + + + 20 + + + 21 + + + 22 + + + 23 + + + 24 + + + 25 + general failsafes, prefer specific failsafes over this as much as possible + + + 26 + + + 27 + + + 28 + + + 29 + + + 30 + + + 31 + + + 32 + + + 33 + + + 34 + + + 35 + + + 36 + + + 37 + + + 38 + + + 39 + + + 40 + + + 41 + + + 42 + + + 43 + + + 44 + + + 45 + + + 46 + + + 47 + + + 48 + + + 49 + + + 50 + + + 51 + + + 52 + + + 53 + + + 54 + + + 55 + + + + + + + Main loop performance monitoring message. + + + Time since system startup + + + Loop delay so far + + + Current task + + + Internal error mask + + + Count of internal error occurances + + + Internal Error line + + + MAVLink message currently being processed + + + MAVLink command currently being processed + + + If semaphore taken, line of semaphore take call + + + count of SPI transactions + + + count of i2c transactions + + + + + Motor mixer information + + + Time since system startup + + + Maximum motor compensation gain + + + Ratio between detected battery voltage and maximum battery voltage + + + Throttle limit set due to battery current limitations + + + Maximum average throttle that can be used to maintain attitude control, derived from throttle mix params + + + Throttle output + + + bit 0 motor failed, bit 1 motors balanced, should be 2 in normal flight + + + + + Textual messages + + + Time since system startup + + + identifier for chunks making up a message + + + chunk sequence number within message identified by ID + + + message text + + + + + Message mapping from single character to numeric multiplier + + + Time since system startup + + + character referenced by FMTU + + + numeric multiplier + + + + + EKF2 beacon sensor diagnostics + + + Time since system startup + + + EKF2 core this data is for + + + Beacon sensor ID + + + Beacon range + + + Beacon range innovation + + + sqrt of beacon range innovation variance + + + Beacon range innovation consistency test ratio + + + Beacon north position + + + Beacon east position + + + Beacon down position + + + High estimate of vertical position offset of beacons rel to EKF origin + + + Low estimate of vertical position offset of beacons rel to EKF origin + + + always zero + + + always zero + + + always zero + + + + + EKF2 estimator outputs + + + Time since system startup + + + EKF2 core this data is for + + + Estimated roll + + + Estimated pitch + + + Estimated yaw + + + Estimated velocity (North component) + + + Estimated velocity (East component) + + + Estimated velocity (Down component) + + + Filtered derivative of vertical position (down) + + + Estimated distance from origin (North component) + + + Estimated distance from origin (East component) + + + Estimated distance from origin (Down component) + + + Estimated gyro bias, X axis + + + Estimated gyro bias, Y axis + + + Estimated gyro bias, Z axis + + + Height of origin above WGS-84 + + + + + EKF2 estimator secondary outputs + + + Time since system startup + + + EKF2 core this data is for + + + Estimated accelerometer Z bias + + + Gyro Scale Factor (X-axis) + + + Gyro Scale Factor (Y-axis) + + + Gyro Scale Factor (Z-axis) + + + Estimated wind velocity (moving-to-North component) + + + Estimated wind velocity (moving-to-East component) + + + Magnetic field strength (North component) + + + Magnetic field strength (East component) + + + Magnetic field strength (Down component) + + + Magnetic field strength (body X-axis) + + + Magnetic field strength (body Y-axis) + + + Magnetic field strength (body Z-axis) + + + Magnetometer used for data + + + + + EKF2 innovations + + + Time since system startup + + + EKF2 core this data is for + + + Innovation in velocity (North component) + + + Innovation in velocity (East component) + + + Innovation in velocity (Down component) + + + Innovation in position (North component) + + + Innovation in position (East component) + + + Innovation in position (Down component) + + + Innovation in magnetic field strength (X-axis component) + + + Innovation in magnetic field strength (Y-axis component) + + + Innovation in magnetic field strength (Z-axis component) + + + Innovation in vehicle yaw + + + Innovation in true-airspeed + + + Accumulated relative error of this core with respect to active primary core + + + A consolidated error score where higher numbers are less healthy + + + + + EKF2 variances SV, SP, SH and SM are probably best described as 'Squared Innovation Test Ratios' where values <1 tells us the measurement was accepted and >1 tells us it was rejected. They represent the square of the (innovation / maximum allowed innovation) where the innovation is the difference between predicted and measured value and the maximum allowed innovation is determined from the uncertainty of the measurement, uncertainty of the prediction and scaled using the number of standard deviations set by the innovation gate parameter for that measurement, eg EK2_MAG_I_GATE, EK2_HGT_I_GATE, etc + + + Time since system startup + + + EKF2 core this data is for + + + Square root of the velocity variance + + + Square root of the position variance + + + Square root of the height variance + + + Magnetic field variance + + + tilt error convergence metric + + + Filtered error in roll/pitch estimate + + + Most recent position reset (North component) + + + Most recent position reset (East component) + + + Filter fault status + + + Filter timeout status bitmask (0:position measurement, 1:velocity measurement, 2:height measurement, 3:magnetometer measurement, 4:airspeed measurement) + + + Filter solution status + + + 1 + attitude estimate valid + + + 2 + horizontal velocity estimate valid + + + 4 + vertical velocity estimate valid + + + 8 + relative horizontal position estimate valid + + + 16 + absolute horizontal position estimate valid + + + 32 + vertical position estimate valid + + + 64 + terrain height estimate valid + + + 128 + in constant position mode + + + 256 + expected good relative horizontal position estimate - used before takeoff + + + 512 + expected good absolute horizontal position estimate - used before takeoff + + + 1024 + optical flow takeoff has been detected + + + 2048 + compensating for baro errors during takeoff + + + 4096 + compensating for baro errors during touchdown + + + 8192 + using GPS position + + + 16384 + GPS glitching is affecting navigation accuracy + + + 32768 + can use GPS for navigation + + + 65536 + has ever been healthy + + + 131072 + rejecting airspeed data + + + 262144 + dead reckoning (e.g. no position or velocity source) + + + + + Filter GPS status + + + Primary core index + + + + + EKF2 Sensor innovations (primary core) and general dumping ground + + + Time since system startup + + + EKF2 core this data is for + + + Normalised flow variance + + + Optical flow LOS rate vector innovations from the main nav filter (X-axis) + + + Optical flow LOS rate vector innovations from the main nav filter (Y-axis) + + + Optical flow LOS rate innovation from terrain offset estimator + + + Height above ground level + + + Estimated vertical position of the terrain relative to the nav filter zero datum + + + Range finder innovations + + + Measured range + + + Filter ground offset state error + + + Magnitude of angular error + + + Magnitude of velocity error + + + Magnitude of position error + + + + + EKF2 quaternion defining the rotation from NED to XYZ (autopilot) axes + + + Time since system startup + + + EKF2 core this data is for + + + Quaternion a term + + + Quaternion b term + + + Quaternion c term + + + Quaternion d term + + + + + EKF2 timing information + + + Time since system startup + + + EKF core this message instance applies to + + + count of samples used to create this message + + + smallest IMU sample interval + + + largest IMU sample interval + + + low-passed achieved average time step rate for the EKF (minimum) + + + low-passed achieved average time step rate for the EKF (maximum) + + + accumulated measurement time interval for the delta angle (minimum) + + + accumulated measurement time interval for the delta angle (maximum) + + + accumulated measurement time interval for the delta velocity (minimum) + + + accumulated measurement time interval for the delta velocity (maximum) + + + + + EKF Yaw Estimator States + + + Time since system startup + + + EKF core this data is for + + + GSF yaw estimate (deg) + + + GSF yaw estimate 1-Sigma uncertainty (deg) + + + Yaw estimate from individual EKF filter 0 (deg) + + + Yaw estimate from individual EKF filter 1 (deg) + + + Yaw estimate from individual EKF filter 2 (deg) + + + Yaw estimate from individual EKF filter 3 (deg) + + + Yaw estimate from individual EKF filter 4 (deg) + + + Weighting applied to yaw estimate from individual EKF filter 0 + + + Weighting applied to yaw estimate from individual EKF filter 1 + + + Weighting applied to yaw estimate from individual EKF filter 2 + + + Weighting applied to yaw estimate from individual EKF filter 3 + + + Weighting applied to yaw estimate from individual EKF filter 4 + + + + + EKF Yaw Estimator Innovations + + + Time since system startup + + + EKF core this data is for + + + North velocity innovation from individual EKF filter 0 (m/s) + + + North velocity innovation from individual EKF filter 1 (m/s) + + + North velocity innovation from individual EKF filter 2 (m/s) + + + North velocity innovation from individual EKF filter 3 (m/s) + + + North velocity innovation from individual EKF filter 4 (m/s) + + + East velocity innovation from individual EKF filter 0 (m/s) + + + East velocity innovation from individual EKF filter 1 (m/s) + + + East velocity innovation from individual EKF filter 2 (m/s) + + + East velocity innovation from individual EKF filter 3 (m/s) + + + East velocity innovation from individual EKF filter 4 (m/s) + + + + + Navigation Tuning information - e.g. vehicle destination + + + Time since system startup + + + distance to the current navigation waypoint + + + bearing to the current navigation waypoint + + + the vehicle's desired heading + + + difference between current vehicle height and target height + + + the vehicle's current distance from the current travel segment + + + integration of the vehicle's crosstrack error + + + difference between vehicle's airspeed and desired airspeed + + + target latitude + + + target longitude + + + target altitude WP + + + target altitude TECS + + + target airspeed + + + + + Named Value Float messages; messages sent to GCS via NAMED_VALUE_FLOAT + + + Time since system startup + + + Name of float + + + Value of float + + + + + Named Value String messages; messages sent to GCS via NAMED_VALUE_STRING + + + Time since system startup + + + Name of string + + + Value of string + + + + + Object avoidance (Bendy Ruler) diagnostics + + + Time since system startup + + + Type of BendyRuler currently active + + + True if Bendy Ruler avoidance is being used + + + Best yaw chosen to avoid obstacle + + + Current vehicle yaw + + + Desired pitch chosen to avoid obstacle + + + True if BendyRuler resisted changing bearing and continued in last calculated bearing + + + Margin from path to obstacle on best yaw chosen + + + Destination latitude + + + Destination longitude + + + Desired alt above EKF Origin + + + Intermediate location chosen for avoidance + + + Intermediate location chosen for avoidance + + + Intermediate alt chosen for avoidance above EKF origin + + + + + Object avoidance (Dijkstra) diagnostics + + + Time since system startup + + + Dijkstra avoidance library state + + + Dijkstra library error condition + + + Destination point in calculated path to destination + + + Number of points in path to destination + + + Destination latitude + + + Destination longitude + + + Object Avoidance chosen destination point latitude + + + Object Avoidance chosen destination point longitude + + + + + Object avoidance path planning visgraph points + + + Time since system startup + + + Visgraph version, increments each time the visgraph is re-generated + + + point number in visgraph + + + Latitude + + + longitude + + + + + Optical flow sensor data + + + Time since system startup + + + Estimated sensor data quality + + + Sensor flow rate, X-axis + + + Sensor flow rate,Y-axis + + + derived rotational velocity, X-axis + + + derived rotational velocity, Y-axis + + + + + Optical Flow Calibration sample + + + Time since system startup + + + Axis (X=0 Y=1) + + + Sample number + + + Flow rate + + + Body rate + + + Los pred + + + + + OFfboard-Guided - an advanced version of GUIDED for companion computers that includes rate/s. + + + Time since system startup + + + target airspeed cm + + + target airspeed accel + + + target alt + + + target alt velocity (rate of change) + + + target alt frame (MAVLink) + + + target heading + + + target heading lim + + + target alt frame (Location) + + + + + Vehicle navigation origin or other notable position + + + Time since system startup + + + Position type + + + 0 + + + 1 + + + + + Position latitude + + + Position longitude + + + Position altitude + + + + + parameter value + + + Time since system startup + + + parameter name + + + parameter value + + + default parameter value for this board and config + + + + + Proportional/Integral/Derivative gain values for vertical acceleration + + + Time since system startup + + + desired value + + + achieved value + + + error between target and achieved + + + proportional part of PID + + + integral part of PID + + + derivative part of PID + + + controller feed-forward portion of response + + + controller derivative feed-forward portion of response + + + scaler applied to D gain to reduce limit cycling + + + slew rate used in slew limiter + + + bitmask of PID state flags + + + 1 + true if the output is saturated, I term anti windup is active + + + 2 + true if the PD sum limit is active + + + 4 + true if the controller was reset + + + 8 + true if the I term has been set externally including reseting to 0 + + + + + + + Proportional/Integral/Derivative gain values for East/West velocity + + + Time since system startup + + + desired value + + + achieved value + + + error between target and achieved + + + proportional part of PID + + + integral part of PID + + + derivative part of PID + + + controller feed-forward portion of response + + + controller derivative feed-forward portion of response + + + scaler applied to D gain to reduce limit cycling + + + slew rate used in slew limiter + + + bitmask of PID state flags + + + 1 + true if the output is saturated, I term anti windup is active + + + 2 + true if the PD sum limit is active + + + 4 + true if the controller was reset + + + 8 + true if the I term has been set externally including reseting to 0 + + + + + + + Plane Proportional/Integral/Derivative gain values for Heading when using COMMAND_INT control. + + + Time since system startup + + + desired value + + + achieved value + + + error between target and achieved + + + proportional part of PID + + + integral part of PID + + + derivative part of PID + + + controller feed-forward portion of response + + + controller derivative feed-forward portion of response + + + scaler applied to D gain to reduce limit cycling + + + slew rate + + + bitmask of PID state flags + + + 1 + true if the output is saturated, I term anti windup is active + + + 2 + true if the PD sum limit is active + + + 4 + true if the controller was reset + + + 8 + true if the I term has been set externally including reseting to 0 + + + + + + + Proportional/Integral/Derivative gain values for North/South velocity + + + Time since system startup + + + desired value + + + achieved value + + + error between target and achieved + + + proportional part of PID + + + integral part of PID + + + derivative part of PID + + + controller feed-forward portion of response + + + controller derivative feed-forward portion of response + + + scaler applied to D gain to reduce limit cycling + + + slew rate used in slew limiter + + + bitmask of PID state flags + + + 1 + true if the output is saturated, I term anti windup is active + + + 2 + true if the PD sum limit is active + + + 4 + true if the controller was reset + + + 8 + true if the I term has been set externally including reseting to 0 + + + + + + + Proportional/Integral/Derivative gain values for Pitch rate + + + Time since system startup + + + desired value + + + achieved value + + + error between target and achieved + + + proportional part of PID + + + integral part of PID + + + derivative part of PID + + + controller feed-forward portion of response + + + controller derivative feed-forward portion of response + + + scaler applied to D gain to reduce limit cycling + + + slew rate used in slew limiter + + + bitmask of PID state flags + + + 1 + true if the output is saturated, I term anti windup is active + + + 2 + true if the PD sum limit is active + + + 4 + true if the controller was reset + + + 8 + true if the I term has been set externally including reseting to 0 + + + + + + + Proportional/Integral/Derivative gain values for Roll rate + + + Time since system startup + + + desired value + + + achieved value + + + error between target and achieved + + + proportional part of PID + + + integral part of PID + + + derivative part of PID + + + controller feed-forward portion of response + + + controller derivative feed-forward portion of response + + + scaler applied to D gain to reduce limit cycling + + + slew rate used in slew limiter + + + bitmask of PID state flags + + + 1 + true if the output is saturated, I term anti windup is active + + + 2 + true if the PD sum limit is active + + + 4 + true if the controller was reset + + + 8 + true if the I term has been set externally including reseting to 0 + + + + + + + Proportional/Integral/Derivative gain values for ground steering yaw rate + + + Time since system startup + + + desired value + + + achieved value + + + error between target and achieved + + + proportional part of PID + + + integral part of PID + + + derivative part of PID + + + controller feed-forward portion of response + + + controller derivative feed-forward portion of response + + + scaler applied to D gain to reduce limit cycling + + + slew rate used in slew limiter + + + bitmask of PID state flags + + + 1 + true if the output is saturated, I term anti windup is active + + + 2 + true if the PD sum limit is active + + + 4 + true if the controller was reset + + + 8 + true if the I term has been set externally including reseting to 0 + + + + + + + Proportional/Integral/Derivative gain values for Yaw rate + + + Time since system startup + + + desired value + + + achieved value + + + error between target and achieved + + + proportional part of PID + + + integral part of PID + + + derivative part of PID + + + controller feed-forward portion of response + + + controller derivative feed-forward portion of response + + + scaler applied to D gain to reduce limit cycling + + + slew rate used in slew limiter + + + bitmask of PID state flags + + + 1 + true if the output is saturated, I term anti windup is active + + + 2 + true if the PD sum limit is active + + + 4 + true if the controller was reset + + + 8 + true if the I term has been set externally including reseting to 0 + + + + + + + QuadPlane Proportional/Integral/Derivative gain values for vertical acceleration + + + Time since system startup + + + desired value + + + achieved value + + + error between target and achieved + + + proportional part of PID + + + integral part of PID + + + derivative part of PID + + + controller feed-forward portion of response + + + controller derivative feed-forward portion of response + + + scaler applied to D gain to reduce limit cycling + + + slew rate + + + bitmask of PID state flags + + + 1 + true if the output is saturated, I term anti windup is active + + + 2 + true if the PD sum limit is active + + + 4 + true if the controller was reset + + + 8 + true if the I term has been set externally including reseting to 0 + + + + + + + QuadPlane Proportional/Integral/Derivative gain values for Pitch rate + + + Time since system startup + + + desired value + + + achieved value + + + error between target and achieved + + + proportional part of PID + + + integral part of PID + + + derivative part of PID + + + controller feed-forward portion of response + + + controller derivative feed-forward portion of response + + + scaler applied to D gain to reduce limit cycling + + + slew rate + + + bitmask of PID state flags + + + 1 + true if the output is saturated, I term anti windup is active + + + 2 + true if the PD sum limit is active + + + 4 + true if the controller was reset + + + 8 + true if the I term has been set externally including reseting to 0 + + + + + + + QuadPlane Proportional/Integral/Derivative gain values for Roll rate + + + Time since system startup + + + desired value + + + achieved value + + + error between target and achieved + + + proportional part of PID + + + integral part of PID + + + derivative part of PID + + + controller feed-forward portion of response + + + controller derivative feed-forward portion of response + + + scaler applied to D gain to reduce limit cycling + + + slew rate + + + bitmask of PID state flags + + + 1 + true if the output is saturated, I term anti windup is active + + + 2 + true if the PD sum limit is active + + + 4 + true if the controller was reset + + + 8 + true if the I term has been set externally including reseting to 0 + + + + + + + QuadPlane Proportional/Integral/Derivative gain values for Yaw rate + + + Time since system startup + + + desired value + + + achieved value + + + error between target and achieved + + + proportional part of PID + + + integral part of PID + + + derivative part of PID + + + controller feed-forward portion of response + + + controller derivative feed-forward portion of response + + + scaler applied to D gain to reduce limit cycling + + + slew rate + + + bitmask of PID state flags + + + 1 + true if the output is saturated, I term anti windup is active + + + 2 + true if the PD sum limit is active + + + 4 + true if the controller was reset + + + 8 + true if the I term has been set externally including reseting to 0 + + + + + + + Precision Landing messages + + + Time since system startup + + + True if Precision Landing is healthy + + + True if landing target is detected + + + Target position relative to vehicle, X-Axis (0 if target not found) + + + Target position relative to vehicle, Y-Axis (0 if target not found) + + + Target velocity relative to vehicle, X-Axis (0 if target not found) + + + Target velocity relative to vehicle, Y-Axis (0 if target not found) + + + Target's relative to origin position as 3-D Vector, X-Axis + + + Target's relative to origin position as 3-D Vector, Y-Axis + + + Target's relative to origin position as 3-D Vector, Z-Axis + + + Time when target was last detected + + + EKF's outlier count + + + Type of estimator used + + + + + autopilot system performance and general data dumping ground + + + Time since system startup + + + Main loop rate + + + Number of long loops detected + + + Number of measurement loops for this message + + + Maximum loop time + + + Free memory available + + + System processor load + + + Internal error line number; last line number on which a internal error was detected + + + Internal error mask; which internal errors have been detected + + + 1 + + + 2 + + + 4 + + + 8 + + + 16 + + + 32 + + + 64 + + + 128 + + + 256 + + + 512 + + + 1024 + + + 2048 + + + 4096 + + + 8192 + + + 16384 + + + 32768 + + + 65536 + + + 131072 + + + 262144 + + + 524288 + + + 1048576 + + + 2097152 + + + 4194304 + + + 8388608 + + + 16777216 + + + 33554432 + + + 67108864 + + + 134217728 + + + 268435456 + + + 536870912 + + + 1073741824 + + + + + Internal error count; how many internal errors have been detected + + + Number of SPI transactions processed + + + Number of i2c transactions processed + + + Number of i2c interrupts serviced + + + number of microseconds being added to each loop to address scheduler overruns + + + RTC time, time since Unix epoch + + + + + Canonical vehicle position + + + Time since system startup + + + Canonical vehicle latitude + + + Canonical vehicle longitude + + + Canonical vehicle altitude + + + Canonical vehicle altitude relative to home + + + Canonical vehicle altitude relative to navigation origin + + + + + System power information + + + Time since system startup + + + Flight board voltage + + + Servo rail voltage + + + System power flags + + + 1 + main brick power supply valid + + + 2 + main servo power supply valid for FMU + + + 4 + USB power is connected + + + 8 + peripheral supply is in over-current state + + + 16 + hi-power peripheral supply is in over-current state + + + 32 + Power status has changed since boot + + + + + Accumulated System power flags; all flags which have ever been set + + + 1 + main brick power supply valid + + + 2 + main servo power supply valid for FMU + + + 4 + USB power is connected + + + 8 + peripheral supply is in over-current state + + + 16 + hi-power peripheral supply is in over-current state + + + 32 + Power status has changed since boot + + + + + Hardware Safety Switch status + + + + + Plane Parameter Tuning data + + + Time since system startup + + + Parameter set being tuned + + + Parameter being tuned + + + Current parameter value + + + Center value (startpoint of current modifications) of parameter being tuned + + + + + Proximity Filtered sensor data + + + Time since system startup + + + Pitch(instance) at which the obstacle is at. 0th layer {-75,-45} degrees. 1st layer {-45,-15} degrees. 2nd layer {-15, 15} degrees. 3rd layer {15, 45} degrees. 4th layer {45,75} degrees. Minimum distance in each layer will be logged. + + + True if proximity sensor is healthy + + + Nearest object in sector surrounding 0-degrees + + + Nearest object in sector surrounding 45-degrees + + + Nearest object in sector surrounding 90-degrees + + + Nearest object in sector surrounding 135-degrees + + + Nearest object in sector surrounding 180-degrees + + + Nearest object in sector surrounding 225-degrees + + + Nearest object in sector surrounding 270-degrees + + + Nearest object in sector surrounding 315-degrees + + + Nearest object in upwards direction + + + Angle to closest object + + + Distance to closest object + + + + + Proximity Raw sensor data + + + Time since system startup + + + Pitch(instance) at which the obstacle is at. 0th layer {-75,-45} degrees. 1st layer {-45,-15} degrees. 2nd layer {-15, 15} degrees. 3rd layer {15, 45} degrees. 4th layer {45,75} degrees. Minimum distance in each layer will be logged. + + + Nearest object in sector surrounding 0-degrees + + + Nearest object in sector surrounding 45-degrees + + + Nearest object in sector surrounding 90-degrees + + + Nearest object in sector surrounding 135-degrees + + + Nearest object in sector surrounding 180-degrees + + + Nearest object in sector surrounding 225-degrees + + + Nearest object in sector surrounding 270-degrees + + + Nearest object in sector surrounding 315-degrees + + + + + Position Control Down + + + Time since system startup + + + Desired position relative to EKF origin + Offsets + + + Target position relative to EKF origin + + + Position relative to EKF origin + + + Desired velocity Down + + + Target velocity Down + + + Velocity Down + + + Desired acceleration Down + + + Target acceleration Down + + + Acceleration Down + + + + + Position Control East + + + Time since system startup + + + Desired position relative to EKF origin + Offsets + + + Target position relative to EKF origin + + + Position relative to EKF origin + + + Desired velocity East + + + Target velocity East + + + Velocity East + + + Desired acceleration East + + + Target acceleration East + + + Acceleration East + + + + + Position Control North + + + Time since system startup + + + Desired position relative to EKF origin + + + Target position relative to EKF origin + + + Position relative to EKF origin + + + Desired velocity North + + + Target velocity North + + + Velocity North + + + Desired acceleration North + + + Target acceleration North + + + Acceleration North + + + + + Position Control Offsets Down + + + Time since system startup + + + Target position offset Down + + + Position offset Down + + + Target velocity offset Down + + + Velocity offset Down + + + Target acceleration offset Down + + + Acceleration offset Down + + + + + Position Control Offsets East + + + Time since system startup + + + Target position offset East + + + Position offset East + + + Target velocity offset East + + + Velocity offset East + + + Target acceleration offset East + + + Acceleration offset East + + + + + Position Control Offsets North + + + Time since system startup + + + Target position offset North + + + Position offset North + + + Target velocity offset North + + + Velocity offset North + + + Target acceleration offset North + + + Acceleration offset North + + + + + Position Control Offsets Terrain (Down) + + + Time since system startup + + + Target position offset Terrain + + + Position offset Terrain + + + Target velocity offset Terrain + + + Velocity offset Terrain + + + Target acceleration offset Terrain + + + Acceleration offset Terrain + + + + + Quadplane Braking + + + Time since system startup + + + braking speed scaler + + + upper limit for navigation pitch + + + upper limit for back transition pitch + + + demanded navigation pitch + + + + + Quadplane position data + + + Time since system startup + + + Position control state + + + 0 + + + 1 + + + 2 + + + 3 + + + 4 + + + 5 + + + 6 + + + 7 + + + 8 + + + + + Distance to next waypoint + + + Target speed + + + Target acceleration + + + True if landing point is overshot or heading off by more than 60 degrees + + + + + QuadPlane vertical tuning message + + + Time since system startup + + + throttle input + + + angle boost + + + throttle output + + + calculated hover throttle + + + desired altitude + + + achieved altitude + + + barometric altitude + + + desired climb rate + + + climb rate + + + transition throttle mix value + + + Transition state: 0-AirspeedWait,1-Timer,2-Done / TailSitter: 0-FW Wait,1-VTOL Wait,2-Done + + + bitmask of assistance flags + + + 1 + true if VTOL assist is active + + + 2 + true if assistance is forced + + + 4 + true if assistance due to low airspeed + + + 8 + true if assistance due to low altitude + + + 16 + true if assistance due to attitude error + + + 32 + true if forcing use of fixed wing controllers + + + 64 + true if recovering from a spin + + + + + + + Quicktune + + + Time since system startup + + + number of parameter being tuned + + + slew rate + + + test gain for current axis and PID element + + + name of parameter being being tuned + + + + + Telemetry radio statistics + + + Time since system startup + + + RSSI + + + RSSI reported from remote radio + + + number of bytes in radio ready to be sent + + + local noise floor + + + local noise floor reported from remote radio + + + damaged packet count + + + fixed damaged packet count + + + + + Rally point information + + + Time since system startup + + + total number of rally points onboard + + + this rally point's sequence number + + + latitude of rally point + + + longitude of rally point + + + altitude of rally point + + + altitude frame flags + + + + + Replay Airspeed Sensor Header + + + airspeed instance number + + + number of airspeed instances + + + + + Replay Airspeed Sensor Instance data + + + measured airspeed + + + timestamp of measured airspeed + + + indicator of airspeed sensor health + + + true if airspeed is configured to be used + + + airspeed instance number + + + + + Desired and achieved vehicle attitude rates. Not logged in Fixed Wing Plane modes. + + + Time since system startup + + + vehicle desired roll rate + + + achieved vehicle roll rate + + + normalized output for Roll + + + vehicle desired pitch rate + + + vehicle pitch rate + + + normalized output for Pitch + + + vehicle desired yaw rate + + + achieved vehicle yaw rate + + + normalized output for Yaw + + + desired vehicle vertical acceleration + + + achieved vehicle vertical acceleration + + + percentage of vertical thrust output current being used + + + vertical thrust output slew rate + + + + + Replay Data Beacon Header + + + zero, unused + + + zero, unused + + + zero, unused + + + zero, unused + + + origin latitude + + + origin longitude + + + origin altitude + + + vehicle_position_ned_returncode,get_origin_returncode,enabled + + + number of beacons + + + + + Replay Data Beacon Instance + + + last update from this beacon instance + + + beacon distance from origin, X-axis + + + beacon distance from origin, Y-axis + + + beacon distance from origin, Z-axis + + + distance to beacon + + + beacon data health + + + beacon instance number + + + + + Replay body odometry data + + + data quality measure + + + delta-position-X + + + delta-position-Y + + + delta-position-Z + + + delta-angle-X + + + delta-angle-Y + + + delta-angle-Z + + + delta-time + + + data timestamp + + + zero, unused + + + zero, unused + + + zero, unused + + + zero, unused + + + + + Replay Data Barometer Header + + + primary barometer instance number + + + number of barometer sensors + + + + + Replay Data Barometer Instance + + + timestamp of barometer data + + + barometer altitude estimate + + + barometer sensor health indication + + + barometer instance number + + + + + Raw RC data + + + Time since system startup + + + data arrival timestamp + + + Protocol currently being decoded + + + Number of valid bytes in message + + + first quartet of bytes + + + second quartet of bytes + + + third quartet of bytes + + + fourth quartet of bytes + + + fifth quartet of bytes + + + sixth quartet of bytes + + + seventh quartet of bytes + + + eight quartet of bytes + + + ninth quartet of bytes + + + tenth quartet of bytes + + + + + (More) RC input channels to vehicle + + + Time since system startup + + + channel 15 input + + + channel 16 input + + + bitmask of RC channels being overridden by mavlink input + + + bitmask of RC state flags + + + 1 + true if the system is receiving good RC values + + + 2 + true if the system is current in RC failsafe + + + 4 + true if the RC Protocol library is indicating the RC receiver is indicating failsafe via its protocol + + + + + + + RC input channels to vehicle + + + Time since system startup + + + channel 1 input + + + channel 2 input + + + channel 3 input + + + channel 4 input + + + channel 5 input + + + channel 6 input + + + channel 7 input + + + channel 8 input + + + channel 9 input + + + channel 10 input + + + channel 11 input + + + channel 12 input + + + channel 13 input + + + channel 14 input + + + + + Servo channel output values 15 to 18 + + + Time since system startup + + + channel 15 output + + + channel 16 output + + + channel 17 output + + + channel 18 output + + + + + Servo channel output values 19 to 32 + + + Time since system startup + + + channel 19 output + + + channel 20 output + + + channel 21 output + + + channel 22 output + + + channel 23 output + + + channel 24 output + + + channel 25 output + + + channel 26 output + + + channel 27 output + + + channel 28 output + + + channel 29 output + + + channel 30 output + + + channel 31 output + + + channel 32 output + + + + + Servo channel output values 1 to 14 + + + Time since system startup + + + channel 1 output + + + channel 2 output + + + channel 3 output + + + channel 4 output + + + channel 5 output + + + channel 6 output + + + channel 7 output + + + channel 8 output + + + channel 9 output + + + channel 10 output + + + channel 11 output + + + channel 12 output + + + channel 13 output + + + channel 14 output + + + + + Relay state + + + Time since system startup + + + relay instance number + + + current state + + + + + Replay external position data + + + external position estimate, X-axis + + + external position estimate, Y-axis + + + external position estimate, Z-axis + + + external attitude quaternion + + + external attitude quaternion + + + external attitude quaternion + + + external attitude quaternion + + + external position error estimate + + + external attitude error estimate + + + timestamp on external error estimate + + + timestamp of last external reset + + + delay on external data + + + + + Replay Event (EKF2) + + + external event injected into EKF + + + 0 + + + 1 + + + 9 + + + 10 + + + 11 + + + 12 + + + 13 + + + 14 + + + 15 + + + + + + + Replay Event (EKF3) + + + external event injected into EKF + + + 0 + + + 1 + + + 9 + + + 10 + + + 11 + + + 12 + + + 13 + + + 14 + + + 15 + + + + + + + Replay external velocity data + + + external velocity estimate, X-axis + + + external velocity estimate, Y-axis + + + external velocity estimate, Z-axis + + + error in velocity estimate + + + timestamp of velocity estimate + + + delay in external velocity data + + + + + Replay Euler Yaw event + + + externally supplied yaw angle + + + error in externally supplied yaw angle + + + timestamp associated with yaw angle and yaw angle error + + + number that needs documenting + + + + + RealFlight mode messages + + + Time since system startup + + + delta time between this frame and the previous frame + + + frames-per-second implied by the current delta time + + + + + Rangefinder sensor information + + + Time since system startup + + + rangefinder instance number this data is from + + + Reported distance from sensor + + + Sensor state + + + 0 + + + 1 + + + 2 + + + 3 + + + 4 + + + + + Sensor orientation + + + 0 + + + 1 + + + 2 + + + 3 + + + 4 + + + 5 + + + 6 + + + 7 + + + 8 + + + 9 + + + 10 + + + 11 + + + 12 + + + 13 + + + 14 + + + 15 + + + 16 + + + 17 + + + 18 + + + 19 + + + 20 + + + 21 + + + 22 + + + 23 + + + 24 + + + 25 + + + 26 + same as ROTATION_ROLL_180_YAW_270 + + + 27 + same as ROTATION_ROLL_180_YAW_90 + + + 28 + + + 29 + + + 30 + + + 31 + + + 32 + + + 33 + + + 34 + + + 35 + + + 36 + + + 37 + + + 38 + this is actually, roll 90, pitch 68.8, yaw 293.3 + + + 39 + + + 40 + + + 41 + + + 42 + + + 43 + + + 44 + + + 100 + + + 101 + + + 102 + + + 103 + + + + + Signal quality. -1 means invalid, 0 is no signal, 100 is perfect signal + + + + + Replay FRame data - Finished frame + + + accumulated method calls made during frame + + + 1 + + + 2 + + + 4 + + + 8 + + + 16 + + + 32 + + + + + true if we are not keeping up with IMU loop rate + + + + + Replay FRame Header + + + Time since system startup + + + Time flying + + + + + Replay FRame - aNother frame header + + + home latitude + + + home latitude + + + home altitude AMSL + + + EAS to TAS factor + + + available memory + + + AHRS trim X + + + AHRS trim Y + + + AHRS trim Z + + + AHRS Vehicle Class + + + configured EKF type + + + 0 + + + 1 + + + + + bitmask of boolean state + + + 1 + + + 2 + + + 4 + + + 8 + + + 16 + + + 32 + + + 64 + + + 128 + + + + + + + Replay Data GPS Header + + + number of GPS sensors + + + instance number of primary sensor + + + + + Replay Data GPS Instance, infrequently changing data + + + antenna body-frame offset, X-axis + + + antenna body-frame offset, Y-axis + + + antenna body-frame offset, Z-axis + + + GPS time lag + + + various GPS flags + + + 1 + + + 2 + + + 4 + + + 8 + + + 16 + + + 32 + + + + + GPS fix status + + + number of satellites GPS is using + + + GPS sensor instance number + + + + + Replay Data GPS Instance - rapidly changing data + + + GPS data timestamp + + + GPS velocity, North + + + GPS velocity, East + + + GPS velocity, Down + + + speed accuracy + + + GPS yaw + + + GPS yaw accuracy + + + timestamp of GPS yaw estimate + + + latitude + + + longitude + + + altitude + + + horizontal accuracy + + + vertical accuracy + + + HDOP + + + GPS sensor instance number + + + + + Richenpower generator telemetry + + + Time since system startup + + + total generator runtime + + + time until generator requires maintenance + + + bitmask of error received from generator + + + current generator RPM + + + output voltage + + + output current + + + generator mode; idle/run/charge/balance + + + + + Replay Inertial Sensor header + + + INS loop rate + + + primary gyro index + + + primary accel index + + + INS loop-delta-t + + + accel count + + + gyro count + + + + + Replay Inertial Sensor instance data + + + x-axis delta-velocity + + + y-axis delta-velocity + + + z-axis delta-velocity + + + x-axis delta-angle + + + y-axis delta-angle + + + z-axis delta-angle + + + delta-velocity-delta-time + + + delta-angle-delta-time + + + use-accel, use-gyro, delta-vel-valid, delta-accel-valid + + + IMU instance + + + + + Replay Data Magnetometer Header + + + vehicle declination + + + true if the compass library is marking itself as available + + + number of compass instances + + + true if compass autodeclination is enabled + + + number of enabled compass instances + + + true if compass learning of offsets is enabled + + + true if compasses are consistent + + + index of first usable compass + + + + + Replay Data Magnetometer Instance + + + last update time for magnetometer data + + + mag sensor offset, X-axis + + + mag sensor offset, Y-axis + + + mag sensor offset, Z-axis + + + field strength, X-axis + + + field strength, Y-axis + + + field strength, Z-axis + + + true if compass is being used for yaw + + + sensor health + + + compass has scale factor + + + magnetometer instance number + + + + + Replay optical flow data + + + raw flow rate, X-axis + + + raw flow rate, Y-axis + + + gyro rate, X-axis + + + gyro rate, Y-axis + + + measurement timestamp + + + gyro rate, X-axis + + + body-frame offset, Y-axis + + + body-frame offset, Z-axis + + + sensor height override + + + flow quality measurement + + + + + Data from RPM sensors + + + Time since system startup + + + Instance + + + Sensor's rpm measurement + + + Signal quality + + + Sensor Health (Bool) + + + + + Replay Data Rangefinder Header + + + rangefinder ground clearance for downward-facing rangefinders + + + rangefinder maximum distance for downward-facing rangefinders + + + number of rangefinder instances + + + + + Replay Data Rangefinder Instance + + + rangefinder body-frame offset, X-axis + + + rangefinder body-frame offset, Y-axis + + + rangefinder body-frame offset, Z-axis + + + Measured rangefinder distance + + + orientation + + + status + + + rangefinder instance number + + + + + Replay Set Lat Lng event + + + latitude + + + longitude + + + position accuracy, 1-StD + + + timestamp of latitude/longitude + + + + + Replay Set Origin event (EKF2) + + + origin latitude + + + origin longitude + + + origin altitude + + + + + Replay Set Origin event (EKF3) + + + origin latitude + + + origin longitude + + + origin altitude + + + + + Received Signal Strength Indicator for RC receiver + + + Time since system startup + + + RSSI + + + RX Link Quality + + + + + Information about RTC clock resets + + + Time since system startup + + + old time + + + new time + + + + + GPS atmospheric perturbation data + + + Time since system startup + + + mavlink channel number this data was received on + + + ID field from RTCM packet + + + RTCM packet length + + + calculated crc32 for the packet + + + + + Replay Terrain SRTM Altitude + + + altitude above origin in meters + + + + + Replay Data Visual Odometry data + + + offset, x-axis + + + offset, y-axis + + + offset, z-axis + + + data delay + + + sensor health + + + sensor enabled + + + + + Replay set-default-airspeed event (EKF2) + + + default airspeed + + + uncertainty in default airspeed + + + + + Replay set-default-airspeed event (EKF3) + + + default airspeed + + + uncertainty in default airspeed + + + + + Replay wheel odometry data + + + delta-angle + + + delta-time + + + data timestamp + + + sensor body-frame offset, x-axis + + + sensor body-frame offset, y-axis + + + sensor body-frame offset, z-axis + + + wheel radius + + + + + Simple Avoidance messages + + + Time since system startup + + + True if Simple Avoidance is active + + + Desired velocity, X-Axis (Velocity before Avoidance) + + + Desired velocity, Y-Axis (Velocity before Avoidance) + + + Desired velocity, Z-Axis (Velocity before Avoidance) + + + Modified velocity, X-Axis (Velocity after Avoidance) + + + Modified velocity, Y-Axis (Velocity after Avoidance) + + + Modified velocity, Z-Axis (Velocity after Avoidance) + + + True if vehicle is backing away + + + + + Simulated Blimp Sin-Angles + + + Time since system startup + + + sin(x angle) + + + sin(y angle) + + + sin(z angle) + + + + + Simulated Blimp Angles + + + Time since system startup + + + x angle + + + y angle + + + z angle + + + + + Simulated Blimp Angles + + + Time since system startup + + + x earth-frame angle + + + y earth-frame angle + + + z earth-frame angle + + + + + Simulated Blimp Body-Frame accelerations + + + Time since system startup + + + x-axis acceleration + + + y-axis acceleration + + + z-axis acceleration + + + + + Simulated Blimp Rotational Accelerations + + + Time since system startup + + + acceleration around X axis + + + acceleration around Y axis + + + acceleration around Z axis + + + + + Swift Health Data + + + Time since system startup + + + Number of packet CRC errors on serial connection + + + Timestamp of last raw data injection to GPS + + + Current number of integer ambiguity hypotheses + + + + + Swift Time Data + + + Time since system startup + + + GPS week number + + + Milliseconds through GPS week + + + residual of milliseconds rounding in ns + + + GPIO pin levels + + + time quality + + + + + Scripting runtime stats + + + Time since system startup + + + script name + + + run time + + + total memory usage of all scripts + + + run memory usage + + + + + Simulated Glider Drop control outputs + + + Time since system startup + + + aileron output + + + elevator output + + + rudder output + + + + + Debug message for SCurve internal error + + + Time since system startup + + + duration of the raised cosine jerk profile + + + maximum value of the raised cosine jerk profile + + + initial velocity magnitude + + + maximum constant acceleration + + + maximum constant velocity + + + Length of the path + + + maximum value of the raised cosine jerk profile + + + segment duration + + + segment duration + + + segment duration + + + segment duration + + + + + Simulated Blimp Fin Angles + + + Time since system startup + + + fin 0 angle + + + fin 1 angle + + + fin 2 angle + + + fin 3 angle + + + + + Simulated Blimp Servo Angles + + + Time since system startup + + + fin 0 servo angle + + + fin 1 servo angle + + + fin 2 servo angle + + + fin 3 servo angle + + + + + Simulated Blimp Fin Forces + + + Time since system startup + + + Fin 0 normal force + + + Fin 1 normal force + + + Fin 2 normal force + + + Fin 3 normal force + + + + + Simulated Blimp Fin Thrust + + + Time since system startup + + + Fin 0 tangential thrust + + + Fin 1 tangential thrust + + + Fin 2 tangential thrust + + + Fin 3 tangential thrust + + + + + Simulated Blimp Fin Velocities + + + Time since system startup + + + fin 0 velocity + + + fin 1 velocity + + + fin 2 velocity + + + fin 3 velocity + + + + + System ID data + + + Time since system startup + + + Time reference for waveform + + + Current waveform sample + + + Instantaneous waveform frequency + + + Delta angle, X-Axis + + + Delta angle, Y-Axis + + + Delta angle, Z-Axis + + + Delta velocity, X-Axis + + + Delta velocity, Y-Axis + + + Delta velocity, Z-Axis + + + + + System ID data for Plane + + + Time since system startup + + + Desired Roll Angle + + + Roll Angle + + + Desired Pitch Angle + + + Pitch Angle + + + Desired Roll Rate + + + Measured Roll Rate + + + Desired Pitch Rate + + + Measured Pitch Rate + + + Aileron + + + Elevator + + + Speed_Scalar + + + EAS2TAS + + + + + System ID settings + + + Time since system startup + + + The axis which is being excited + + + Magnitude of the chirp waveform + + + Frequency at the start of chirp + + + Frequency at the end of chirp + + + Time to reach maximum amplitude of chirp + + + Time at constant frequency before chirp starts + + + Time taken to complete chirp waveform + + + Time to reach zero amplitude after chirp finishes + + + + + SITL simulator state + + + Time since system startup + + + Simulated roll + + + Simulated pitch + + + Simulated yaw + + + Simulated altitude + + + Simulated latitude + + + Simulated longitude + + + Attitude quaternion component 1 + + + Attitude quaternion component 2 + + + Attitude quaternion component 3 + + + Attitude quaternion component 4 + + + + + Additional simulator state + + + Time since system startup + + + North position from home + + + East position from home + + + Down position from home + + + Velocity north + + + Velocity east + + + Velocity down + + + Airspeed + + + Achieved simulation speedup value + + + Number of times simulation paused for serial0 output + + + + + Simulation data + + + Time since system startup + + + Velocity - North component + + + Velocity - East component + + + Velocity - Down component + + + Acceleration - North component + + + Acceleration - East component + + + Acceleration - Down component + + + Position - North component + + + Position - East component + + + Position - Down component + + + + + More Simulated Glider Dropped Calculations + + + Time since system startup + + + altitude in feet + + + equivalent airspeed in knots + + + true airspeed in knots + + + air density + + + lift + + + drag + + + lift/drag ratio + + + elevator output + + + aileron output + + + rudder output + + + Angle of Attack + + + Side Slip Angle + + + air pressire + + + z-axis body-frame acceleration + + + + + Simulated Glider Dropped Calculations + + + Time since system startup + + + altitude in feet + + + altitude in metres + + + equivalent airspeed + + + true airspeed + + + air density + + + lift + + + drag + + + lift/drag ratio + + + elevator output + + + angle of attack + + + X-axis force + + + Y-axis force + + + Z-axis force + + + air pressure + + + + + Slung payload + + + Time since system startup + + + 1 if payload is landed, 0 otherwise + + + Tension ratio, 1 if line is taut, 0 if slack + + + Line length + + + Payload position as offset from vehicle in North direction + + + Payload position as offset from vehicle in East direction + + + Payload position as offset from vehicle in Down direction + + + Payload velocity in North direction + + + Payload velocity in East direction + + + Payload velocity in Down direction + + + Payload acceleration in North direction + + + Payload acceleration in East direction + + + Payload acceleration in Down direction + + + Force on vehicle in North direction + + + Force on vehicle in East direction + + + Force on vehicle in Down direction + + + + + Log data received from JSON simulator 1 + + + Time since system startup (us) + + + Slave instance + + + magic JSON protocol key + + + Slave instance's desired frame rate + + + Slave instance's current frame count + + + 1 if the servo outputs are being used from this instance + + + + + Log data received from JSON simulator 2 + + + Time since system startup + + + Slave instance + + + channel 1 output + + + channel 2 output + + + channel 3 output + + + channel 4 output + + + channel 5 output + + + channel 6 output + + + channel 7 output + + + channel 8 output + + + channel 9 output + + + channel 10 output + + + channel 11 output + + + channel 12 output + + + channel 13 output + + + channel 14 output + + + + + Simulated Blimp Mass and COG + + + Time since system startup + + + mass + + + gravity + + + centre-of-gravity, z-axis + + + + + Smoothed sensor data fed to EKF to avoid inconsistencies + + + Time since system startup + + + Angular Velocity (around x-axis) + + + Angular Velocity (around y-axis) + + + Angular Velocity (around z-axis) + + + Velocity (along x-axis) + + + Velocity (along y-axis) + + + Velocity (along z-axis) + + + Roll + + + Pitch + + + Yaw + + + DCM Roll + + + DCM Pitch + + + DCM Yaw + + + + + Simulated Volz servo information + + + Time since system startup + + + Volz servo ID + + + Current Simulated Position + + + Desired Simulated Position + + + simulated servo voltage + + + simulated servo current + + + simulated PCB Temperature + + + simulated motor Temperature + + + + + https://ardupilot.org/plane/docs/soaring.html + Logged data from soaring feature + + + microseconds since system startup + + + Estimate of vertical speed of surrounding airmass + + + Thermal strength estimate + + + Thermal radius estimate + + + Thermal position estimate north from home + + + Thermal position estimate east from home + + + Aircraft position north from home + + + Aircraft position east from home + + + Aircraft altitude + + + Wind speed north + + + Wind speed east + + + Estimate of achievable climbrate in thermal + + + + + https://ardupilot.org/plane/docs/soaring.html + Soaring Cruise-phase data + + + Time since system startup + + + body-frame wind estimate, x-axis + + + body-frame wind estimate, z-axis + + + estimated thermal vertical speed + + + expected climb-rate lower-limit + + + expected climb-rate upper-limit + + + calculated optimal speed to fly + + + + + Simulated Blimp Rotational forces + + + Time since system startup + + + zero + + + zero + + + zero + + + + + Transformed Simulated Blimp Rotational forces + + + Time since system startup + + + x-axis wobble rotational force + + + y-axis wobble rotational force + + + z-axis wobble rotational force + + + + + Simulated Blimp Torques + + + Time since system startup + + + torque around x axis + + + torque around y axis + + + torque around z axis + + + + + SmartRTL statistics + + + Time since system startup + + + true if SmartRTL could be used right now + + + number of points currently in use + + + maximum number of points that could be used + + + most recent internal action taken by SRTL library + + + 0 + + + 1 + + + 2 + + + 3 + + + 4 + + + 5 + + + 6 + + + 7 + + + 9 + + + 10 + + + 11 + + + + + point associated with most recent action (North component) + + + point associated with most recent action (East component) + + + point associated with most recent action (Down component) + + + + + Simulated Blimp Servo Inputs + + + Time since system startup + + + fin 0 servo angle input + + + fin 1 servo angle input + + + fin 2 servo angle input + + + fin 3 servo angle input + + + + + Stack information + + + Time since system startup + + + thread ID + + + thread priority + + + total stack + + + free stack + + + thread name + + + + + Current status of the aircraft + + + Time since system startup + + + True if aircraft is probably flying + + + Probability that the aircraft is flying + + + Arm status of the aircraft + + + State of the safety switch + + + True if crash is detected + + + True when vehicle is not moving in any axis + + + Current stage of the flight + + + True if impact is detected + + + True if throttle is suppressed + + + + + Helicopter swashplate logging + + + Time since system startup + + + Swashplate instance + + + Blade pitch angle contribution from collective + + + Total blade pitch angle contribution from cyclic + + + Blade pitch angle contribution from pitch cyclic + + + Blade pitch angle contribution from roll cyclic + + + + + Temperature Calibration Information + + + Time since system startup + + + temperature calibration instance number + + + sensor type (0==accel, 1==gyro) + + + current temperature + + + x-axis sample sum + + + y-axis sample sum + + + z-axis sample sum + + + sample count + + + + + http://ardupilot.org/plane/docs/tecs-total-energy-control-system-for-speed-height-tuning-guide.html + Additional information about the Total Energy Control System + + + Time since system startup + + + Potential energy weighting + + + Kinetic energy weighting + + + Energy balance demand + + + Energy balance estimate + + + Energy balance rate demand + + + Energy balance rate estimate + + + Energy balance rate demand + Energy balance rate error*pitch_damping + + + Minimum integrator value + + + Maximum integrator value + + + Energy balance error integral + + + Pitch demand kinetic energy integral + + + Throttle min + + + Throttle max + + + + + http://ardupilot.org/plane/docs/tecs-total-energy-control-system-for-speed-height-tuning-guide.html + Additional additional information about the Total Energy Control System + + + Time since system startup + + + Kinetic Energy Dot (1st derivative of KE) + + + Potential Energy Dot (1st derivative of PE) + + + Kinetic Energy Dot Demand + + + Potential Energy Dot Demand + + + Total energy error + + + Total energy dot error (1st derivative of total energy error) + + + feed-forward throttle + + + integrator limit based on throttle values + + + integrator limit based on throttle values + + + integrator state for throttle + + + lower limit for potential energy error + + + upper limit for potential energy error + + + + + http://ardupilot.org/plane/docs/tecs-total-energy-control-system-for-speed-height-tuning-guide.html + Additional additional additional information about the Total Energy Control System + + + Time since system startup + + + estimate of potential energy + + + estimate of kinetic energy + + + demanded potential energy + + + demanded kinetic energy + + + + + http://ardupilot.org/plane/docs/tecs-total-energy-control-system-for-speed-height-tuning-guide.html + Information about the Total Energy Control System + + + Time since system startup + + + height estimate (UP) currently in use by TECS + + + current climb rate ("delta-height") + + + height demand received by TECS + + + height demand after rate limiting and filtering that TECS is currently trying to achieve + + + climb rate TECS is currently trying to achieve + + + True AirSpeed TECS is currently trying to achieve + + + current estimated True AirSpeed + + + x-axis acceleration estimate ("delta-speed") + + + throttle output + + + pitch output + + + pitch lower limit + + + pitch upper limit + + + demanded acceleration output ("delta-speed demand") + + + flags + + + 1 + + + 2 + + + 4 + + + 8 + + + + + + + Temperature Sensor Data + + + Time since system startup + + + temperature sensor instance + + + temperature + + + + + Terrain database information + + + Time since system startup + + + Terrain database status + + + 0 + not enabled + + + 1 + no terrain data for current location + + + 2 + terrain data available + + + + + Current vehicle latitude + + + Current vehicle longitude + + + terrain Tile spacing + + + current Terrain height + + + Vehicle height above terrain + + + Number of tile requests outstanding + + + Number of tiles in memory + + + terrain reference offset for arming altitude + + + + + Tether state + + + Time since system startup + + + Tether length + + + Force on vehicle in North direction + + + Force on vehicle in East direction + + + Force on vehicle in Down direction + + + + + Tiltrotor tilt values + + + Time since system startup + + + Current tilt angle, 0 deg vertical, 90 deg horizontal + + + Front left tilt angle, 0 deg vertical, 90 deg horizontal + + + Front right tilt angle, 0 deg vertical, 90 deg horizontal + + + + + Camera shutter information + + + Time since system startup + + + Instance number + + + Image number + + + milliseconds since start of GPS week + + + weeks since 5 Jan 1980 + + + current latitude + + + current longitude + + + current altitude + + + current altitude relative to home + + + altitude as reported by GPS + + + current vehicle roll + + + current vehicle pitch + + + current vehicle yaw + + + + + Torqeedo Motor Param + + + Time since system startup + + + instance + + + Motor RPM + + + Motor power + + + Motor voltage + + + Motor current + + + ESC Temp + + + Motor Temp + + + + + Torqeedo Motor Status + + + Time since system startup + + + instance + + + Motor status flags + + + Motor error flags + + + + + Torqeedo Status + + + Time since system startup + + + instance + + + Health + + + Desired Motor Speed (-1000 to 1000) + + + Motor Speed (-1000 to 1000) + + + Success Count + + + Error Count + + + + + Torqeedo System Setup + + + Time since system startup + + + instance + + + Flags + + + Motor type + + + Motor software version + + + Battery capacity + + + Battery charge percentage + + + Battery type + + + Master software version + + + + + Torqeedo System State + + + Time since system startup + + + instance + + + Flags bitmask + + + Master error code + + + Motor voltage + + + Motor current + + + Motor power + + + Motor RPM + + + Motor Temp (higher of pcb or stator) + + + Battery charge percentage + + + Battery voltage + + + Battery current + + + + + tailsitter speed scaling values + + + Time since system startup + + + throttle scaling used for tilt motors + + + speed scaling used for control surfaces method from Q_TAILSIT_GSCMSK + + + minimum output throttle calculated from disk thoery gain scale with Q_TAILSIT_MIN_VO + + + + + Time synchronisation response information + + + Time since system startup + + + system ID this data is for + + + round trip time for this system + + + + + UART stats + + + Time since system startup + + + instance + + + transmitted data rate bytes per second + + + received data rate bytes per second, this is all incoming data, it may not all be processed by the driver using this port. + + + Data rate of dropped received bytes, ideally should be 0. This is the difference between the received data rate and the processed data rate. + + + + + uBlox-specific GPS information (part 1) + + + Time since system startup + + + GPS instance number + + + noise level as measured by GPS + + + jamming indicator; higher is more likely jammed + + + antenna power indicator; 2 is don't know + + + automatic gain control monitor + + + bitmask for messages which haven't been seen + + + + + uBlox-specific GPS information (part 2) + + + Time since system startup + + + GPS instance number + + + imbalance of I part of complex signal + + + magnitude of I part of complex signal + + + imbalance of Q part of complex signal + + + magnitude of Q part of complex signal + + + + + uBlox specific UBX-TIM-TM2 logging, see uBlox interface description + + + Time since system startup + + + GPS instance number + + + Channel (i.e. EXTINT) upon which the pulse was measured + + + Bitmask + + + Rising edge counter + + + Week number of last rising edge + + + Tow of rising edge + + + Millisecond fraction of tow of rising edge in nanoseconds + + + Week number of last falling edge + + + Tow of falling edge + + + Millisecond fraction of tow of falling edge in nanoseconds + + + Accuracy estimate + + + + + Message mapping from single character to SI unit + + + Time since system startup + + + character referenced by FMTU + + + Unit - SI where available + + + + + Variometer data + + + Time since system startup + + + always zero + + + filtered and constrained airspeed + + + AHRS altitude + + + AHRS roll + + + estimated air vertical speed + + + low-pass filtered air vertical speed + + + raw climb rate + + + filtered climb rate + + + expected sink rate relative to air in thermalling turn + + + average acceleration along X axis + + + detected bias in average acceleration along X axis + + + + + Ardupilot version + + + Time since system startup + + + Board type + + + 3 + + + 7 + + + 10 + + + 12 + + + 13 + + + 99 + + + + + Board subtype + + + -1 + + + 1000 + + + 1001 + + + 1002 + + + 1003 + + + 1005 + + + 1006 + + + 1009 + + + 1010 + + + 1012 + + + 1013 + + + 1014 + + + 1015 + + + 1016 + + + 1018 + + + 1020 + + + 1022 + + + 1023 + + + 1024 + + + 1025 + + + 1026 + + + 1027 + + + 1028 + + + 1029 + + + 1030 + + + + + Major version number + + + Minor version number + + + Patch number + + + Firmware type + + + Github commit + + + Firmware version string + + + Board ID + + + Build vehicle type + + + 1 + + + 2 + + + 3 + + + 4 + + + 5 + + + 6 + + + 7 + + + 8 + + + 9 + + + 10 + + + 11 + + + 12 + + + 13 + + + + + Filter version + + + IOMCU MCU ID + + + IOMCU CPU ID + + + + + Processed (acceleration) vibration information + + + Time since system startup + + + Vibration instance number + + + Primary accelerometer filtered vibration, x-axis + + + Primary accelerometer filtered vibration, y-axis + + + Primary accelerometer filtered vibration, z-axis + + + Number of clipping events on 1st accelerometer + + + + + Visual Odometry + + + System time + + + Time period this data covers + + + Angular change for body-frame roll axis + + + Angular change for body-frame pitch axis + + + Angular change for body-frame z axis + + + Position change for body-frame X axis (Forward-Back) + + + Position change for body-frame Y axis (Right-Left) + + + Position change for body-frame Z axis (Down-Up) + + + Confidence + + + + + Vision Position + + + System time + + + Remote system time + + + Corrected system time + + + Position X-axis (North-South) + + + Position Y-axis (East-West) + + + Position Z-axis (Down-Up) + + + Roll lean angle + + + Pitch lean angle + + + Yaw angle + + + Position estimate error + + + Attitude estimate error + + + Position reset counter + + + Ignored + + + Quality + + + + + Vision Velocity + + + System time + + + Remote system time + + + Corrected system time + + + Velocity X-axis (North-South) + + + Velocity Y-axis (East-West) + + + Velocity Z-axis (Down-Up) + + + Velocity estimate error + + + Velocity reset counter + + + Ignored + + + Quality + + + + + VectorNav Attitude data + + + Time since system startup + + + Attitude quaternion 1 + + + Attitude quaternion 2 + + + Attitude quaternion 3 + + + Attitude quaternion 4 + + + Yaw + + + Pitch + + + Roll + + + Yaw unceratainty + + + Pitch uncertainty + + + Roll uncertainty + + + + + VectorNav IMU data + + + Time since system startup + + + Temprature + + + Pressure + + + Magnetic feild X-axis + + + Magnetic feild Y-axis + + + Magnetic feild Z-axis + + + Acceleration X-axis + + + Acceleration Y-axis + + + Acceleration Z-axis + + + Rotation rate X-axis + + + Rotation rate Y-axis + + + Rotation rate Z-axis + + + + + VectorNav INS Kalman Filter data + + + Time since system startup + + + VectorNav INS health status + + + Latitude + + + Longitude + + + Altitude + + + Velocity Northing + + + Velocity Easting + + + Velocity Downing + + + Filter estimated position uncertainty + + + Filter estimated Velocity uncertainty + + + + + Log message for video stabilisation software such as Gyroflow + + + Time since system startup + + + measured rotation rate about X axis + + + measured rotation rate about Y axis + + + measured rotation rate about Z axis + + + acceleration along X axis + + + acceleration along Y axis + + + acceleration along Z axis + + + Estimated attitude quaternion component 1 + + + Estimated attitude quaternion component 2 + + + Estimated attitude quaternion component 3 + + + Estimated attitude quaternion component 4 + + + + + Watchdog diagnostics + + + Time since system startup + + + current task number + + + internal error mast + + + internal error count + + + line internal error was raised on + + + mavlink message being acted on + + + mavlink command being acted on + + + line semaphore was taken on + + + fault_line + + + fault_type + + + fault address + + + fault thread priority + + + ICS regiuster + + + long return address + + + Thread name + + + + + Wheel encoder measurements + + + Time since system startup + + + First wheel distance travelled + + + Quality measurement of Dist0 + + + Second wheel distance travelled + + + Quality measurement of Dist1 + + + + + Winch + + + Time since system startup + + + Healthy + + + Reached end of thread + + + Motor is moving + + + Clutch is engaged (motor can move freely) + + + 0 is Relaxed, 1 is Position Control, 2 is Rate Control + + + Desired Length + + + Estimated Length + + + Desired Rate + + + Tension on line + + + Voltage to Motor + + + Motor temperature + + + + + Windvane readings + + + Time since system startup + + + raw apparent wind direction direct from sensor, in body-frame + + + Apparent wind direction, in body-frame + + + True wind direction + + + raw wind speed direct from sensor + + + Apparent wind Speed + + + True wind speed + + + + + EKF3 beacon sensor diagnostics + + + Time since system startup + + + EKF3 core this data is for + + + Beacon sensor ID + + + Beacon range + + + Beacon range innovation + + + sqrt of beacon range innovation variance + + + Beacon range innovation consistency test ratio + + + Beacon north position + + + Beacon east position + + + Beacon down position + + + High estimate of vertical position offset of beacons rel to EKF origin + + + Low estimate of vertical position offset of beacons rel to EKF origin + + + North position of receiver rel to EKF origin + + + East position of receiver rel to EKF origin + + + Down position of receiver rel to EKF origin + + + + + EKF3 estimator outputs + + + Time since system startup + + + EKF3 core this data is for + + + Estimated roll + + + Estimated pitch + + + Estimated yaw + + + Estimated velocity (North component) + + + Estimated velocity (East component) + + + Estimated velocity (Down component) + + + Filtered derivative of vertical position (down) + + + Estimated distance from origin (North component) + + + Estimated distance from origin (East component) + + + Estimated distance from origin (Down component) + + + Estimated gyro bias, X axis + + + Estimated gyro bias, Y axis + + + Estimated gyro bias, Z axis + + + Height of origin above WGS-84 + + + + + EKF3 estimator secondary outputs + + + Time since system startup + + + EKF3 core this data is for + + + Estimated accelerometer X bias + + + Estimated accelerometer Y bias + + + Estimated accelerometer Z bias + + + Estimated wind velocity (moving-to-North component) + + + Estimated wind velocity (moving-to-East component) + + + Magnetic field strength (North component) + + + Magnetic field strength (East component) + + + Magnetic field strength (Down component) + + + Magnetic field strength (body X-axis) + + + Magnetic field strength (body Y-axis) + + + Magnetic field strength (body Z-axis) + + + Innovation in vehicle drag acceleration (X-axis component) + + + Innovation in vehicle drag acceleration (Y-axis component) + + + Innovation in vehicle sideslip + + + + + EKF3 innovations + + + Time since system startup + + + EKF3 core this data is for + + + Innovation in velocity (North component) + + + Innovation in velocity (East component) + + + Innovation in velocity (Down component) + + + Innovation in position (North component) + + + Innovation in position (East component) + + + Innovation in position (Down component) + + + Innovation in magnetic field strength (X-axis component) + + + Innovation in magnetic field strength (Y-axis component) + + + Innovation in magnetic field strength (Z-axis component) + + + Innovation in vehicle yaw + + + Innovation in true-airspeed + + + Accumulated relative error of this core with respect to active primary core + + + A consolidated error score where higher numbers are less healthy + + + + + EKF3 variances. SV, SP, SH and SM are probably best described as 'Squared Innovation Test Ratios' where values <1 tells us the measurement was accepted and >1 tells us it was rejected. They represent the square of the (innovation / maximum allowed innovation) where the innovation is the difference between predicted and measured value and the maximum allowed innovation is determined from the uncertainty of the measurement, uncertainty of the prediction and scaled using the number of standard deviations set by the innovation gate parameter for that measurement, eg EK3_MAG_I_GATE, EK3_HGT_I_GATE, etc + + + Time since system startup + + + EKF3 core this data is for + + + Square root of the velocity variance + + + Square root of the position variance + + + Square root of the height variance + + + Magnetic field variance + + + Square root of the total airspeed variance + + + Filtered error in roll/pitch estimate + + + Most recent position reset (North component) + + + Most recent position reset (East component) + + + Filter fault status + + + Filter timeout status bitmask (0:position measurement, 1:velocity measurement, 2:height measurement, 3:magnetometer measurement, 4:airspeed measurement, 5:drag measurement) + + + Filter solution status + + + 1 + attitude estimate valid + + + 2 + horizontal velocity estimate valid + + + 4 + vertical velocity estimate valid + + + 8 + relative horizontal position estimate valid + + + 16 + absolute horizontal position estimate valid + + + 32 + vertical position estimate valid + + + 64 + terrain height estimate valid + + + 128 + in constant position mode + + + 256 + expected good relative horizontal position estimate - used before takeoff + + + 512 + expected good absolute horizontal position estimate - used before takeoff + + + 1024 + optical flow takeoff has been detected + + + 2048 + compensating for baro errors during takeoff + + + 4096 + compensating for baro errors during touchdown + + + 8192 + using GPS position + + + 16384 + GPS glitching is affecting navigation accuracy + + + 32768 + can use GPS for navigation + + + 65536 + has ever been healthy + + + 131072 + rejecting airspeed data + + + 262144 + dead reckoning (e.g. no position or velocity source) + + + + + Filter GPS status + + + Primary core index + + + + + EKF3 Sensor innovations (primary core) and general dumping ground + + + Time since system startup + + + EKF3 core this data is for + + + Normalised flow variance + + + Optical flow LOS rate vector innovations from the main nav filter (X-axis) + + + Optical flow LOS rate vector innovations from the main nav filter (Y-axis) + + + Optical flow LOS rate innovation from terrain offset estimator + + + Height above ground level + + + Estimated vertical position of the terrain relative to the nav filter zero datum + + + Range finder innovations + + + Measured range + + + Filter ground offset state error + + + Magnitude of angular error + + + Magnitude of velocity error + + + Magnitude of position error + + + + + EKF3 Body Frame Odometry errors + + + Time since system startup + + + EKF3 core this data is for + + + Innovation in velocity (X-axis) + + + Innovation in velocity (Y-axis) + + + Innovation in velocity (Z-axis) + + + Variance in velocity (X-axis) + + + Variance in velocity (Y-axis) + + + Variance in velocity (Z-axis) + + + + + EKF3 diagnostic data for on-ground-and-not-moving check + + + Time since system startup + + + EKF core this message instance applies to + + + True of on ground and not moving + + + Gyroscope length ratio + + + Accelerometer length ratio + + + Gyroscope rate of change ratio + + + Accelerometer rate of change ratio + + + + + EKF3 sensor selection + + + Time since system startup + + + EKF3 core this data is for + + + compass selection index + + + barometer selection index + + + GPS selection index + + + airspeed selection index + + + Source Set (primary=0/secondary=1/tertiary=2) + + + GPS good to align + + + Waiting for GPS checks to pass + + + Magnetometer fusion (0=not fusing/1=fuse yaw/2=fuse mag) + + + + + EKF3 quaternion defining the rotation from NED to XYZ (autopilot) axes + + + Time since system startup + + + EKF3 core this data is for + + + Quaternion a term + + + Quaternion b term + + + Quaternion c term + + + Quaternion d term + + + + + EKF3 timing information + + + Time since system startup + + + EKF core this message instance applies to + + + count of samples used to create this message + + + smallest IMU sample interval + + + largest IMU sample interval + + + low-passed achieved average time step rate for the EKF (minimum) + + + low-passed achieved average time step rate for the EKF (maximum) + + + accumulated measurement time interval for the delta angle (minimum) + + + accumulated measurement time interval for the delta angle (maximum) + + + accumulated measurement time interval for the delta velocity (minimum) + + + accumulated measurement time interval for the delta velocity (maximum) + + + + + EKF3 Yaw Estimator States + + + Time since system startup + + + EKF3 core this data is for + + + Tilt Error Variance from symbolic equations (rad^2) + + + Tilt Error Variance from difference method (rad^2) + + + + + EKF3 State variances (primary core) + + + Time since system startup + + + EKF3 core this data is for + + + Variance for state 0 (attitude quaternion) + + + Variance for state 1 (attitude quaternion) + + + Variance for state 2 (attitude quaternion) + + + Variance for state 3 (attitude quaternion) + + + Variance for state 4 (velocity-north) + + + Variance for state 5 (velocity-east) + + + Variance for state 6 (velocity-down) + + + Variance for state 7 (position-north) + + + Variance for state 8 (position-east) + + + Variance for state 9 (position-down) + + + Variance for state 10 (delta-angle-bias-x) + + + Variance for state 11 (delta-angle-bias-y) + + + + + more EKF3 State Variances (primary core) + + + Time since system startup + + + EKF3 core this data is for + + + Variance for state 12 (delta-angle-bias-z) + + + Variance for state 13 (delta-velocity-bias-x) + + + Variance for state 14 (delta-velocity-bias-y) + + + Variance for state 15 (delta-velocity-bias-z) + + + Variance for state 16 (Earth-frame mag-field-bias-x) + + + Variance for state 17 (Earth-frame mag-field-bias-y) + + + Variance for state 18 (Earth-frame mag-field-bias-z) + + + Variance for state 19 (body-frame mag-field-bias-x) + + + Variance for state 20 (body-frame mag-field-bias-y) + + + Variance for state 21 (body-frame mag-field-bias-z) + + + Variance for state 22 (wind-north) + + + Variance for state 23 (wind-east) + + + + + EKF Yaw Estimator States + + + Time since system startup + + + EKF core this data is for + + + GSF yaw estimate (deg) + + + GSF yaw estimate 1-Sigma uncertainty (deg) + + + Yaw estimate from individual EKF filter 0 (deg) + + + Yaw estimate from individual EKF filter 1 (deg) + + + Yaw estimate from individual EKF filter 2 (deg) + + + Yaw estimate from individual EKF filter 3 (deg) + + + Yaw estimate from individual EKF filter 4 (deg) + + + Weighting applied to yaw estimate from individual EKF filter 0 + + + Weighting applied to yaw estimate from individual EKF filter 1 + + + Weighting applied to yaw estimate from individual EKF filter 2 + + + Weighting applied to yaw estimate from individual EKF filter 3 + + + Weighting applied to yaw estimate from individual EKF filter 4 + + + + + EKF Yaw Estimator Innovations + + + Time since system startup + + + EKF core this data is for + + + North velocity innovation from individual EKF filter 0 (m/s) + + + North velocity innovation from individual EKF filter 1 (m/s) + + + North velocity innovation from individual EKF filter 2 (m/s) + + + North velocity innovation from individual EKF filter 3 (m/s) + + + North velocity innovation from individual EKF filter 4 (m/s) + + + East velocity innovation from individual EKF filter 0 (m/s) + + + East velocity innovation from individual EKF filter 1 (m/s) + + + East velocity innovation from individual EKF filter 2 (m/s) + + + East velocity innovation from individual EKF filter 3 (m/s) + + + East velocity innovation from individual EKF filter 4 (m/s) + + + + diff --git a/DataLoadAPBin/dataload_apbin.cpp b/DataLoadAPBin/dataload_apbin.cpp index 39d30c2..391b7a5 100644 --- a/DataLoadAPBin/dataload_apbin.cpp +++ b/DataLoadAPBin/dataload_apbin.cpp @@ -15,10 +15,17 @@ #include #include #include +#include +#include +#include +#include +#include "LogMessageDescriptions.h" #include #include #include #include +#include +#include // Debugging @@ -529,6 +536,11 @@ bool DataLoadAPBIN::readDataFromFile(FileLoadInfo* info, PlotDataMapRef& plot_da // -------------------- publish to plotjuggler -------------------- // +#ifdef QT_CORE_LIB + load_log_messages(info->filename); +#else + load_log_messages(info->filename); +#endif #ifdef DEBUG_RUNTIME auto publish_start = std::chrono::high_resolution_clock::now(); #endif @@ -561,6 +573,10 @@ bool DataLoadAPBIN::readDataFromFile(FileLoadInfo* info, PlotDataMapRef& plot_da const std::vector& timestamps = msg_data[time_idx].second; size_t idx = 0; + bool message_desc_assigned = false; + std::string message_desc; + auto mit = _message_tooltips.find(msg_name); + if (mit != _message_tooltips.end()) message_desc = mit->second; for (const auto& field : msg_data) { if ( idx == time_idx || ( has_instance[msg_id] && (idx == instance_idx[msg_id]) ) ) @@ -606,6 +622,30 @@ bool DataLoadAPBIN::readDataFromFile(FileLoadInfo* info, PlotDataMapRef& plot_da auto series = plot_data.addNumeric(series_name); + // Prefer per-field descriptions. Only attach message description to the + // first series for this message instance that does not have a field description. + std::string field_desc; + auto fit_map_it = _field_tooltips.find(msg_name); + if (fit_map_it != _field_tooltips.end()) + { + auto fit = fit_map_it->second.find(field_name); + if (fit != fit_map_it->second.end()) + { + field_desc = fit->second; + } + } + + if (!field_desc.empty()) + { + series->second.setAttribute(PJ::TOOL_TIP, QString::fromStdString(field_desc)); + } + else if (!message_desc_assigned && !message_desc.empty()) + { + // attach message description once for this instance + series->second.setAttribute(PJ::TOOL_TIP, QString::fromStdString(message_desc)); + message_desc_assigned = true; + } + for (size_t i = 0; i < field.second.size(); i++) { const double& msg_time = timestamps[i]; @@ -995,6 +1035,73 @@ std::string DataLoadAPBIN::get_unit(const std::string& msg_name, const std::stri } +void DataLoadAPBIN::load_log_messages(const QString& datafile_path) +{ + // Helper to parse a QXmlStreamReader and merge descriptions + auto parseXml = [&](QXmlStreamReader &xml) { + while (!xml.atEnd() && !xml.hasError()) + { + xml.readNext(); + if (xml.isStartElement() && xml.name() == QLatin1String("logformat")) + { + QString msgName = xml.attributes().value(QLatin1String("name")).toString(); + QString msgDesc; + + // process children until end of this logformat + while (!(xml.isEndElement() && xml.name() == QLatin1String("logformat"))) + { + xml.readNext(); + if (xml.isStartElement()) + { + if (xml.name() == QLatin1String("description")) + { + msgDesc = xml.readElementText().trimmed(); + _message_tooltips[msgName.toStdString()] = msgDesc.toStdString(); + } + else if (xml.name() == QLatin1String("field")) + { + QString fieldName = xml.attributes().value(QLatin1String("name")).toString(); + // read inside field until end + while (!(xml.isEndElement() && xml.name() == QLatin1String("field"))) + { + xml.readNext(); + if (xml.isStartElement() && xml.name() == QLatin1String("description")) + { + QString fdesc = xml.readElementText().trimmed(); + _field_tooltips[msgName.toStdString()][fieldName.toStdString()] = fdesc.toStdString(); + } + } + } + } + } + } + } + }; + + // First, parse embedded XMLs compiled into the library (if present). + // Use a sanity check on the embedded C-string rather than relying on sizeof. + if (kEmbeddedLogMessagesXml[0] != '\0') + { + const char* emb = kEmbeddedLogMessagesXml; + size_t emb_len = std::strlen(emb); + // require a minimal length and at least one '<' character after skipping whitespace + if (emb_len > 10) + { + size_t i = 0; + while (i < emb_len && std::isspace(static_cast(emb[i]))) ++i; + if (i < emb_len && emb[i] == '<') + { + QXmlStreamReader xmlEmbedded(QString::fromUtf8(emb)); + parseXml(xmlEmbedded); + if (xmlEmbedded.hasError()) + { + qDebug() << "Warning: embedded log message XML parse error:" << xmlEmbedded.errorString(); + } + } + } + } +} + void DataLoadAPBIN::apply_multipliers(void) { diff --git a/DataLoadAPBin/dataload_apbin.h b/DataLoadAPBin/dataload_apbin.h index 3e42eab..7ea0ff1 100644 --- a/DataLoadAPBin/dataload_apbin.h +++ b/DataLoadAPBin/dataload_apbin.h @@ -106,6 +106,13 @@ class DataLoadAPBIN : public DataLoader // get unit string for a field std::string get_unit(const std::string& msg_name, const std::string& field_name); + // load human readable descriptions from LogMessages.xml + void load_log_messages(const QString& datafile_path); + + // tooltips/descriptions loaded from LogMessages.xml + std::map _message_tooltips; + std::map> _field_tooltips; + // apply multipliers from FMTU and MULT messages to the messages_map void apply_multipliers(void); diff --git a/DataLoadAPBin/scripts/generate_LogMessageDescriptions_header.py b/DataLoadAPBin/scripts/generate_LogMessageDescriptions_header.py new file mode 100644 index 0000000..3664dbd --- /dev/null +++ b/DataLoadAPBin/scripts/generate_LogMessageDescriptions_header.py @@ -0,0 +1,86 @@ +#!/usr/bin/env python3 +""" +Generate a C header containing raw string literals with embedded XML +for Plane.xml and Copter.xml if present. If they are missing, emit +empty strings so the code compiles but no embedded content is used. + +Usage: + generate_LogMessageDescriptions_header.py + +The script reads any xml files in if present. +""" +import sys +import os + +def read_file_safe(path): + try: + with open(path, 'r', encoding='utf-8') as f: + return f.read() + except Exception: + return '' + +def make_raw_string(name, content): + # Use a delimiter unlikely to appear in XML + delim = 'XML_DELIM' + return 'static const char ' + name + '[] = R"' + delim + '(' + content + ')' + delim + '";\n\n' + +def main(): + if len(sys.argv) < 3: + print('Usage: generate_LogMessageDescriptions_header.py ') + return 2 + input_dir = sys.argv[1] + out_path = sys.argv[2] + + contents = [] + contents.append('/* Auto-generated by generate_LogMessageDescriptions_header.py */') + contents.append('#pragma once') + contents.append('\n') + + # Read any XML files in the input directory and merge them into one embedded variable. + merged = [] + if os.path.isdir(input_dir): + for entry in sorted(os.listdir(input_dir)): + # accept files with .xml extension (case-insensitive) or any file + if not os.path.isfile(os.path.join(input_dir, entry)): + continue + _, ext = os.path.splitext(entry) + if ext.lower() != '.xml': + # skip non-XML files + continue + fpath = os.path.join(input_dir, entry) + xml = read_file_safe(fpath) + if not xml: + continue + # strip BOM if present + if xml.startswith('\ufeff'): + xml = xml.lstrip('\ufeff') + merged.append(xml) + + # Strip XML prologs and wrap merged content in a single root so the parser + # can consume multiple files as one well-formed XML document. + processed = [] + for xml in merged: + s = xml.lstrip() + if s.startswith('') + if idx != -1: + s = s[idx+2:] + processed.append(s) + + merged_inner = '\n'.join(processed) + if merged_inner: + merged_content = '\n' + merged_inner + '\n' + else: + merged_content = '' + + contents.append(make_raw_string('kEmbeddedLogMessagesXml', merged_content)) + + # Write header directory (ensure parent exists) + os.makedirs(os.path.dirname(out_path) or '.', exist_ok=True) + with open(out_path, 'w', encoding='utf-8') as out: + out.write('\n'.join(contents)) + + return 0 + +if __name__ == '__main__': + sys.exit(main()) From faa966aac27a99a28cfdf0df1fe6380aff00dfb3 Mon Sep 17 00:00:00 2001 From: Terran Gerratt Date: Fri, 23 Jan 2026 22:23:42 -0700 Subject: [PATCH 6/6] update build instructions and other helpful comments --- .../generate_LogMessageDescriptions_header.py | 7 ++++--- README.md | 13 +++++++++++++ 2 files changed, 17 insertions(+), 3 deletions(-) diff --git a/DataLoadAPBin/scripts/generate_LogMessageDescriptions_header.py b/DataLoadAPBin/scripts/generate_LogMessageDescriptions_header.py index 3664dbd..66067c9 100644 --- a/DataLoadAPBin/scripts/generate_LogMessageDescriptions_header.py +++ b/DataLoadAPBin/scripts/generate_LogMessageDescriptions_header.py @@ -1,13 +1,14 @@ #!/usr/bin/env python3 """ Generate a C header containing raw string literals with embedded XML -for Plane.xml and Copter.xml if present. If they are missing, emit -empty strings so the code compiles but no embedded content is used. +for files from https://autotest.ardupilot.org/LogMessages/ (i.e. Plane.xml and Copter.xml) +If they are missing, emit empty strings so the code compiles but no embedded content is used. Usage: generate_LogMessageDescriptions_header.py -The script reads any xml files in if present. +The script reads any xml files in and merges them into a single header file. +Any updates to the XML files requires rebuilding the project to embed the new content. """ import sys import os diff --git a/README.md b/README.md index 1363ef0..be60577 100644 --- a/README.md +++ b/README.md @@ -88,6 +88,19 @@ If you compiled the plugin in your host system, the plugin has been installed to Ensure that PlotJuggler scans for plugins in this folder or copy the plugin in one of the folders PlotJuggler already scans. +## Notes for building on MacOS +Some of the dependencies weren't found automatically, I had to run the following to make everything happy (These might be specific to my setup, but I figure it might help someone else as well. Obviously update your paths accordingly). +``` +cmake -DCMAKE_PREFIX_PATH="/opt/homebrew/opt/qt@5;~/plotjuggler_ws/install/lib/cmake/plotjuggler" -DCMAKE_LIBRARY_PATH="~/plotjuggler_ws/install/lib;~/plotjuggler_ws/build/PlotJuggler" .. + +export LIBRARY_PATH="$LIBRARY_PATH:~/plotjuggler_ws/install/lib" +``` +If using this plugin with the new official PlotJuggler .dmg releases, you may ran into signing and security issues. This command allowed me to run a custom plugin on a signed version of PlotJuggler: +``` +sudo codesign --force --deep --sign - /Applications/PlotJuggler.app +``` +As far as I understand, this adds your signature to the app so your plugin and the official .dmg now share a common signature. + ## Displaying units This plugin allows the units of logged fields to be appended to the logged field names.