---
pageClass: is-wide-page
---
# VehicleStatus (UORB message)
Encodes the system state of the vehicle published by commander.
**TOPICS:** vehicle_status
## Fields
| Name | Type | Unit [Frame] | Range/Enum | Description |
| -------------------------------- | -------- | ------------ | ---------- | ----------------------------------------------------------------------------------------------- |
| timestamp | `uint64` | | | time since system start (microseconds) |
| armed_time | `uint64` | | | Arming timestamp (microseconds) |
| takeoff_time | `uint64` | | | Takeoff timestamp (microseconds) |
| arming_state | `uint8` | | |
| latest_arming_reason | `uint8` | | |
| latest_disarming_reason | `uint8` | | |
| nav_state_timestamp | `uint64` | | | time when current nav_state activated |
| nav_state_user_intention | `uint8` | | | Mode that the user selected (might be different from nav_state in a failsafe situation) |
| nav_state | `uint8` | | | Currently active mode |
| executor_in_charge | `uint8` | | | Current mode executor in charge (0=Autopilot) |
| nav_state_display | `uint8` | | | User-visible nav state sent via MAVLink (executor state if active, otherwise nav_state) |
| valid_nav_states_mask | `uint32` | | | Bitmask for all valid nav_state values |
| can_set_nav_states_mask | `uint32` | | | Bitmask for all modes that a user can select |
| failure_detector_status | `uint16` | | |
| hil_state | `uint8` | | |
| vehicle_type | `uint8` | | |
| failsafe | `bool` | | | true if system is in failsafe state (e.g.:RTL, Hover, Terminate, ...) |
| failsafe_and_user_took_over | `bool` | | | true if system is in failsafe state but the user took over control |
| failsafe_defer_state | `uint8` | | | one of FAILSAFE*DEFER_STATE*\* |
| gcs_connection_lost | `bool` | | | datalink to GCS lost |
| gcs_connection_lost_counter | `uint8` | | | counts unique GCS connection lost events |
| high_latency_data_link_lost | `bool` | | | Set to true if the high latency data link (eg. RockBlock Iridium 9603 telemetry module) is lost |
| is_vtol | `bool` | | | True if the system is VTOL capable |
| is_vtol_tailsitter | `bool` | | | True if the system performs a 90° pitch down rotation during transition from MC to FW |
| in_transition_mode | `bool` | | | True if VTOL is doing a transition |
| in_transition_to_fw | `bool` | | | True if VTOL is doing a transition from MC to FW |
| system_type | `uint8` | | | system type, contains mavlink MAV_TYPE |
| system_id | `uint8` | | | system id, contains MAVLink's system ID field |
| component_id | `uint8` | | | subsystem / component id, contains MAVLink's component ID field |
| safety_button_available | `bool` | | | Set to true if a safety button is connected |
| safety_off | `bool` | | | Set to true if safety is off |
| power_input_valid | `bool` | | | set if input power is valid |
| usb_connected | `bool` | | | set to true (never cleared) once telemetry received from usb link |
| open_drone_id_system_present | `bool` | | |
| open_drone_id_system_healthy | `bool` | | |
| parachute_system_present | `bool` | | |
| parachute_system_healthy | `bool` | | |
| traffic_avoidance_system_present | `bool` | | |
| rc_calibration_in_progress | `bool` | | |
| calibration_enabled | `bool` | | |
| pre_flight_checks_pass | `bool` | | | true if all checks necessary to arm pass |
## Constants
| Name | Type | Value | Description |
| --------------------------------------------------------------------------------------- | -------- | ----- | ------------------------------------------------ |
| MESSAGE_VERSION | `uint32` | 2 |
| ARMING_STATE_DISARMED | `uint8` | 1 |
| ARMING_STATE_ARMED | `uint8` | 2 |
| ARM_DISARM_REASON_STICK_GESTURE | `uint8` | 1 |
| ARM_DISARM_REASON_RC_SWITCH | `uint8` | 2 |
| ARM_DISARM_REASON_COMMAND_INTERNAL | `uint8` | 3 |
| ARM_DISARM_REASON_COMMAND_EXTERNAL | `uint8` | 4 |
| ARM_DISARM_REASON_MISSION_START | `uint8` | 5 |
| ARM_DISARM_REASON_LANDING | `uint8` | 6 |
| ARM_DISARM_REASON_PREFLIGHT_INACTION | `uint8` | 7 |
| ARM_DISARM_REASON_KILL_SWITCH | `uint8` | 8 |
| ARM_DISARM_REASON_RC_BUTTON | `uint8` | 13 |
| ARM_DISARM_REASON_FAILSAFE | `uint8` | 14 |
| NAVIGATION_STATE_MANUAL | `uint8` | 0 | Manual mode |
| NAVIGATION_STATE_ALTCTL | `uint8` | 1 | Altitude control mode |
| NAVIGATION_STATE_POSCTL | `uint8` | 2 | Position control mode |
| NAVIGATION_STATE_AUTO_MISSION | `uint8` | 3 | Auto mission mode |
| NAVIGATION_STATE_AUTO_LOITER | `uint8` | 4 | Auto loiter mode |
| NAVIGATION_STATE_AUTO_RTL | `uint8` | 5 | Auto return to launch mode |
| NAVIGATION_STATE_POSITION_SLOW | `uint8` | 6 |
| NAVIGATION_STATE_FREE5 | `uint8` | 7 |
| NAVIGATION_STATE_ALTITUDE_CRUISE | `uint8` | 8 | Altitude with Cruise mode |
| NAVIGATION_STATE_FREE3 | `uint8` | 9 |
| NAVIGATION_STATE_ACRO | `uint8` | 10 | Acro mode |
| NAVIGATION_STATE_FREE2 | `uint8` | 11 |
| NAVIGATION_STATE_DESCEND | `uint8` | 12 | Descend mode (no position control) |
| NAVIGATION_STATE_TERMINATION | `uint8` | 13 | Termination mode |
| NAVIGATION_STATE_OFFBOARD | `uint8` | 14 |
| NAVIGATION_STATE_STAB | `uint8` | 15 | Stabilized mode |
| NAVIGATION_STATE_FREE1 | `uint8` | 16 |
| NAVIGATION_STATE_AUTO_TAKEOFF | `uint8` | 17 | Takeoff |
| NAVIGATION_STATE_AUTO_LAND | `uint8` | 18 | Land |
| NAVIGATION_STATE_AUTO_FOLLOW_TARGET | `uint8` | 19 | Auto Follow |
| NAVIGATION_STATE_AUTO_PRECLAND | `uint8` | 20 | Precision land with landing target |
| NAVIGATION_STATE_ORBIT | `uint8` | 21 | Orbit in a circle |
| NAVIGATION_STATE_AUTO_VTOL_TAKEOFF | `uint8` | 22 | Takeoff, transition, establish loiter |
| NAVIGATION_STATE_EXTERNAL1 | `uint8` | 23 |
| NAVIGATION_STATE_EXTERNAL2 | `uint8` | 24 |
| NAVIGATION_STATE_EXTERNAL3 | `uint8` | 25 |
| NAVIGATION_STATE_EXTERNAL4 | `uint8` | 26 |
| NAVIGATION_STATE_EXTERNAL5 | `uint8` | 27 |
| NAVIGATION_STATE_EXTERNAL6 | `uint8` | 28 |
| NAVIGATION_STATE_EXTERNAL7 | `uint8` | 29 |
| NAVIGATION_STATE_EXTERNAL8 | `uint8` | 30 |
| NAVIGATION_STATE_MAX | `uint8` | 31 |
| FAILURE_NONE | `uint16` | 0 |
| FAILURE_ROLL | `uint16` | 1 | (1 << 0) |
| FAILURE_PITCH | `uint16` | 2 | (1 << 1) |
| FAILURE_ALT | `uint16` | 4 | (1 << 2) |
| FAILURE_EXT | `uint16` | 8 | (1 << 3) |
| FAILURE_ARM_ESC | `uint16` | 16 | (1 << 4) |
| FAILURE_BATTERY | `uint16` | 32 | (1 << 5) |
| FAILURE_IMBALANCED_PROP | `uint16` | 64 | (1 << 6) |
| FAILURE_MOTOR | `uint16` | 128 | (1 << 7) |
| HIL_STATE_OFF | `uint8` | 0 |
| HIL_STATE_ON | `uint8` | 1 |
| VEHICLE_TYPE_UNSPECIFIED | `uint8` | 0 |
| VEHICLE_TYPE_ROTARY_WING | `uint8` | 1 |
| VEHICLE_TYPE_FIXED_WING | `uint8` | 2 |
| VEHICLE_TYPE_ROVER | `uint8` | 3 |
| FAILSAFE_DEFER_STATE_DISABLED | `uint8` | 0 |
| FAILSAFE_DEFER_STATE_ENABLED | `uint8` | 1 |
| FAILSAFE_DEFER_STATE_WOULD_FAILSAFE | `uint8` | 2 | Failsafes deferred, but would trigger a failsafe |
## Source Message
[Source file (GitHub)](https://github.com/PX4/PX4-Autopilot/blob/main/msg/versioned/VehicleStatus.msg)
::: details Click here to see original file
```c
# Encodes the system state of the vehicle published by commander
uint32 MESSAGE_VERSION = 2
uint64 timestamp # time since system start (microseconds)
uint64 armed_time # Arming timestamp (microseconds)
uint64 takeoff_time # Takeoff timestamp (microseconds)
uint8 arming_state
uint8 ARMING_STATE_DISARMED = 1
uint8 ARMING_STATE_ARMED = 2
uint8 latest_arming_reason
uint8 latest_disarming_reason
uint8 ARM_DISARM_REASON_STICK_GESTURE = 1
uint8 ARM_DISARM_REASON_RC_SWITCH = 2
uint8 ARM_DISARM_REASON_COMMAND_INTERNAL = 3
uint8 ARM_DISARM_REASON_COMMAND_EXTERNAL = 4
uint8 ARM_DISARM_REASON_MISSION_START = 5
uint8 ARM_DISARM_REASON_LANDING = 6
uint8 ARM_DISARM_REASON_PREFLIGHT_INACTION = 7
uint8 ARM_DISARM_REASON_KILL_SWITCH = 8
uint8 ARM_DISARM_REASON_RC_BUTTON = 13
uint8 ARM_DISARM_REASON_FAILSAFE = 14
uint64 nav_state_timestamp # time when current nav_state activated
uint8 nav_state_user_intention # Mode that the user selected (might be different from nav_state in a failsafe situation)
uint8 nav_state # Currently active mode
uint8 NAVIGATION_STATE_MANUAL = 0 # Manual mode
uint8 NAVIGATION_STATE_ALTCTL = 1 # Altitude control mode
uint8 NAVIGATION_STATE_POSCTL = 2 # Position control mode
uint8 NAVIGATION_STATE_AUTO_MISSION = 3 # Auto mission mode
uint8 NAVIGATION_STATE_AUTO_LOITER = 4 # Auto loiter mode
uint8 NAVIGATION_STATE_AUTO_RTL = 5 # Auto return to launch mode
uint8 NAVIGATION_STATE_POSITION_SLOW = 6
uint8 NAVIGATION_STATE_FREE5 = 7
uint8 NAVIGATION_STATE_ALTITUDE_CRUISE = 8 # Altitude with Cruise mode
uint8 NAVIGATION_STATE_FREE3 = 9
uint8 NAVIGATION_STATE_ACRO = 10 # Acro mode
uint8 NAVIGATION_STATE_FREE2 = 11
uint8 NAVIGATION_STATE_DESCEND = 12 # Descend mode (no position control)
uint8 NAVIGATION_STATE_TERMINATION = 13 # Termination mode
uint8 NAVIGATION_STATE_OFFBOARD = 14
uint8 NAVIGATION_STATE_STAB = 15 # Stabilized mode
uint8 NAVIGATION_STATE_FREE1 = 16
uint8 NAVIGATION_STATE_AUTO_TAKEOFF = 17 # Takeoff
uint8 NAVIGATION_STATE_AUTO_LAND = 18 # Land
uint8 NAVIGATION_STATE_AUTO_FOLLOW_TARGET = 19 # Auto Follow
uint8 NAVIGATION_STATE_AUTO_PRECLAND = 20 # Precision land with landing target
uint8 NAVIGATION_STATE_ORBIT = 21 # Orbit in a circle
uint8 NAVIGATION_STATE_AUTO_VTOL_TAKEOFF = 22 # Takeoff, transition, establish loiter
uint8 NAVIGATION_STATE_EXTERNAL1 = 23
uint8 NAVIGATION_STATE_EXTERNAL2 = 24
uint8 NAVIGATION_STATE_EXTERNAL3 = 25
uint8 NAVIGATION_STATE_EXTERNAL4 = 26
uint8 NAVIGATION_STATE_EXTERNAL5 = 27
uint8 NAVIGATION_STATE_EXTERNAL6 = 28
uint8 NAVIGATION_STATE_EXTERNAL7 = 29
uint8 NAVIGATION_STATE_EXTERNAL8 = 30
uint8 NAVIGATION_STATE_MAX = 31
uint8 executor_in_charge # Current mode executor in charge (0=Autopilot)
uint8 nav_state_display # User-visible nav state sent via MAVLink (executor state if active, otherwise nav_state)
uint32 valid_nav_states_mask # Bitmask for all valid nav_state values
uint32 can_set_nav_states_mask # Bitmask for all modes that a user can select
# Bitmask of detected failures
uint16 failure_detector_status
uint16 FAILURE_NONE = 0
uint16 FAILURE_ROLL = 1 # (1 << 0)
uint16 FAILURE_PITCH = 2 # (1 << 1)
uint16 FAILURE_ALT = 4 # (1 << 2)
uint16 FAILURE_EXT = 8 # (1 << 3)
uint16 FAILURE_ARM_ESC = 16 # (1 << 4)
uint16 FAILURE_BATTERY = 32 # (1 << 5)
uint16 FAILURE_IMBALANCED_PROP = 64 # (1 << 6)
uint16 FAILURE_MOTOR = 128 # (1 << 7)
uint8 hil_state
uint8 HIL_STATE_OFF = 0
uint8 HIL_STATE_ON = 1
# Current vehicle locomotion method. A vehicle can have different methods (e.g. VTOL transitions from RW to FW method)
uint8 vehicle_type
uint8 VEHICLE_TYPE_UNSPECIFIED = 0
uint8 VEHICLE_TYPE_ROTARY_WING = 1
uint8 VEHICLE_TYPE_FIXED_WING = 2
uint8 VEHICLE_TYPE_ROVER = 3
uint8 FAILSAFE_DEFER_STATE_DISABLED = 0
uint8 FAILSAFE_DEFER_STATE_ENABLED = 1
uint8 FAILSAFE_DEFER_STATE_WOULD_FAILSAFE = 2 # Failsafes deferred, but would trigger a failsafe
bool failsafe # true if system is in failsafe state (e.g.:RTL, Hover, Terminate, ...)
bool failsafe_and_user_took_over # true if system is in failsafe state but the user took over control
uint8 failsafe_defer_state # one of FAILSAFE_DEFER_STATE_*
# Link loss
bool gcs_connection_lost # datalink to GCS lost
uint8 gcs_connection_lost_counter # counts unique GCS connection lost events
bool high_latency_data_link_lost # Set to true if the high latency data link (eg. RockBlock Iridium 9603 telemetry module) is lost
# VTOL flags
bool is_vtol # True if the system is VTOL capable
bool is_vtol_tailsitter # True if the system performs a 90° pitch down rotation during transition from MC to FW
bool in_transition_mode # True if VTOL is doing a transition
bool in_transition_to_fw # True if VTOL is doing a transition from MC to FW
# MAVLink identification
uint8 system_type # system type, contains mavlink MAV_TYPE
uint8 system_id # system id, contains MAVLink's system ID field
uint8 component_id # subsystem / component id, contains MAVLink's component ID field
bool safety_button_available # Set to true if a safety button is connected
bool safety_off # Set to true if safety is off
bool power_input_valid # set if input power is valid
bool usb_connected # set to true (never cleared) once telemetry received from usb link
bool open_drone_id_system_present
bool open_drone_id_system_healthy
bool parachute_system_present
bool parachute_system_healthy
bool traffic_avoidance_system_present
bool rc_calibration_in_progress
bool calibration_enabled
bool pre_flight_checks_pass # true if all checks necessary to arm pass
```
:::