2014-12-18 07:08:39 -04:00
|
|
|
# If you change the order, add or remove arming_state_t states make sure to update the arrays
|
|
|
|
# in state_machine_helper.cpp as well.
|
2018-08-07 10:42:32 -03:00
|
|
|
uint64 timestamp # time since system start (microseconds)
|
2018-08-06 21:30:05 -03:00
|
|
|
|
2014-12-18 07:08:39 -04:00
|
|
|
uint8 ARMING_STATE_INIT = 0
|
|
|
|
uint8 ARMING_STATE_STANDBY = 1
|
|
|
|
uint8 ARMING_STATE_ARMED = 2
|
2018-03-27 17:04:17 -03:00
|
|
|
uint8 ARMING_STATE_STANDBY_ERROR = 3
|
|
|
|
uint8 ARMING_STATE_REBOOT = 4
|
|
|
|
uint8 ARMING_STATE_IN_AIR_RESTORE = 5
|
|
|
|
uint8 ARMING_STATE_MAX = 6
|
2014-12-18 07:08:39 -04:00
|
|
|
|
2018-08-10 08:31:57 -03:00
|
|
|
# FailureDetector status
|
|
|
|
uint8 FAILURE_NONE = 0
|
|
|
|
uint8 FAILURE_ROLL = 1 # (1 << 0)
|
|
|
|
uint8 FAILURE_PITCH = 2 # (1 << 1)
|
|
|
|
uint8 FAILURE_ALT = 4 # (1 << 2)
|
|
|
|
|
|
|
|
# HIL
|
2014-12-18 07:08:39 -04:00
|
|
|
uint8 HIL_STATE_OFF = 0
|
|
|
|
uint8 HIL_STATE_ON = 1
|
|
|
|
|
|
|
|
# Navigation state, i.e. "what should vehicle do".
|
|
|
|
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_AUTO_RCRECOVER = 6 # RC recover mode
|
|
|
|
uint8 NAVIGATION_STATE_AUTO_RTGS = 7 # Auto return to groundstation on data link loss
|
|
|
|
uint8 NAVIGATION_STATE_AUTO_LANDENGFAIL = 8 # Auto land on engine failure
|
|
|
|
uint8 NAVIGATION_STATE_AUTO_LANDGPSFAIL = 9 # Auto land on gps failure (e.g. open loop loiter down)
|
|
|
|
uint8 NAVIGATION_STATE_ACRO = 10 # Acro mode
|
2016-03-13 11:39:12 -03:00
|
|
|
uint8 NAVIGATION_STATE_UNUSED = 11 # Free slot
|
2014-12-18 07:08:39 -04:00
|
|
|
uint8 NAVIGATION_STATE_DESCEND = 12 # Descend mode (no position control)
|
|
|
|
uint8 NAVIGATION_STATE_TERMINATION = 13 # Termination mode
|
|
|
|
uint8 NAVIGATION_STATE_OFFBOARD = 14
|
2015-05-17 07:58:44 -03:00
|
|
|
uint8 NAVIGATION_STATE_STAB = 15 # Stabilized mode
|
2015-10-20 21:38:42 -03:00
|
|
|
uint8 NAVIGATION_STATE_RATTITUDE = 16 # Rattitude (aka "flip") mode
|
2015-11-20 06:14:36 -04:00
|
|
|
uint8 NAVIGATION_STATE_AUTO_TAKEOFF = 17 # Takeoff
|
2016-03-13 11:39:12 -03:00
|
|
|
uint8 NAVIGATION_STATE_AUTO_LAND = 18 # Land
|
2016-02-18 10:57:01 -04:00
|
|
|
uint8 NAVIGATION_STATE_AUTO_FOLLOW_TARGET = 19 # Auto Follow
|
2018-01-14 13:52:00 -04:00
|
|
|
uint8 NAVIGATION_STATE_AUTO_PRECLAND = 20 # Precision land with landing target
|
2018-11-23 15:47:52 -04:00
|
|
|
uint8 NAVIGATION_STATE_ORBIT = 21 # Orbit in a circle
|
|
|
|
uint8 NAVIGATION_STATE_MAX = 22
|
2014-12-18 07:08:39 -04:00
|
|
|
|
2015-05-24 12:40:06 -03:00
|
|
|
uint8 RC_IN_MODE_DEFAULT = 0
|
|
|
|
uint8 RC_IN_MODE_OFF = 1
|
|
|
|
uint8 RC_IN_MODE_GENERATED = 2
|
|
|
|
|
2014-12-18 07:08:39 -04:00
|
|
|
# state machine / state of vehicle.
|
|
|
|
# Encodes the complete system state and is set by the commander app.
|
|
|
|
|
|
|
|
uint8 nav_state # set navigation state machine to specified value
|
|
|
|
uint8 arming_state # current arming state
|
|
|
|
uint8 hil_state # current hil state
|
2018-08-10 08:31:57 -03:00
|
|
|
bool failsafe # true if system is in failsafe state (e.g.:RTL, Hover, Terminate, ...)
|
2014-12-18 07:08:39 -04:00
|
|
|
|
2016-02-24 06:10:50 -04:00
|
|
|
uint8 system_type # system type, contains mavlink MAV_TYPE
|
2017-09-26 13:25:02 -03:00
|
|
|
uint8 system_id # system id, contains MAVLink's system ID field
|
|
|
|
uint8 component_id # subsystem / component id, contains MAVLink's component ID field
|
2014-12-18 07:08:39 -04:00
|
|
|
|
2014-12-25 04:59:58 -04:00
|
|
|
bool is_rotary_wing # True if system is in rotary wing configuration, so for a VTOL this is only true while flying as a multicopter
|
|
|
|
bool is_vtol # True if the system is VTOL capable
|
2016-11-23 10:23:04 -04:00
|
|
|
bool vtol_fw_permanent_stab # True if VTOL should stabilize attitude for fw in manual mode
|
2016-02-08 05:20:22 -04:00
|
|
|
bool in_transition_mode # True if VTOL is doing a transition
|
2016-05-26 02:06:06 -03:00
|
|
|
bool in_transition_to_fw # True if VTOL is doing a transition from MC to FW
|
2014-12-18 07:08:39 -04:00
|
|
|
|
|
|
|
bool rc_signal_lost # true if RC reception lost
|
2015-05-25 11:34:21 -03:00
|
|
|
uint8 rc_input_mode # set to 1 to disable the RC input, 2 to enable manual control to RC in mapping.
|
2014-12-18 07:08:39 -04:00
|
|
|
|
|
|
|
bool data_link_lost # datalink to GCS lost
|
2018-01-31 06:04:59 -04:00
|
|
|
bool high_latency_data_link_active # all low latency datalinks to GCS lost
|
2014-12-18 07:08:39 -04:00
|
|
|
uint8 data_link_lost_counter # counts unique data link lost events
|
|
|
|
bool engine_failure # Set to true if an engine failure is detected
|
2016-02-12 20:08:07 -04:00
|
|
|
bool mission_failure # Set to true if mission could not continue/finish
|
2018-08-10 08:31:57 -03:00
|
|
|
uint8 failure_detector_status # Bitmask containing FailureDetector status [0, 0, 0, 0, 0, FAILURE_ALT, FAILURE_PITCH, FAILURE_ROLL]
|
2014-12-18 07:08:39 -04:00
|
|
|
|
|
|
|
# see SYS_STATUS mavlink message for the following
|
|
|
|
uint32 onboard_control_sensors_present
|
|
|
|
uint32 onboard_control_sensors_enabled
|
|
|
|
uint32 onboard_control_sensors_health
|