Skip to content

VehicleStatus (UORB message)

Encodes the system state of the vehicle published by commander.

TOPICS: vehicle_status

Fields

NameTypeUnit [Frame]Range/EnumDescription
timestampuint64time since system start (microseconds)
armed_timeuint64Arming timestamp (microseconds)
takeoff_timeuint64Takeoff timestamp (microseconds)
arming_stateuint8
latest_arming_reasonuint8
latest_disarming_reasonuint8
nav_state_timestampuint64time when current nav_state activated
nav_state_user_intentionuint8Mode that the user selected (might be different from nav_state in a failsafe situation)
nav_stateuint8Currently active mode
executor_in_chargeuint8Current mode executor in charge (0=Autopilot)
valid_nav_states_maskuint32Bitmask for all valid nav_state values
can_set_nav_states_maskuint32Bitmask for all modes that a user can select
failure_detector_statusuint16
hil_stateuint8
vehicle_typeuint8
failsafebooltrue if system is in failsafe state (e.g.:RTL, Hover, Terminate, ...)
failsafe_and_user_took_overbooltrue if system is in failsafe state but the user took over control
failsafe_defer_stateuint8one of FAILSAFEDEFER_STATE*
gcs_connection_lostbooldatalink to GCS lost
gcs_connection_lost_counteruint8counts unique GCS connection lost events
high_latency_data_link_lostboolSet to true if the high latency data link (eg. RockBlock Iridium 9603 telemetry module) is lost
is_vtolboolTrue if the system is VTOL capable
is_vtol_tailsitterboolTrue if the system performs a 90° pitch down rotation during transition from MC to FW
in_transition_modeboolTrue if VTOL is doing a transition
in_transition_to_fwboolTrue if VTOL is doing a transition from MC to FW
system_typeuint8system type, contains mavlink MAV_TYPE
system_iduint8system id, contains MAVLink's system ID field
component_iduint8subsystem / component id, contains MAVLink's component ID field
safety_button_availableboolSet to true if a safety button is connected
safety_offboolSet to true if safety is off
power_input_validboolset if input power is valid
usb_connectedboolset to true (never cleared) once telemetry received from usb link
open_drone_id_system_presentbool
open_drone_id_system_healthybool
parachute_system_presentbool
parachute_system_healthybool
rc_calibration_in_progressbool
calibration_enabledbool
pre_flight_checks_passbooltrue if all checks necessary to arm pass

Constants

NameTypeValueDescription
MESSAGE_VERSIONuint321
ARMING_STATE_DISARMEDuint81
ARMING_STATE_ARMEDuint82
ARM_DISARM_REASON_STICK_GESTUREuint81
ARM_DISARM_REASON_RC_SWITCHuint82
ARM_DISARM_REASON_COMMAND_INTERNALuint83
ARM_DISARM_REASON_COMMAND_EXTERNALuint84
ARM_DISARM_REASON_MISSION_STARTuint85
ARM_DISARM_REASON_LANDINGuint86
ARM_DISARM_REASON_PREFLIGHT_INACTIONuint87
ARM_DISARM_REASON_KILL_SWITCHuint88
ARM_DISARM_REASON_RC_BUTTONuint813
ARM_DISARM_REASON_FAILSAFEuint814
NAVIGATION_STATE_MANUALuint80Manual mode
NAVIGATION_STATE_ALTCTLuint81Altitude control mode
NAVIGATION_STATE_POSCTLuint82Position control mode
NAVIGATION_STATE_AUTO_MISSIONuint83Auto mission mode
NAVIGATION_STATE_AUTO_LOITERuint84Auto loiter mode
NAVIGATION_STATE_AUTO_RTLuint85Auto return to launch mode
NAVIGATION_STATE_POSITION_SLOWuint86
NAVIGATION_STATE_FREE5uint87
NAVIGATION_STATE_ALTITUDE_CRUISEuint88Altitude with Cruise mode
NAVIGATION_STATE_FREE3uint89
NAVIGATION_STATE_ACROuint810Acro mode
NAVIGATION_STATE_FREE2uint811
NAVIGATION_STATE_DESCENDuint812Descend mode (no position control)
NAVIGATION_STATE_TERMINATIONuint813Termination mode
NAVIGATION_STATE_OFFBOARDuint814
NAVIGATION_STATE_STABuint815Stabilized mode
NAVIGATION_STATE_FREE1uint816
NAVIGATION_STATE_AUTO_TAKEOFFuint817Takeoff
NAVIGATION_STATE_AUTO_LANDuint818Land
NAVIGATION_STATE_AUTO_FOLLOW_TARGETuint819Auto Follow
NAVIGATION_STATE_AUTO_PRECLANDuint820Precision land with landing target
NAVIGATION_STATE_ORBITuint821Orbit in a circle
NAVIGATION_STATE_AUTO_VTOL_TAKEOFFuint822Takeoff, transition, establish loiter
NAVIGATION_STATE_EXTERNAL1uint823
NAVIGATION_STATE_EXTERNAL2uint824
NAVIGATION_STATE_EXTERNAL3uint825
NAVIGATION_STATE_EXTERNAL4uint826
NAVIGATION_STATE_EXTERNAL5uint827
NAVIGATION_STATE_EXTERNAL6uint828
NAVIGATION_STATE_EXTERNAL7uint829
NAVIGATION_STATE_EXTERNAL8uint830
NAVIGATION_STATE_MAXuint831
FAILURE_NONEuint160
FAILURE_ROLLuint161(1 << 0)
FAILURE_PITCHuint162(1 << 1)
FAILURE_ALTuint164(1 << 2)
FAILURE_EXTuint168(1 << 3)
FAILURE_ARM_ESCuint1616(1 << 4)
FAILURE_BATTERYuint1632(1 << 5)
FAILURE_IMBALANCED_PROPuint1664(1 << 6)
FAILURE_MOTORuint16128(1 << 7)
HIL_STATE_OFFuint80
HIL_STATE_ONuint81
VEHICLE_TYPE_UNSPECIFIEDuint80
VEHICLE_TYPE_ROTARY_WINGuint81
VEHICLE_TYPE_FIXED_WINGuint82
VEHICLE_TYPE_ROVERuint83
FAILSAFE_DEFER_STATE_DISABLEDuint80
FAILSAFE_DEFER_STATE_ENABLEDuint81
FAILSAFE_DEFER_STATE_WOULD_FAILSAFEuint82Failsafes deferred, but would trigger a failsafe

Source Message

Source file (GitHub)

Click here to see original file
c
# Encodes the system state of the vehicle published by commander

uint32 MESSAGE_VERSION = 1

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)

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 rc_calibration_in_progress
bool calibration_enabled

bool pre_flight_checks_pass		# true if all checks necessary to arm pass