MAVLINKHUD

HIL_STATE

ID: 90
Unsupported

Summary

Hardware in the loop state.

Status

Unsupported

Directionality

  • TX (Transmit): None
  • RX (Receive): None

Description

ArduPilot does not support this message. It uses HIL_STATE_QUATERNION (115) for HIL simulation to avoid gimbal lock singularities associated with Euler angles.

Theoretical Use Cases

Legacy HIL simulation.

HIL_CONTROLS

ID: 91
Unsupported

Summary

Hardware in the loop control outputs.

Status

Unsupported

Directionality

  • TX (Transmit): None
  • RX (Receive): None

Description

ArduPilot does not implement this message.

Theoretical Use Cases

Sending control surface outputs to a simulator.

Unsupported

Summary

Raw RC inputs for HIL.

Status

Unsupported

Directionality

  • TX (Transmit): None
  • RX (Receive): None

Description

ArduPilot does not implement this message.

Theoretical Use Cases

Injecting RC input into a simulation.

Unsupported

Summary

HIL actuator controls.

Status

Unsupported

Directionality

  • TX (Transmit): None
  • RX (Receive): None

Description

ArduPilot does not implement this message.

Theoretical Use Cases

Sending actuator commands to a simulator.

HIL_SENSOR

ID: 107
Deprecated / Unsupported

Summary

The HIL_SENSOR message was designed to allow external simulators to provide raw sensor data (IMU, Barometer, Magnetometer) to the flight controller during Hardware-In-The-Loop (HIL) simulation. ArduPilot no longer supports this message. It has been deprecated and removed from the core libraries in favor of the more robust and higher-performance Software-In-The-Loop (SITL) architecture.

Status

Deprecated / Unsupported

Directionality

  • TX (Transmit): None
  • RX (Receive): None (Ignored)

Analysis

ArduPilot has transitioned away from MAVLink-based HIL for sensors. Historically, messages like HIL_SENSOR were used with simulators like X-Plane or older versions of Gazebo. Modern ArduPilot workflows use SITL, where sensor data is injected via specialized backend classes (e.g., AP_InertialSensor_SITL) that communicate with simulators using high-bandwidth JSON/UDP protocols or shared memory, rather than the bandwidth-limited MAVLink stream.

  • Absence: There is no mapping for MAVLINK_MSG_ID_HIL_SENSOR (107) in the GCS_MAVLink libraries.
  • Parameters: Legacy parameters like HIL_MODE are now marked as unused in the firmware source code.

Data Fields

  • time_usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).
  • xacc: X acceleration (m/s^2).
  • yacc: Y acceleration (m/s^2).
  • zacc: Z acceleration (m/s^2).
  • xgyro: Angular speed around X axis (rad/s).
  • ygyro: Angular speed around Y axis (rad/s).
  • zgyro: Angular speed around Z axis (rad/s).
  • xmag: X Magnetic field (Gauss).
  • ymag: Y Magnetic field (Gauss).
  • zmag: Z Magnetic field (Gauss).
  • abs_pressure: Absolute pressure (hectopascal).
  • diff_pressure: Differential pressure (hectopascal).
  • pressure_alt: Altitude calculated from pressure.
  • temperature: Temperature (degrees celsius).
  • fields_updated: Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature.

Recommendation

Developers looking to perform simulations should use the SITL system. If external sensor injection is required on physical hardware, consider using the VISION_POSITION_ESTIMATE (102) or GPS_INPUT (232) pipelines, which remain active and supported.

Key Codebase Locations

SIM_STATE

ID: 108
Supported (TX Only)

Summary

Status of the simulation environment (SITL).

Status

Supported (TX Only)

Directionality

  • TX (Transmit): SITL - Sends simulation ground truth.
  • RX (Receive): None

Transmission (TX)

ArduPilot sends this message when running in Software In The Loop (SITL) mode to report the "true" physical state of the vehicle, bypassing sensor noise and estimation errors.

Source: libraries/SITL/SITL.cpp

Protocol Logic

Data Fields

  • q1: Quaternion q1.
  • q2: Quaternion q2.
  • q3: Quaternion q3.
  • q4: Quaternion q4.
  • roll: Roll angle (rad).
  • pitch: Pitch angle (rad).
  • yaw: Yaw angle (rad).
  • xacc: X acceleration (m/s^2).
  • yacc: Y acceleration (m/s^2).
  • zacc: Z acceleration (m/s^2).
  • xgyro: X angular speed (rad/s).
  • ygyro: Y angular speed (rad/s).
  • zgyro: Z angular speed (rad/s).
  • lat: Latitude (deg).
  • lon: Longitude (deg).
  • alt: Altitude (m).
  • std_dev_horz: Horizontal position standard deviation.
  • std_dev_vert: Vertical position standard deviation.
  • vn: Velocity North (m/s).
  • ve: Velocity East (m/s).
  • vd: Velocity Down (m/s).

Practical Use Cases

  1. Estimation Analysis:
    • Scenario: Developing a new EKF.
    • Action: Developer compares SIM_STATE.roll (Truth) vs ATTITUDE.roll (Estimated) to quantify the filter's performance.

Key Codebase Locations

  • libraries/SITL/SITL.cpp:1557: Sending implementation.

HIL_GPS

ID: 113
Legacy / Deprecated

Summary

The HIL_GPS message allows an external simulator to provide fake GPS coordinates, velocity, and fix status to the flight controller. While it remains functional in current stable releases, it is officially considered Legacy and is slated for removal in ArduPilot 4.7. Developers are strongly encouraged to migrate to the more robust GPS_INPUT (232) message.

Status

Legacy / Deprecated (Removal planned for version 4.7)

Directionality

  • TX (Transmit): None
  • RX (Receive): All Vehicles (External GPS injection)

Reception (RX)

Reception is handled by the AP_GPS_MAV backend, with the entry point in libraries/GCS_MAVLink/GCS_Common.cpp:4317.

Data Processing

  1. Decoding: The message is decoded in AP_GPS_MAV::handle_msg (libraries/AP_GPS/AP_GPS_MAV.cpp:149).
  2. Mapping: It maps standard GPS fields (Lat, Lon, Alt, Vel) into the autopilot's internal GPS_State structure.
  3. Limitations: Unlike the modern GPS_INPUT (232), HIL_GPS lacks support for yaw data, precise accuracy estimates (horizontal/vertical/speed accuracy), and transport jitter correction.

Data Fields

  • time_usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).
  • fix_type: 0-1: no fix, 2: 2D fix, 3: 3D fix.
  • lat: Latitude (WGS84, EGM96 ellipsoid), in degrees * 1E7.
  • lon: Longitude (WGS84, EGM96 ellipsoid), in degrees * 1E7.
  • alt: Altitude (MSL). Positive for up.
  • eph: GPS HDOP horizontal dilution of precision in cm (m*100). If unknown, set to: 65535.
  • epv: GPS VDOP vertical dilution of precision in cm (m*100). If unknown, set to: 65535.
  • vel: GPS ground speed (m/s * 100). If unknown, set to: 65535.
  • vn: GPS velocity in north direction in cm/s.
  • ve: GPS velocity in east direction in cm/s.
  • vd: GPS velocity in down direction in cm/s.
  • cog: Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535.
  • satellites_visible: Number of satellites visible. If unknown, set to 255.
  • id: GPS ID (zero indexed). Optional, default: 0.
  • yaw: Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north.

Practical Use Cases

  1. Legacy Simulator Support:
    • Scenario: A user is using an older HIL-capable simulator that only outputs the HIL_GPS packet.
    • Action: ArduPilot accepts the packet and allows the user to "fly" the simulated environment on physical hardware.
  2. Minimal GPS Emulation:
    • Scenario: A developer wants to quickly "fake" a GPS lock for indoor testing without implementing the full GPS_INPUT protocol.
    • Action: A simple script sends HIL_GPS at 5Hz to satisfy the autopilot's pre-arm checks for GPS-dependent modes.

Key Codebase Locations

Unsupported

Summary

Simulated optical flow sensor data.

Status

Unsupported

Directionality

  • TX (Transmit): None
  • RX (Receive): None

Description

ArduPilot does not implement this message. It likely uses standard OPTICAL_FLOW (100) or direct sensor injection for simulation.

Theoretical Use Cases

Simulating optical flow.

Unsupported

Summary

The HIL_STATE_QUATERNION message is defined in MAVLink to provide the full ground-truth state of a vehicle (position, attitude, velocity, and acceleration) from a simulator to the flight controller. ArduPilot does not implement this message.

Status

Unsupported

Directionality

  • TX (Transmit): None
  • RX (Receive): None (Ignored)

Analysis

Like HIL_SENSOR (107), this message is part of the legacy MAVLink-based Hardware-In-The-Loop (HIL) architecture. ArduPilot has migrated its simulation strategy to the Software-In-The-Loop (SITL) system, which uses higher-performance, non-MAVLink protocols for state injection.

  • Absence: There is no handler for MAVLINK_MSG_ID_HIL_STATE_QUATERNION (115) in any of ArduPilot's GCS or state estimation libraries.
  • Alternative: Developers using ArduPilot's SITL should use the built-in simulator drivers which handle state synchronization automatically without using this MAVLink packet.

Data Fields

  • time_usec: Timestamp (microseconds since UNIX epoch or microseconds since system boot).
  • attitude_quaternion: Vehicle attitude expressed as normalized quaternion (w, x, y, z).
  • rollspeed: Body frame roll / phi angular speed (rad/s).
  • pitchspeed: Body frame pitch / theta angular speed (rad/s).
  • yawspeed: Body frame yaw / psi angular speed (rad/s).
  • lat: Latitude (degE7).
  • lon: Longitude (degE7).
  • alt: Altitude (meters).
  • vx: Ground X Speed (Latitude) (cm/s).
  • vy: Ground Y Speed (Longitude) (cm/s).
  • vz: Ground Z Speed (Altitude) (cm/s).
  • ind_airspeed: Indicated airspeed (cm/s).
  • true_airspeed: True airspeed (cm/s).
  • xacc: X acceleration (mG).
  • yacc: Y acceleration (mG).
  • zacc: Z acceleration (mG).

Key Codebase Locations

SIMSTATE

ID: 164
Supported (SITL Only)

Summary

The SIMSTATE message provides the "Ground Truth" state of the vehicle from the Software In The Loop (SITL) simulator. It allows developers to compare the autopilot's estimated state (AHRS/EKF) against the perfect physical reality simulated by the physics engine.

Status

Supported (SITL Only)

Directionality

  • TX (Transmit): SITL Vehicles (Reports perfect simulation state)
  • RX (Receive): None (Ignored)

Transmission (TX)

Transmission is handled by SIM::simstate_send within libraries/SITL/SITL.cpp:1514.

Data Source

All fields are populated directly from the internal SITL::state structure, which holds the physics engine's calculations for position, attitude, and dynamics.

Data Fields

  • roll: True roll angle (radians).
  • pitch: True pitch angle (radians).
  • yaw: True yaw angle (radians), normalized to +/- PI.
  • xacc: True X acceleration (m/s/s) in body frame.
  • yacc: True Y acceleration (m/s/s) in body frame.
  • zacc: True Z acceleration (m/s/s) in body frame.
  • xgyro: True roll rate (rad/s) in body frame.
  • ygyro: True pitch rate (rad/s) in body frame.
  • zgyro: True yaw rate (rad/s) in body frame.
  • lat: True latitude (deg * 1E7).
  • lng: True longitude (deg * 1E7).

Practical Use Cases

  1. Estimator Tuning:
    • Scenario: A developer is tuning the EKF.
    • Action: By plotting SIMSTATE.roll vs ATTITUDE.roll, they can see exactly how much error the estimator has and how much lag is introduced by filtering.
  2. Vibration Testing:
    • Scenario: Testing how the EKF handles high vibration.
    • Action: The simulator adds noise to the IMU data (RAW_IMU). Comparing the noisy RAW_IMU against the clean SIMSTATE and the filtered ATTITUDE helps verify the vibration rejection logic.

Key Codebase Locations