1 //*******************************************************
2 // Copyright (c) MLRS project
4 // https://www.gnu.org/licenses/gpl-3.0.de.html
5 // OlliW @ www.olliw.eu
6 //*******************************************************
7 // ArduPilot Protocol Stuff
8 //*******************************************************
10 #ifndef ARDUPILOT_PROTOCOL_H
11 #define ARDUPILOT_PROTOCOL_H
14 //-------------------------------------------------------
15 // ArduPilot flight modes
16 //-------------------------------------------------------
18 // this we got from ArduCopter/mode.h
20 AP_COPTER_FLIGHTMODE_STABILIZE
= 0, // manual airframe angle with manual throttle
21 AP_COPTER_FLIGHTMODE_ACRO
= 1, // manual body-frame angular rate with manual throttle
22 AP_COPTER_FLIGHTMODE_ALT_HOLD
= 2, // manual airframe angle with automatic throttle
23 AP_COPTER_FLIGHTMODE_AUTO
= 3, // fully automatic waypoint control using mission commands
24 AP_COPTER_FLIGHTMODE_GUIDED
= 4, // fully automatic fly to coordinate or fly at velocity/direction using GCS immediate commands
25 AP_COPTER_FLIGHTMODE_LOITER
= 5, // automatic horizontal acceleration with automatic throttle
26 AP_COPTER_FLIGHTMODE_RTL
= 6, // automatic return to launching point
27 AP_COPTER_FLIGHTMODE_CIRCLE
= 7, // automatic circular flight with automatic throttle
28 AP_COPTER_FLIGHTMODE_LAND
= 9, // automatic landing with horizontal position control
29 AP_COPTER_FLIGHTMODE_DRIFT
= 11, // semi-autonomous position, yaw and throttle control
30 AP_COPTER_FLIGHTMODE_SPORT
= 13, // manual earth-frame angular rate control with manual throttle
31 AP_COPTER_FLIGHTMODE_FLIP
= 14, // automatically flip the vehicle on the roll axis
32 AP_COPTER_FLIGHTMODE_AUTOTUNE
= 15, // automatically tune the vehicle's roll and pitch gains
33 AP_COPTER_FLIGHTMODE_POSHOLD
= 16, // automatic position hold with manual override, with automatic throttle
34 AP_COPTER_FLIGHTMODE_BRAKE
= 17, // full-brake using inertial/GPS system, no pilot input
35 AP_COPTER_FLIGHTMODE_THROW
= 18, // throw to launch mode using inertial/GPS system, no pilot input
36 AP_COPTER_FLIGHTMODE_AVOID_ADSB
= 19, // automatic avoidance of obstacles in the macro scale - e.g. full-sized aircraft
37 AP_COPTER_FLIGHTMODE_GUIDED_NOGPS
= 20, // guided mode but only accepts attitude and altitude
38 AP_COPTER_FLIGHTMODE_SMART_RTL
= 21, // SMART_RTL returns to home by retracing its steps
39 AP_COPTER_FLIGHTMODE_FLOWHOLD
= 22, // FLOWHOLD holds position with optical flow without rangefinder
40 AP_COPTER_FLIGHTMODE_FOLLOW
= 23, // follow attempts to follow another vehicle or ground station
41 AP_COPTER_FLIGHTMODE_ZIGZAG
= 24, // ZIGZAG mode is able to fly in a zigzag manner with predefined point A and point B
42 AP_COPTER_FLIGHTMODE_SYSTEMID
= 25, // System ID mode produces automated system identification signals in the controllers
43 AP_COPTER_FLIGHTMODE_AUTOROTATE
= 26, // Autonomous autorotation
44 AP_COPTER_FLIGHTMODE_AUTO_RTL
= 27, // Auto RTL, this is not a true mode, AUTO will report as this mode if entered to perform a DO_LAND_START Landing sequence
45 AP_COPTER_FLIGHTMODE_TURTLE
= 28, // Flip over after crash
46 } AP_COPTER_FLIGHTMODE_ENUM
;
49 // this we got from ArduPlane/mode.h
51 AP_PLANE_FLIGHTMODE_MANUAL
= 0,
52 AP_PLANE_FLIGHTMODE_CIRCLE
= 1,
53 AP_PLANE_FLIGHTMODE_STABILIZE
= 2,
54 AP_PLANE_FLIGHTMODE_TRAINING
= 3,
55 AP_PLANE_FLIGHTMODE_ACRO
= 4,
56 AP_PLANE_FLIGHTMODE_FLY_BY_WIRE_A
= 5,
57 AP_PLANE_FLIGHTMODE_FLY_BY_WIRE_B
= 6,
58 AP_PLANE_FLIGHTMODE_CRUISE
= 7,
59 AP_PLANE_FLIGHTMODE_AUTOTUNE
= 8,
60 AP_PLANE_FLIGHTMODE_AUTO
= 10,
61 AP_PLANE_FLIGHTMODE_RTL
= 11,
62 AP_PLANE_FLIGHTMODE_LOITER
= 12,
63 AP_PLANE_FLIGHTMODE_TAKEOFF
= 13,
64 AP_PLANE_FLIGHTMODE_AVOID_ADSB
= 14,
65 AP_PLANE_FLIGHTMODE_GUIDED
= 15,
66 AP_PLANE_FLIGHTMODE_INITIALISING
= 16,
67 AP_PLANE_FLIGHTMODE_QSTABILIZE
= 17,
68 AP_PLANE_FLIGHTMODE_QHOVER
= 18,
69 AP_PLANE_FLIGHTMODE_QLOITER
= 19,
70 AP_PLANE_FLIGHTMODE_QLAND
= 20,
71 AP_PLANE_FLIGHTMODE_QRTL
= 21,
72 AP_PLANE_FLIGHTMODE_QAUTOTUNE
= 22,
73 AP_PLANE_FLIGHTMODE_QACRO
= 23,
74 AP_PLANE_FLIGHTMODE_THERMAL
= 24,
75 AP_PLANE_FLIGHTMODE_LOITER_ALT_QLAND
= 25,
76 } AP_PLANE_FLIGHTMODE_ENUM
;
79 // this we got from Rover/mode.h
81 AP_ROVER_FLIGHTMODE_MANUAL
= 0,
82 AP_ROVER_FLIGHTMODE_ACRO
= 1,
83 AP_ROVER_FLIGHTMODE_STEERING
= 3,
84 AP_ROVER_FLIGHTMODE_HOLD
= 4,
85 AP_ROVER_FLIGHTMODE_LOITER
= 5,
86 AP_ROVER_FLIGHTMODE_FOLLOW
= 6,
87 AP_ROVER_FLIGHTMODE_SIMPLE
= 7,
88 AP_ROVER_FLIGHTMODE_DOCK
= 8,
89 AP_ROVER_FLIGHTMODE_AUTO
= 10,
90 AP_ROVER_FLIGHTMODE_RTL
= 11,
91 AP_ROVER_FLIGHTMODE_SMART_RTL
= 12,
92 AP_ROVER_FLIGHTMODE_GUIDED
= 15,
93 AP_ROVER_FLIGHTMODE_INITIALISING
= 16,
94 } AP_ROVER_FLIGHTMODE_ENUM
;
97 // this we got from ArduSub/defines.h
99 AP_SUB_FLIGHTMODE_STABILIZE
= 0, // manual angle with manual depth/throttle
100 AP_SUB_FLIGHTMODE_ACRO
= 1, // manual body-frame angular rate with manual depth/throttle
101 AP_SUB_FLIGHTMODE_ALT_HOLD
= 2, // manual angle with automatic depth/throttle
102 AP_SUB_FLIGHTMODE_AUTO
= 3, // fully automatic waypoint control using mission commands
103 AP_SUB_FLIGHTMODE_GUIDED
= 4, // fully automatic fly to coordinate or fly at velocity/direction using GCS immediate commands
104 AP_SUB_FLIGHTMODE_CIRCLE
= 7, // automatic circular flight with automatic throttle
105 AP_SUB_FLIGHTMODE_SURFACE
= 9, // automatically return to surface, pilot maintains horizontal control
106 AP_SUB_FLIGHTMODE_POSHOLD
= 16, // automatic position hold with manual override, with automatic throttle
107 AP_SUB_FLIGHTMODE_MANUAL
= 19, // Pass-through input with no stabilization
108 AP_SUB_FLIGHTMODE_MOTOR_DETECT
= 20 // Automatically detect motors orientation
109 } AP_SUB_FLIGHTMODE_ENUM
;
112 // these we find in ArduCopter/mode.h
113 void ap_copter_flight_mode_name4(char* name4
, uint8_t flight_mode
)
115 switch (flight_mode
) {
116 case AP_COPTER_FLIGHTMODE_STABILIZE
: strcpy(name4
, "STAB"); break;
117 case AP_COPTER_FLIGHTMODE_ACRO
: strcpy(name4
, "ACRO"); break;
118 case AP_COPTER_FLIGHTMODE_ALT_HOLD
: strcpy(name4
, "ALTH"); break;
119 case AP_COPTER_FLIGHTMODE_AUTO
: strcpy(name4
, "AUTO"); break; // can be also "ARTL"
120 case AP_COPTER_FLIGHTMODE_GUIDED
: strcpy(name4
, "GUID"); break;
121 case AP_COPTER_FLIGHTMODE_LOITER
: strcpy(name4
, "LOIT"); break;
122 case AP_COPTER_FLIGHTMODE_RTL
: strcpy(name4
, "RTL "); break;
123 case AP_COPTER_FLIGHTMODE_CIRCLE
: strcpy(name4
, "CIRC"); break;
124 case AP_COPTER_FLIGHTMODE_LAND
: strcpy(name4
, "LAND"); break;
125 case AP_COPTER_FLIGHTMODE_DRIFT
: strcpy(name4
, "DRIF"); break;
126 case AP_COPTER_FLIGHTMODE_SPORT
: strcpy(name4
, "SPRT"); break;
127 case AP_COPTER_FLIGHTMODE_FLIP
: strcpy(name4
, "FLIP"); break;
128 case AP_COPTER_FLIGHTMODE_AUTOTUNE
: strcpy(name4
, "ATUN"); break;
129 case AP_COPTER_FLIGHTMODE_POSHOLD
: strcpy(name4
, "PHLD"); break;
130 case AP_COPTER_FLIGHTMODE_BRAKE
: strcpy(name4
, "BRAK"); break;
131 case AP_COPTER_FLIGHTMODE_THROW
: strcpy(name4
, "THRW"); break;
132 case AP_COPTER_FLIGHTMODE_AVOID_ADSB
: strcpy(name4
, "AVOI"); break;
133 case AP_COPTER_FLIGHTMODE_GUIDED_NOGPS
: strcpy(name4
, "GNGP"); break;
134 case AP_COPTER_FLIGHTMODE_SMART_RTL
: strcpy(name4
, "SRTL"); break;
135 case AP_COPTER_FLIGHTMODE_FLOWHOLD
: strcpy(name4
, "FHLD"); break;
136 case AP_COPTER_FLIGHTMODE_FOLLOW
: strcpy(name4
, "FOLL"); break;
137 case AP_COPTER_FLIGHTMODE_ZIGZAG
: strcpy(name4
, "ZIGZ"); break;
138 case AP_COPTER_FLIGHTMODE_SYSTEMID
: strcpy(name4
, "SYSI"); break;
139 case AP_COPTER_FLIGHTMODE_AUTOROTATE
: strcpy(name4
, "AROT"); break;
140 case AP_COPTER_FLIGHTMODE_AUTO_RTL
: strcpy(name4
, "ARTL"); break;
141 case AP_COPTER_FLIGHTMODE_TURTLE
: strcpy(name4
, "TRTL"); break;
148 // these we find in ArduPlane/mode.h
149 void ap_plane_flight_mode_name4(char* name4
, uint8_t flight_mode
)
151 switch (flight_mode
) {
152 case AP_PLANE_FLIGHTMODE_MANUAL
: strcpy(name4
, "MANU"); break;
153 case AP_PLANE_FLIGHTMODE_CIRCLE
: strcpy(name4
, "CIRC"); break;
154 case AP_PLANE_FLIGHTMODE_STABILIZE
: strcpy(name4
, "STAB"); break;
155 case AP_PLANE_FLIGHTMODE_TRAINING
: strcpy(name4
, "TRAN"); break;
156 case AP_PLANE_FLIGHTMODE_ACRO
: strcpy(name4
, "ACRO"); break;
157 case AP_PLANE_FLIGHTMODE_FLY_BY_WIRE_A
: strcpy(name4
, "FBWA"); break;
158 case AP_PLANE_FLIGHTMODE_FLY_BY_WIRE_B
: strcpy(name4
, "FBWB"); break;
159 case AP_PLANE_FLIGHTMODE_CRUISE
: strcpy(name4
, "CRUS"); break;
160 case AP_PLANE_FLIGHTMODE_AUTOTUNE
: strcpy(name4
, "ATUN"); break;
161 case AP_PLANE_FLIGHTMODE_AUTO
: strcpy(name4
, "AUTO"); break;
162 case AP_PLANE_FLIGHTMODE_RTL
: strcpy(name4
, "RTL "); break;
163 case AP_PLANE_FLIGHTMODE_LOITER
: strcpy(name4
, "LOIT"); break;
164 case AP_PLANE_FLIGHTMODE_TAKEOFF
: strcpy(name4
, "TKOF"); break;
165 case AP_PLANE_FLIGHTMODE_AVOID_ADSB
: strcpy(name4
, "AVOI"); break;
166 case AP_PLANE_FLIGHTMODE_GUIDED
: strcpy(name4
, "GUID"); break;
167 case AP_PLANE_FLIGHTMODE_INITIALISING
: strcpy(name4
, "INIT"); break;
168 case AP_PLANE_FLIGHTMODE_QSTABILIZE
: strcpy(name4
, "QSTB"); break;
169 case AP_PLANE_FLIGHTMODE_QHOVER
: strcpy(name4
, "QHOV"); break;
170 case AP_PLANE_FLIGHTMODE_QLOITER
: strcpy(name4
, "QLOT"); break;
171 case AP_PLANE_FLIGHTMODE_QLAND
: strcpy(name4
, "QLND"); break;
172 case AP_PLANE_FLIGHTMODE_QRTL
: strcpy(name4
, "QRTL"); break;
173 case AP_PLANE_FLIGHTMODE_QAUTOTUNE
: strcpy(name4
, "QATN"); break;
174 case AP_PLANE_FLIGHTMODE_QACRO
: strcpy(name4
, "QACO"); break;
175 case AP_PLANE_FLIGHTMODE_THERMAL
: strcpy(name4
, "THML"); break;
176 case AP_PLANE_FLIGHTMODE_LOITER_ALT_QLAND
: strcpy(name4
, "L2QL"); break;
183 // these we find in Rover/mode.h
184 void ap_rover_flight_mode_name4(char* name4
, uint8_t flight_mode
)
186 switch (flight_mode
) {
187 case AP_ROVER_FLIGHTMODE_MANUAL
: strcpy(name4
, "MANU"); break;
188 case AP_ROVER_FLIGHTMODE_ACRO
: strcpy(name4
, "ACRO"); break;
189 case AP_ROVER_FLIGHTMODE_STEERING
: strcpy(name4
, "STER"); break;
190 case AP_ROVER_FLIGHTMODE_HOLD
: strcpy(name4
, "HOLD"); break;
191 case AP_ROVER_FLIGHTMODE_LOITER
: strcpy(name4
, "LOIT"); break;
192 case AP_ROVER_FLIGHTMODE_FOLLOW
: strcpy(name4
, "FOLL"); break;
193 case AP_ROVER_FLIGHTMODE_SIMPLE
: strcpy(name4
, "SMPL"); break;
194 case AP_ROVER_FLIGHTMODE_DOCK
: strcpy(name4
, "DOCK"); break;
195 case AP_ROVER_FLIGHTMODE_AUTO
: strcpy(name4
, "AUTO"); break;
196 case AP_ROVER_FLIGHTMODE_RTL
: strcpy(name4
, "RTL "); break;
197 case AP_ROVER_FLIGHTMODE_SMART_RTL
: strcpy(name4
, "SRTL"); break;
198 case AP_ROVER_FLIGHTMODE_GUIDED
: strcpy(name4
, "GUID"); break;
199 case AP_ROVER_FLIGHTMODE_INITIALISING
: strcpy(name4
, "INIT"); break;
206 // there are these? made them up myself
207 void ap_sub_flight_mode_name4(char* name4
, uint8_t flight_mode
)
209 switch (flight_mode
) {
210 case AP_SUB_FLIGHTMODE_STABILIZE
: strcpy(name4
, "STAB"); break;
211 case AP_SUB_FLIGHTMODE_ACRO
: strcpy(name4
, "ACRO"); break;
212 case AP_SUB_FLIGHTMODE_ALT_HOLD
: strcpy(name4
, "AHLD"); break;
213 case AP_SUB_FLIGHTMODE_AUTO
: strcpy(name4
, "AUTO"); break;
214 case AP_SUB_FLIGHTMODE_GUIDED
: strcpy(name4
, "GUID"); break;
215 case AP_SUB_FLIGHTMODE_CIRCLE
: strcpy(name4
, "CIRC"); break;
216 case AP_SUB_FLIGHTMODE_SURFACE
: strcpy(name4
, "SURF"); break; // ?
217 case AP_SUB_FLIGHTMODE_POSHOLD
: strcpy(name4
, "PHLD"); break;
218 case AP_SUB_FLIGHTMODE_MANUAL
: strcpy(name4
, "MANU"); break;
219 case AP_SUB_FLIGHTMODE_MOTOR_DETECT
: strcpy(name4
, "MDET"); break; // ?
226 //-------------------------------------------------------
227 // ArduPilot vehicles
228 //-------------------------------------------------------
231 AP_VEHICLE_GENERIC
= 0,
239 // this we deduce by searching for MAV_TYPE in ArduPilot code
240 uint8_t ap_vehicle_from_mavtype(uint8_t mav_type
)
243 case MAV_TYPE_COAXIAL
:
244 case MAV_TYPE_HELICOPTER
:
245 case MAV_TYPE_TRICOPTER
:
246 case MAV_TYPE_QUADROTOR
:
247 case MAV_TYPE_HEXAROTOR
:
248 case MAV_TYPE_OCTOROTOR
:
249 case MAV_TYPE_DECAROTOR
:
250 case MAV_TYPE_DODECAROTOR
:
251 return AP_VEHICLE_COPTER
;
253 case MAV_TYPE_SURFACE_BOAT
:
254 case MAV_TYPE_GROUND_ROVER
:
255 return AP_VEHICLE_ROVER
;
257 case MAV_TYPE_SUBMARINE
:
258 return AP_VEHICLE_SUB
;
260 case MAV_TYPE_GENERIC
:
261 return AP_VEHICLE_GENERIC
; // sadly we don't know nothing
264 return AP_VEHICLE_PLANE
; // let's guess it's a plane
268 //-------------------------------------------------------
270 //-------------------------------------------------------
272 void ap_flight_mode_name4(char* name4
, uint8_t vehicle
, uint8_t flight_mode
)
275 case AP_VEHICLE_COPTER
:
276 ap_copter_flight_mode_name4(name4
, flight_mode
);
278 case AP_VEHICLE_PLANE
:
279 ap_plane_flight_mode_name4(name4
, flight_mode
);
281 case AP_VEHICLE_ROVER
:
282 ap_rover_flight_mode_name4(name4
, flight_mode
);
285 ap_sub_flight_mode_name4(name4
, flight_mode
);
292 #endif // ARDUPILOT_PROTOCOL_H