@@ -14,3 +14,69 @@ bool guided
14
14
bool manual_input
15
15
string mode
16
16
uint8 system_status
17
+
18
+ string MODE_APM_PLANE_MANUAL = "MANUAL"
19
+ string MODE_APM_PLANE_CIRCLE = "CIRCLE"
20
+ string MODE_APM_PLANE_STABILIZE = "STABILIZE"
21
+ string MODE_APM_PLANE_TRAINING = "TRAINING"
22
+ string MODE_APM_PLANE_ACRO = "ACRO"
23
+ string MODE_APM_PLANE_FBWA = "FBWA"
24
+ string MODE_APM_PLANE_FBWB = "FBWB"
25
+ string MODE_APM_PLANE_CRUISE = "CRUISE"
26
+ string MODE_APM_PLANE_AUTOTUNE = "AUTOTUNE"
27
+ string MODE_APM_PLANE_AUTO = "AUTO"
28
+ string MODE_APM_PLANE_RTL = "RTL"
29
+ string MODE_APM_PLANE_LOITER = "LOITER"
30
+ string MODE_APM_PLANE_LAND = "LAND"
31
+ string MODE_APM_PLANE_GUIDED = "GUIDED"
32
+ string MODE_APM_PLANE_INITIALISING = "INITIALISING"
33
+ string MODE_APM_PLANE_QSTABILIZE = "QSTABILIZE"
34
+ string MODE_APM_PLANE_QHOVER = "QHOVER"
35
+ string MODE_APM_PLANE_QLOITER = "QLOITER"
36
+ string MODE_APM_PLANE_QLAND = "QLAND"
37
+ string MODE_APM_PLANE_QRTL = "QRTL"
38
+
39
+ string MODE_APM_COPTER_STABILIZE = "STABILIZE"
40
+ string MODE_APM_COPTER_ACRO = "ACRO"
41
+ string MODE_APM_COPTER_ALT_HOLD = "ALT_HOLD"
42
+ string MODE_APM_COPTER_AUTO = "AUTO"
43
+ string MODE_APM_COPTER_GUIDED = "GUIDED"
44
+ string MODE_APM_COPTER_LOITER = "LOITER"
45
+ string MODE_APM_COPTER_RTL = "RTL"
46
+ string MODE_APM_COPTER_CIRCLE = "CIRCLE"
47
+ string MODE_APM_COPTER_POSITION = "POSITION"
48
+ string MODE_APM_COPTER_LAND = "LAND"
49
+ string MODE_APM_COPTER_OF_LOITER = "OF_LOITER"
50
+ string MODE_APM_COPTER_DRIFT = "DRIFT"
51
+ string MODE_APM_COPTER_SPORT = "SPORT"
52
+ string MODE_APM_COPTER_FLIP = "FLIP"
53
+ string MODE_APM_COPTER_AUTOTUNE = "AUTOTUNE"
54
+ string MODE_APM_COPTER_POSHOLD = "POSHOLD"
55
+ string MODE_APM_COPTER_BRAKE = "BRAKE"
56
+ string MODE_APM_COPTER_THROW = "THROW"
57
+ string MODE_APM_COPTER_AVOID_ADSB = "AVOID_ADSB"
58
+ string MODE_APM_COPTER_GUIDED_NOGPS = "GUIDED_NOGPS"
59
+
60
+ string MODE_APM_ROVER_MANUAL = "MANUAL"
61
+ string MODE_APM_ROVER_LEARNING = "LEARNING"
62
+ string MODE_APM_ROVER_STEERING = "STEERING"
63
+ string MODE_APM_ROVER_HOLD = "HOLD"
64
+ string MODE_APM_ROVER_AUTO = "AUTO"
65
+ string MODE_APM_ROVER_RTL = "RTL"
66
+ string MODE_APM_ROVER_GUIDED = "GUIDED"
67
+ string MODE_APM_ROVER_INITIALISING = "INITIALISING"
68
+
69
+ string MODE_PX4_MANUAL = "MANUAL"
70
+ string MODE_PX4_ACRO = "ACRO"
71
+ string MODE_PX4_ALTITUDE = "ALTCTL"
72
+ string MODE_PX4_POSITION = "POSCTL"
73
+ string MODE_PX4_OFFBOARD = "OFFBOARD"
74
+ string MODE_PX4_STABILIZED = "STABILIZED"
75
+ string MODE_PX4_RATTITUDE = "RATTITUDE"
76
+ string MODE_PX4_MISSION = "AUTO.MISSION"
77
+ string MODE_PX4_LOITER = "AUTO.LOITER"
78
+ string MODE_PX4_RTL = "AUTO.RTL"
79
+ string MODE_PX4_LAND = "AUTO.LAND"
80
+ string MODE_PX4_RTGS = "AUTO.RTGS"
81
+ string MODE_PX4_READY = "AUTO.READY"
82
+ string MODE_PX4_TAKEOFF = "AUTO.TAKEOFF"
0 commit comments