PX4 User Guide
  • Introduction
  • Getting Started
    • Basic Concepts
    • Vehicles/Frames
    • Flight Controllers
    • Sensors
    • Radio Systems
    • Flight Modes
    • Vehicle Status Notifications
      • LED Meanings
      • Tune/Sound Meanings
      • Preflight Checks
    • Payloads & Cameras
    • Flight Reporting
  • Basic Assembly
    • Mounting the Flight Controller
    • Mounting the GPS/Compass
    • Vibration Isolation
    • Cable Wiring
    • CUAV Pixhawk V6X Wiring QuickStart
    • CUAV V5+ Wiring Quickstart
    • CUAV V5 nano Wiring Quickstart
    • Holybro Pixhawk 6C Wiring Quickstart
    • Holybro Pixhawk 6X Wiring Quickstart
    • Holybro Pixhawk 5X Wiring Quickstart
    • Holybro Pixhawk 4 Wiring Quickstart - Discontinued
    • Holybro Pixhawk 4 Mini Wiring Quickstart - Discontinued
    • Holybro Durandal Wiring Quickstart
    • Holybro Pix32 v5 Wiring Quickstart
    • Cube Wiring Quickstart
    • Pixracer Wiring Quickstart
    • mRo (3DR) Pixhawk Wiring Quickstart
  • Standard Configuration
    • Firmware
    • Airframe
    • Sensor Orientation
    • Compass
    • Gyroscope
    • Accelerometer
    • Airspeed
    • Level Horizon Calibration
    • Radio Setup
    • Joystick Setup
    • Flight Modes
    • Battery
    • Safety
      • Failsafe Simulation
    • ESC Calibration
    • Actuators
    • Autotune
  • Vehicle Types & Setup
    • Multicopters
      • Multicopter Config/Tuning
        • MC Filter/Control Latency Tuning
        • MC PID Tuning (Manual/Basic)
        • MC PID Tuning Guide (Manual/Advanced)
        • MC Setpoint Tuning (Trajectory Generator)
          • MC Jerk-limited Type Trajectory
        • Multicopter Racer Setup
      • X500 v2 (Pixhawk 6C)
      • X500 v2 (Pixhawk 5X)
      • X500 (Pixhawk 4)
      • S500 V2 (Pixhawk 4)
      • DJI F450 (CUAV v5+)
      • DJI F450 (CUAV v5 nano)
      • QAV250 (Pixhawk4 Mini) - Discontinued
      • DJI F450 + RTK (Pixhawk 3 Pro)
      • QAV250 (Pixhawk Mini)
      • QAV-R 5" Racer (Pixracer)
      • Omnicopter
    • Planes
      • Fixed Wing Config/Tuning
        • Fixedwing PID Tuning Guide
        • Fixedwing Advanced Tuning Guide
        • Fixedwing Trimming Guide
      • Reptile Dragon 2 (ARK6X)
      • Turbo Timber Evolution (Pixhawk 4 Mini)
      • Wing Wing Z84 (Pixracer)
    • VTOL
      • VTOL Config/Tuning
        • QuadPlane Configuration
        • Back-transition Tuning
        • VTOL w/o Airspeed Sensor
        • VTOL Weather Vane
      • Standard VTOL
        • FunCub QuadPlane (Pixhawk)
        • Ranger QuadPlane (Pixhawk)
        • Falcon Vertigo QuadPlane (Dropix)
      • Tailsitter VTOL
        • Build: TBS Caipiroshka Tailsitter Build (Pixracer)
      • Tiltrotor VTOL
        • Build: Convergence Tiltrotor (Pixfalcon)
    • Airships (experimental)
    • Autogyros (experimental)
      • ThunderFly Auto-G2 (Holybro pix32)
    • Balloons (experimental)
    • Helicopter (experimental)
      • Helicopter Config/Tuning
    • Rovers (experimental)
      • Traxxas Stampede
    • Submarines (experimental)
      • BlueROV2
    • Airframes Reference
  • Flying
    • First Flight Guidelines
    • Flying 101
    • Missions
      • Package Delivery Mission
    • GeoFence
    • Safety Point Planning
    • Flight Modes
      • Position Mode (MC)
      • Altitude Mode (MC)
      • Manual/Stabilized Mode (MC)
      • Acro Mode (MC)
      • Orbit Mode (MC)
      • Position Mode (FW)
      • Altitude Mode (FW)
      • Stabilized Mode (FW)
      • Acro Mode (FW)
      • Manual Mode (FW)
      • Takeoff Mode
      • Land Mode
      • Return Mode
      • Hold Mode
      • Mission Mode
      • Follow Me Mode
      • Offboard Mode
    • Terrain Following/Holding
  • Flight Log Analysis
    • Log Analysis using Flight Review
    • Log Analysis using PlotJuggler
  • Advanced Configuration
    • Finding/Updating Parameters
    • Full Parameter Reference
    • ECL/EKF Overview & Tuning
    • Flight Termination Configuration
    • Bootloader Flashing onto Betaflight Systems
    • Land Detector Configuration
    • Prearm/Arm/Disarm Configuration
    • IMU Factory Calibration
    • Sensor Thermal Compensation
    • Compass Power Compensation
    • Advanced Controller Orientation
    • Static Pressure Buildup
    • Serial Port Configuration
    • MAVLink Telemetry (OSD/GCS)
    • PX4 Ethernet Setup
    • Bootloader Update
  • Hardware (Drones&Parts)
    • Complete Vehicles
      • ModalAI Starling
      • PX4 Vision Kit
      • MindRacer BNF & RTF
        • MindRacer 210
        • NanoMind 110
      • Holybro Kopis 2
      • Bitcraze Crazyflie 2.1
    • Flight Controllers (Autopilots)
      • Pixhawk Series
        • Silicon Errata
      • Pixhawk Standard Autopilots
        • CUAV Pixhawk V6X (FMUv6X)
        • Holybro Pixhawk 6X (FMUv6X)
        • Holybro Pixhawk 6C (FMUv6C)
        • Holybro Pixhawk 6C Mini(FMUv6C)
        • Holybro Pix32 v6 (FMUv6C)
        • Holybro Pixhawk 5X (FMUv5X)
        • Holybro Pixhawk 4 (FMUv5) - Discontinued
        • Holybro Pixhawk 4 Mini (FMUv5) - Discontinued
        • Drotek Pixhawk 3 Pro (FMUv4pro)
        • mRo Pixracer (FMUv4)
        • Hex Cube Black (FMUv3)
        • mRo Pixhawk (FMUv3)
        • Holybro Pixhawk Mini (FMUv3) - Discontinued
      • Manufacturer-Supported Autopilots
        • AirMind MindPX
        • AirMind MindRacer
        • ARK Electronics ARKV6X
        • CUAV X7
        • CUAV Nora
        • CUAV V5+ (FMUv5)
        • CUAV V5 nano (FMUv5)
        • CUAV Pixhack v3 (FMUv3)
        • CubePilot Cube Orange+ (CubePilot)
        • CubePilot Cube Orange (CubePilot)
        • CubePilot Cube Yellow (CubePilot)
        • Holybro Kakute H7v2
        • Holybro Kakute H7mini
        • Holybro Kakute H7
        • Holybro Durandal
        • Holybro Pix32 v5
        • ModalAI Flight Core v1
        • ModalAI VOXL Flight
        • ModalAI VOXL 2
        • mRobotics-X2.1 (FMUv2)
        • mRo Control Zero F7)
        • NXP RDDRONE-FMUK66 FMU
        • Sky-Drones AIRLink
        • SPRacing SPRacingH7EXTREME
        • ThePeach FCC-K1
        • ThePeach FCC-R1
      • Experimental Autopilots
        • BeagleBone Blue
        • Raspberry Pi 2/3 Navio2
        • Raspberry Pi 2/3/4 PilotPi
          • PilotPi with Raspberry Pi OS
          • PilotPi with Ubuntu Server
      • Discontinued Autopilots/Vehicles
        • Drotek Dropix (FMUv2)
        • Omnibus F4 SD
        • BetaFPV Beta75X 2S Brushless Whoop
        • Bitcraze Crazyflie 2.0
        • Aerotenna OcPoC-Zynq Mini
        • CUAV v5
        • Holybro Kakute F7 (Discontinued)
        • Holybro Pixfalcon
        • Holybro pix32 (FMUv2)
        • mRo AUAV-X2
        • 3DR Pixhawk 1
        • Snapdragon Flight
        • Intel® Aero RTF Drone (Discontinued)
      • Pixhawk Autopilot Bus (PAB) & Carriers
        • ARK Electronics Pixhawk Autopilot Bus Carrier
    • Flight Controller Peripherals
      • ADSB/FLARM (Traffic Avoidance)
      • Air Traffic Avoidance: ADSB/FLARM
      • Air Traffic Avoidance: UTM
      • Airspeed Sensors
        • TFSlot Airspeed Sensor
      • Barometers
      • Camera
      • Distance Sensors (Rangefinders)
        • Lightware SFxx Lidar
        • Ainstein US-D1 Standard Radar Altimeter
        • LeddarOne Lidar
        • Benewake TFmini Lidar
        • Lidar-Lite
        • TeraRanger
        • Lanbao PSK-CM8JL65-CC5
        • Avionics Anonymous Laser Altimeter UAVCAN Interface
      • ESCs & Motors
        • PWM ESCs and Servos
        • DShot ESCs
        • OneShot ESCs and Servos
        • DroneCAN ESCs
          • Zubax Telega
          • PX4 Sapog ESC Firmware
            • Holybro Kotleta
            • Zubax Orel
        • VESC
      • TBS Crossfire (CRSF) Telemetry
      • FrSky Telemetry
      • Gimbal (Mount) Configuration
      • GPS/Compass
        • ARK GPS
        • Holybro DroneCAN M8N GPS
        • LOCOSYS Hawk A1 GNSS
        • Hex Here2
        • Holybro M8N & M9N GPS
        • Sky-Drones SmartAP GPS
      • Grippers
        • Servo Gripper
      • Optical Flow
        • ARK Flow
        • PMW3901
        • PX4FLOW (Deprecated)
      • Precision Landing
      • Parachute
      • Power Modules/PDB
        • CUAV HV pm
        • CUAV CAN PMU
        • Holybro PM02
        • Holybro PM07
        • Holybro PM06 V2
        • Holybro PM02D (digital)
        • Holybro PM03D (digital)
        • Pomegranate Systems Power Module
        • Sky-Drones SmartAP PDB
      • Satellite Coms (Iridium/RockBlock)
      • Telemetry Radios
        • SiK Radio
          • RFD900 (SiK) Telemetry Radio
          • HolyBro (SIK) Telemetry Radio
        • Telemetry Wifi
          • ESP8266 WiFi Module
          • ESP32 WiFi Module
          • 3DR Telemetry Wifi (Discontinued)
        • Microhard Serial Telemetry Radio
          • ARK Electron Microhard Serial Telemetry Radio
          • Holybro Microhard P900 Telemetry Radio
        • CUAV P8 Telemetry Radio
        • HolyBro XBP9X - Discontinued
      • RTK GPS
        • ARK RTK GPS
        • RTK GPS Heading with Dual u-blox F9P
        • CUAV C-RTK
        • CUAV C-RTK2 PPK/RTK GNSS
        • CUAV C-RTK 9Ps
        • Femtones MINI2 Receiver
        • Freefly RTK GPS
        • Holybro H-RTK-F9P
        • Holybro H-RTK-M8P
        • Holybro H-RTK Unicore UM982 GPS
        • Locosys Hawk R1
        • Locosys Hawk R2
        • Septentrio AsteRx-RIB
        • Septentrio mosaic-go
        • Trimble MB-Two
        • CubePilot Here+ (Discontined)
      • Remote ID
      • Smart Batteries
        • Rotoye Batmon Battery Smartification Kit
      • Tachometers (Revolution Counters)
        • ThunderFly TFRPM01 Tachometer Sensor
      • I2C Peripherals
        • I2C bus accelerators
        • TFI2CADT01 I2C address translator
      • CAN Peripherals
      • DroneCAN Peripherals
        • PX4 DroneCAN Firmware
        • ARK CANnode
    • Companion Computers
      • Pixhawk + Companion Setup
        • RasPi Pixhawk Companion
      • Companion Computer Peripherals
      • Holybro Pixhawk RPI CM4 Baseboard
      • Auterion Skynode
      • Computer Vision
        • Obstacle Avoidance
        • Safe Landing
        • Collision Prevention
        • Path Planning Interface
        • Motion Capture (MoCap)
        • Visual Inertial Odometry (VIO)
          • Realsense T265 Tracking Camera (VIO)
      • Video Streaming
  • Development
    • Getting Started
      • Recommended Hardware/Setup
      • Toolchain Installation
        • MacOS Setup
        • Ubuntu Setup
        • Windows Setup
        • Visual Studio Code IDE
        • Other/Generic Tools
      • Building the Code
      • Writing your First Application
      • Application/Module Template
    • Concepts
      • PX4 Architecture
      • PX4 Flight Stack Architecture
        • Controller Diagrams
      • Events Interface
      • Flight Modes
      • Flight Tasks
      • Control Allocation
      • PWM limit state machine
      • System Startup
      • SD Card Layout
    • Simulation
      • jMAVSim Simulation
        • Multi-Vehicle Sim with JMAVSim
      • Gazebo Simulation
        • Vehicles
        • Multi-Vehicle Sim
      • Gazebo Classic Simulation
        • Vehicles
        • Worlds
        • Multi-Vehicle Sim
      • FlightGear Simulation
        • FlightGear Vehicles
        • Multi-Vehicle Sim with FlightGear
      • JSBSim Simulation
      • AirSim Simulation
      • Multi-Vehicle Simulation
      • Simulate Failsafes
      • HITL Simulation
      • Simulation-In-Hardware
    • Hardware
      • Flight Controller Reference Design
      • Manufacturer’s Board Support Guide
      • Flight Controller Porting Guide
        • PX4 Board Configuration (kconfig)
        • NuttX Board Porting Guide
      • Serial Port Mapping
      • Airframes
        • Adding a New Airframe
      • Device Drivers
      • Telemetry Radio
        • SiK Radio
      • Sensor and Actuator I/O
        • DroneCAN
        • I2C Bus
        • UART/Serial Ports
          • Port-Configurable Serial Drivers
      • RTK GPS (Integration)
    • Middleware
      • uORB Messaging
      • uORB Graph
      • uORB Message Reference
        • ActionRequest
        • ActuatorArmed
        • ActuatorControlsStatus
        • ActuatorMotors
        • ActuatorOutputs
        • ActuatorServos
        • ActuatorServosTrim
        • ActuatorTest
        • AdcReport
        • Airspeed
        • AirspeedValidated
        • AirspeedWind
        • AutotuneAttitudeControlStatus
        • BatteryStatus
        • ButtonEvent
        • CameraCapture
        • CameraStatus
        • CameraTrigger
        • CellularStatus
        • CollisionConstraints
        • CollisionReport
        • ControlAllocatorStatus
        • Cpuload
        • DebugArray
        • DebugKeyValue
        • DebugValue
        • DebugVect
        • DifferentialPressure
        • DistanceSensor
        • Ekf2Timestamps
        • EscReport
        • EscStatus
        • EstimatorAidSource1d
        • EstimatorAidSource2d
        • EstimatorAidSource3d
        • EstimatorBias
        • EstimatorBias3d
        • EstimatorEventFlags
        • EstimatorGpsStatus
        • EstimatorInnovations
        • EstimatorSelectorStatus
        • EstimatorSensorBias
        • EstimatorStates
        • EstimatorStatus
        • EstimatorStatusFlags
        • Event
        • FailsafeFlags
        • FailureDetectorStatus
        • FollowTarget
        • FollowTargetEstimator
        • FollowTargetStatus
        • GeneratorStatus
        • GeofenceResult
        • GimbalControls
        • GimbalDeviceAttitudeStatus
        • GimbalDeviceInformation
        • GimbalDeviceSetAttitude
        • GimbalManagerInformation
        • GimbalManagerSetAttitude
        • GimbalManagerSetManualControl
        • GimbalManagerStatus
        • GpioConfig
        • GpioIn
        • GpioOut
        • GpioRequest
        • GpsDump
        • GpsInjectData
        • Gripper
        • HealthReport
        • HeaterStatus
        • HomePosition
        • HoverThrustEstimate
        • InputRc
        • InternalCombustionEngineStatus
        • IridiumsbdStatus
        • IrlockReport
        • LandingGear
        • LandingGearWheel
        • LandingTargetInnovations
        • LandingTargetPose
        • LaunchDetectionStatus
        • LedControl
        • LogMessage
        • LoggerStatus
        • MagWorkerData
        • MagnetometerBiasEstimate
        • ManualControlSetpoint
        • ManualControlSwitches
        • MavlinkLog
        • MavlinkTunnel
        • Mission
        • MissionResult
        • ModeCompleted
        • MountOrientation
        • NavigatorMissionItem
        • NormalizedUnsignedSetpoint
        • NpfgStatus
        • ObstacleDistance
        • OffboardControlMode
        • OnboardComputerStatus
        • OrbTest
        • OrbTestLarge
        • OrbTestMedium
        • OrbitStatus
        • ParameterUpdate
        • Ping
        • PositionControllerLandingStatus
        • PositionControllerStatus
        • PositionSetpoint
        • PositionSetpointTriplet
        • PowerButtonState
        • PowerMonitor
        • PpsCapture
        • PwmInput
        • Px4ioStatus
        • QshellReq
        • QshellRetval
        • RadioStatus
        • RateCtrlStatus
        • RcChannels
        • RcParameterMap
        • Rpm
        • RtlTimeEstimate
        • SatelliteInfo
        • SensorAccel
        • SensorAccelFifo
        • SensorBaro
        • SensorCombined
        • SensorCorrection
        • SensorGnssRelative
        • SensorGps
        • SensorGyro
        • SensorGyroFft
        • SensorGyroFifo
        • SensorHygrometer
        • SensorMag
        • SensorOpticalFlow
        • SensorPreflightMag
        • SensorUwb
        • SensorSelection
        • SensorsStatus
        • SensorsStatusImu
        • SystemPower
        • TakeoffStatus
        • TaskStackInfo
        • TecsStatus
        • TelemetryStatus
        • TiltrotorExtraControls
        • TimesyncStatus
        • TrajectoryBezier
        • TrajectorySetpoint
        • TrajectoryWaypoint
        • TransponderReport
        • TuneControl
        • UavcanParameterRequest
        • UavcanParameterValue
        • UlogStream
        • UlogStreamAck
        • UwbDistance
        • UwbGrid
        • VehicleAcceleration
        • VehicleAirData
        • VehicleAngularAccelerationSetpoint
        • VehicleAngularVelocity
        • VehicleAttitude
        • VehicleAttitudeSetpoint
        • VehicleCommand
        • VehicleCommandAck
        • VehicleConstraints
        • VehicleControlMode
        • VehicleGlobalPosition
        • VehicleImu
        • VehicleImuStatus
        • VehicleLandDetected
        • VehicleLocalPosition
        • VehicleLocalPositionSetpoint
        • VehicleMagnetometer
        • VehicleOdometry
        • VehicleOpticalFlow
        • VehicleOpticalFlowVel
        • VehicleRatesSetpoint
        • VehicleRoi
        • VehicleStatus
        • VehicleThrustSetpoint
        • VehicleTorqueSetpoint
        • VehicleTrajectoryBezier
        • VehicleTrajectoryWaypoint
        • VtolVehicleStatus
        • Wind
        • YawEstimatorStatus
      • MAVLink Messaging
      • uXRCE-DDS (PX4-ROS 2/DDS Bridge)
    • Modules & Commands
      • Autotune
      • Commands
      • Communication
      • Controllers
      • Drivers
        • Airspeed Sensor
        • Baro
        • Distance Sensor
        • IMU
        • INS
        • Magnetometer
        • Optical Flow
        • Rpm Sensor
        • Transponder
      • Estimators
      • Simulations
      • System
      • Template
    • Debugging/Logging
      • FAQ
      • Consoles/Shells
        • MAVLink Shell
        • System Console
      • Debugging with GDB
        • SWD Debug Port
        • JLink Probe
        • Black Magic/DroneCode Probe
        • STLink Probe
        • Hardfault Debugging
      • Debugging with Eclipse
      • Failure Injection
      • Sensor/Topic Debugging
      • Simulation Debugging
      • Sending Debug Values
      • System-wide Replay
      • Profiling
      • Binary Size Profiling
      • Logging
      • Flight Log Analysis
      • ULog File Format
    • Tutorials
      • Long-distance Video Streaming
      • Connecting an RC Receiver on Linux
    • Advanced Topics
      • Parameters & Configs
      • Package Delivery Architecture
      • Computer Vision
        • Motion Capture (VICON, Optitrack, NOKOV)
      • Installing driver for Intel RealSense R200
      • Switching State Estimators
      • Out-of-Tree Modules
      • STM32 Bootloader
      • System Tunes
      • Advanced Linux Installation Cases
      • Windows Cygwin Toolchain Maintenance
      • Unsupported Developer Setup
        • CentOS Linux
        • Arch Linux
        • Windows VM Toolchain
        • Windows Cygwin Toolchain
        • Qt Creator IDE
    • Platform Testing and CI
      • Test Flights
        • Test MC_01 - Manual Modes
        • Test MC_02 - Full Autonomous
        • Test MC_03 - Auto Manual Mix
        • Test MC_04 - Failsafe Testing
        • Test MC_05 - Indoor Flight (Manual Modes)
      • Unit Tests
      • Continuous Integration
      • MAVSDK Integration Testing
      • ROS Integration Testing
      • Docker Containers
      • Maintenance
  • Drone Apps & APIs
    • Offboard Control from Linux
    • ROS
      • ROS 2
        • ROS 2 User Guide
        • ROS 2 Offboard Control Example
        • ROS 2 Multi Vehicle Simulation
      • ROS 1 with MAVROS
        • ROS/MAVROS Installation Guide
        • ROS/MAVROS Offboard Example (C++)
        • ROS/MAVROS Offboard Example (Python)
        • ROS/MAVROS Sending Custom Messages
        • ROS/MAVROS with Gazebo Classic Simulation
        • Gazebo Classic OctoMap Models with ROS 1
        • ROS/MAVROS Installation on RPi
        • External Position Estimation (Vision/Motion based)
    • DroneKit
  • Contribution (&Dev Call)
    • Dev Call
    • Support
    • Source Code Management
      • GIT Examples
    • Documentation
    • Translation
    • Terminology/Notation
    • Licenses
  • Releases
    • 1.14
    • 1.13
    • 1.12
Powered by GitBook
On this page
  1. Development
  2. Middleware
  3. uORB Message Reference

EstimatorStatus

PreviousEstimatorStatesNextEstimatorStatusFlags

Last updated 1 year ago

uint64 timestamp		# time since system start (microseconds)
uint64 timestamp_sample         # the timestamp of the raw data (microseconds)

float32[3] output_tracking_error # return a vector containing the output predictor angular, velocity and position tracking error magnitudes (rad), (m/s), (m)

uint16 gps_check_fail_flags     # Bitmask to indicate status of GPS checks - see definition below
# bits are true when corresponding test has failed
uint8 GPS_CHECK_FAIL_GPS_FIX = 0		# 0 : insufficient fix type (no 3D solution)
uint8 GPS_CHECK_FAIL_MIN_SAT_COUNT = 1		# 1 : minimum required sat count fail
uint8 GPS_CHECK_FAIL_MAX_PDOP = 2		# 2 : maximum allowed PDOP fail
uint8 GPS_CHECK_FAIL_MAX_HORZ_ERR = 3		# 3 : maximum allowed horizontal position error fail
uint8 GPS_CHECK_FAIL_MAX_VERT_ERR = 4		# 4 : maximum allowed vertical position error fail
uint8 GPS_CHECK_FAIL_MAX_SPD_ERR = 5		# 5 : maximum allowed speed error fail
uint8 GPS_CHECK_FAIL_MAX_HORZ_DRIFT = 6		# 6 : maximum allowed horizontal position drift fail - requires stationary vehicle
uint8 GPS_CHECK_FAIL_MAX_VERT_DRIFT = 7		# 7 : maximum allowed vertical position drift fail - requires stationary vehicle
uint8 GPS_CHECK_FAIL_MAX_HORZ_SPD_ERR = 8	# 8 : maximum allowed horizontal speed fail - requires stationary vehicle
uint8 GPS_CHECK_FAIL_MAX_VERT_SPD_ERR = 9	# 9 : maximum allowed vertical velocity discrepancy fail

uint64 control_mode_flags	# Bitmask to indicate EKF logic state
uint8 CS_TILT_ALIGN = 0		# 0 - true if the filter tilt alignment is complete
uint8 CS_YAW_ALIGN = 1		# 1 - true if the filter yaw alignment is complete
uint8 CS_GPS = 2		# 2 - true if GPS measurements are being fused
uint8 CS_OPT_FLOW = 3		# 3 - true if optical flow measurements are being fused
uint8 CS_MAG_HDG = 4		# 4 - true if a simple magnetic yaw heading is being fused
uint8 CS_MAG_3D = 5		# 5 - true if 3-axis magnetometer measurement are being fused
uint8 CS_MAG_DEC = 6		# 6 - true if synthetic magnetic declination measurements are being fused
uint8 CS_IN_AIR = 7		# 7 - true when thought to be airborne
uint8 CS_WIND = 8		# 8 - true when wind velocity is being estimated
uint8 CS_BARO_HGT = 9		# 9 - true when baro height is being fused as a primary height reference
uint8 CS_RNG_HGT = 10		# 10 - true when range finder height is being fused as a primary height reference
uint8 CS_GPS_HGT = 11		# 11 - true when GPS height is being fused as a primary height reference
uint8 CS_EV_POS = 12		# 12 - true when local position data from external vision is being fused
uint8 CS_EV_YAW = 13		# 13 - true when yaw data from external vision measurements is being fused
uint8 CS_EV_HGT = 14		# 14 - true when height data from external vision measurements is being fused
uint8 CS_BETA = 15		# 15 - true when synthetic sideslip measurements are being fused
uint8 CS_MAG_FIELD = 16		# 16 - true when only the magnetic field states are updated by the magnetometer
uint8 CS_FIXED_WING = 17	# 17 - true when thought to be operating as a fixed wing vehicle with constrained sideslip
uint8 CS_MAG_FAULT = 18		# 18 - true when the magnetometer has been declared faulty and is no longer being used
uint8 CS_ASPD = 19		# 19 - true when airspeed measurements are being fused
uint8 CS_GND_EFFECT = 20	# 20 - true when when protection from ground effect induced static pressure rise is active
uint8 CS_RNG_STUCK = 21		# 21 - true when a stuck range finder sensor has been detected
uint8 CS_GPS_YAW = 22		# 22 - true when yaw (not ground course) data from a GPS receiver is being fused
uint8 CS_MAG_ALIGNED = 23	# 23 - true when the in-flight mag field alignment has been completed
uint8 CS_EV_VEL = 24		# 24 - true when local frame velocity data fusion from external vision measurements is intended
uint8 CS_SYNTHETIC_MAG_Z = 25	# 25 - true when we are using a synthesized measurement for the magnetometer Z component
uint8 CS_VEHICLE_AT_REST = 26	# 26 - true when the vehicle is at rest
uint8 CS_GPS_YAW_FAULT = 27	# 27 - true when the GNSS heading has been declared faulty and is no longer being used
uint8 CS_RNG_FAULT = 28		# 28 - true when the range finder has been declared faulty and is no longer being used

uint32 filter_fault_flags	# Bitmask to indicate EKF internal faults
# 0 - true if the fusion of the magnetometer X-axis has encountered a numerical error
# 1 - true if the fusion of the magnetometer Y-axis has encountered a numerical error
# 2 - true if the fusion of the magnetometer Z-axis has encountered a numerical error
# 3 - true if the fusion of the magnetic heading has encountered a numerical error
# 4 - true if the fusion of the magnetic declination has encountered a numerical error
# 5 - true if fusion of the airspeed has encountered a numerical error
# 6 - true if fusion of the synthetic sideslip constraint has encountered a numerical error
# 7 - true if fusion of the optical flow X axis has encountered a numerical error
# 8 - true if fusion of the optical flow Y axis has encountered a numerical error
# 9 - true if fusion of the North velocity has encountered a numerical error
# 10 - true if fusion of the East velocity has encountered a numerical error
# 11 - true if fusion of the Down velocity has encountered a numerical error
# 12 - true if fusion of the North position has encountered a numerical error
# 13 - true if fusion of the East position has encountered a numerical error
# 14 - true if fusion of the Down position has encountered a numerical error
# 15 - true if bad delta velocity bias estimates have been detected
# 16 - true if bad vertical accelerometer data has been detected
# 17 - true if delta velocity data contains clipping (asymmetric railing)

float32 pos_horiz_accuracy # 1-Sigma estimated horizontal position accuracy relative to the estimators origin (m)
float32 pos_vert_accuracy # 1-Sigma estimated vertical position accuracy relative to the estimators origin (m)
uint16 innovation_check_flags # Bitmask to indicate pass/fail status of innovation consistency checks
# 0 - true if velocity observations have been rejected
# 1 - true if horizontal position observations have been rejected
# 2 - true if true if vertical position observations have been rejected
# 3 - true if the X magnetometer observation has been rejected
# 4 - true if the Y magnetometer observation has been rejected
# 5 - true if the Z magnetometer observation has been rejected
# 6 - true if the yaw observation has been rejected
# 7 - true if the airspeed observation has been rejected
# 8 - true if the synthetic sideslip observation has been rejected
# 9 - true if the height above ground observation has been rejected
# 10 - true if the X optical flow observation has been rejected
# 11 - true if the Y optical flow observation has been rejected

float32 mag_test_ratio # ratio of the largest magnetometer innovation component to the innovation test limit
float32 vel_test_ratio # ratio of the largest velocity innovation component to the innovation test limit
float32 pos_test_ratio # ratio of the largest horizontal position innovation component to the innovation test limit
float32 hgt_test_ratio # ratio of the vertical position innovation to the innovation test limit
float32 tas_test_ratio # ratio of the true airspeed innovation to the innovation test limit
float32 hagl_test_ratio # ratio of the height above ground innovation to the innovation test limit
float32 beta_test_ratio # ratio of the synthetic sideslip innovation to the innovation test limit

uint16 solution_status_flags # Bitmask indicating which filter kinematic state outputs are valid for flight control use.
# 0 - True if the attitude estimate is good
# 1 - True if the horizontal velocity estimate is good
# 2 - True if the vertical velocity estimate is good
# 3 - True if the horizontal position (relative) estimate is good
# 4 - True if the horizontal position (absolute) estimate is good
# 5 - True if the vertical position (absolute) estimate is good
# 6 - True if the vertical position (above ground) estimate is good
# 7 - True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow)
# 8 - True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate
# 9 - True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate
# 10 - True if the EKF has detected a GPS glitch
# 11 - True if the EKF has detected bad accelerometer data

uint8 reset_count_vel_ne # number of horizontal position reset events (allow to wrap if count exceeds 255)
uint8 reset_count_vel_d  # number of vertical velocity reset events (allow to wrap if count exceeds 255)
uint8 reset_count_pos_ne # number of horizontal position reset events (allow to wrap if count exceeds 255)
uint8 reset_count_pod_d  # number of vertical position reset events (allow to wrap if count exceeds 255)
uint8 reset_count_quat   # number of quaternion reset events (allow to wrap if count exceeds 255)

float32 time_slip # cumulative amount of time in seconds that the EKF inertial calculation has slipped relative to system time

bool pre_flt_fail_innov_heading
bool pre_flt_fail_innov_vel_horiz
bool pre_flt_fail_innov_vel_vert
bool pre_flt_fail_innov_height
bool pre_flt_fail_mag_field_disturbed

uint32 accel_device_id
uint32 gyro_device_id
uint32 baro_device_id
uint32 mag_device_id

# legacy local position estimator (LPE) flags
uint8 health_flags		# Bitmask to indicate sensor health states (vel, pos, hgt)
uint8 timeout_flags		# Bitmask to indicate timeout flags (vel, pos, hgt)

float32 mag_inclination_deg
float32 mag_inclination_ref_deg
float32 mag_strength_gs
float32 mag_strength_ref_gs
source file