SDCard: multi-block write, card profiling. AFATFS: Bugfixes
[betaflight.git] / src / main / blackbox / blackbox.c
blob24455b05e838c0fc845de91eeba73d6c41ed5434
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #include <stdbool.h>
19 #include <string.h>
21 #include "platform.h"
22 #include "version.h"
23 #include "debug.h"
25 #ifdef BLACKBOX
27 #include "common/maths.h"
28 #include "common/axis.h"
29 #include "common/color.h"
30 #include "common/encoding.h"
31 #include "common/utils.h"
33 #include "drivers/gpio.h"
34 #include "drivers/sensor.h"
35 #include "drivers/system.h"
36 #include "drivers/serial.h"
37 #include "drivers/compass.h"
38 #include "drivers/timer.h"
39 #include "drivers/pwm_rx.h"
40 #include "drivers/accgyro.h"
41 #include "drivers/light_led.h"
43 #include "sensors/sensors.h"
44 #include "sensors/boardalignment.h"
45 #include "sensors/sonar.h"
46 #include "sensors/compass.h"
47 #include "sensors/acceleration.h"
48 #include "sensors/barometer.h"
49 #include "sensors/gyro.h"
50 #include "sensors/battery.h"
52 #include "io/beeper.h"
53 #include "io/display.h"
54 #include "io/escservo.h"
55 #include "io/rc_controls.h"
56 #include "io/gimbal.h"
57 #include "io/gps.h"
58 #include "io/ledstrip.h"
59 #include "io/serial.h"
60 #include "io/serial_cli.h"
61 #include "io/serial_msp.h"
62 #include "io/statusindicator.h"
64 #include "rx/rx.h"
65 #include "rx/msp.h"
67 #include "telemetry/telemetry.h"
69 #include "flight/mixer.h"
70 #include "flight/altitudehold.h"
71 #include "flight/failsafe.h"
72 #include "flight/imu.h"
73 #include "flight/navigation.h"
75 #include "config/runtime_config.h"
76 #include "config/config.h"
77 #include "config/config_profile.h"
78 #include "config/config_master.h"
80 #include "blackbox.h"
81 #include "blackbox_io.h"
83 #define BLACKBOX_I_INTERVAL 32
84 #define BLACKBOX_SHUTDOWN_TIMEOUT_MILLIS 200
85 #define SLOW_FRAME_INTERVAL 4096
87 #define ARRAY_LENGTH(x) (sizeof((x))/sizeof((x)[0]))
89 #define STATIC_ASSERT(condition, name ) \
90 typedef char assert_failed_ ## name [(condition) ? 1 : -1 ]
92 // Some macros to make writing FLIGHT_LOG_FIELD_* constants shorter:
94 #define PREDICT(x) CONCAT(FLIGHT_LOG_FIELD_PREDICTOR_, x)
95 #define ENCODING(x) CONCAT(FLIGHT_LOG_FIELD_ENCODING_, x)
96 #define CONDITION(x) CONCAT(FLIGHT_LOG_FIELD_CONDITION_, x)
97 #define UNSIGNED FLIGHT_LOG_FIELD_UNSIGNED
98 #define SIGNED FLIGHT_LOG_FIELD_SIGNED
100 static const char blackboxHeader[] =
101 "H Product:Blackbox flight data recorder by Nicholas Sherlock\n"
102 "H Data version:2\n"
103 "H I interval:" STR(BLACKBOX_I_INTERVAL) "\n";
105 static const char* const blackboxFieldHeaderNames[] = {
106 "name",
107 "signed",
108 "predictor",
109 "encoding",
110 "predictor",
111 "encoding"
114 /* All field definition structs should look like this (but with longer arrs): */
115 typedef struct blackboxFieldDefinition_s {
116 const char *name;
117 // If the field name has a number to be included in square brackets [1] afterwards, set it here, or -1 for no brackets:
118 int8_t fieldNameIndex;
120 // Each member of this array will be the value to print for this field for the given header index
121 uint8_t arr[1];
122 } blackboxFieldDefinition_t;
124 #define BLACKBOX_DELTA_FIELD_HEADER_COUNT ARRAY_LENGTH(blackboxFieldHeaderNames)
125 #define BLACKBOX_SIMPLE_FIELD_HEADER_COUNT (BLACKBOX_DELTA_FIELD_HEADER_COUNT - 2)
126 #define BLACKBOX_CONDITIONAL_FIELD_HEADER_COUNT (BLACKBOX_DELTA_FIELD_HEADER_COUNT - 2)
128 typedef struct blackboxSimpleFieldDefinition_s {
129 const char *name;
130 int8_t fieldNameIndex;
132 uint8_t isSigned;
133 uint8_t predict;
134 uint8_t encode;
135 } blackboxSimpleFieldDefinition_t;
137 typedef struct blackboxConditionalFieldDefinition_s {
138 const char *name;
139 int8_t fieldNameIndex;
141 uint8_t isSigned;
142 uint8_t predict;
143 uint8_t encode;
144 uint8_t condition; // Decide whether this field should appear in the log
145 } blackboxConditionalFieldDefinition_t;
147 typedef struct blackboxDeltaFieldDefinition_s {
148 const char *name;
149 int8_t fieldNameIndex;
151 uint8_t isSigned;
152 uint8_t Ipredict;
153 uint8_t Iencode;
154 uint8_t Ppredict;
155 uint8_t Pencode;
156 uint8_t condition; // Decide whether this field should appear in the log
157 } blackboxDeltaFieldDefinition_t;
160 * Description of the blackbox fields we are writing in our main intra (I) and inter (P) frames. This description is
161 * written into the flight log header so the log can be properly interpreted (but these definitions don't actually cause
162 * the encoding to happen, we have to encode the flight log ourselves in write{Inter|Intra}frame() in a way that matches
163 * the encoding we've promised here).
165 static const blackboxDeltaFieldDefinition_t blackboxMainFields[] = {
166 /* loopIteration doesn't appear in P frames since it always increments */
167 {"loopIteration",-1, UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(INC), .Pencode = FLIGHT_LOG_FIELD_ENCODING_NULL, CONDITION(ALWAYS)},
168 /* Time advances pretty steadily so the P-frame prediction is a straight line */
169 {"time", -1, UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(STRAIGHT_LINE), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
170 {"axisP", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
171 {"axisP", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
172 {"axisP", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
173 /* I terms get special packed encoding in P frames: */
174 {"axisI", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG2_3S32), CONDITION(ALWAYS)},
175 {"axisI", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG2_3S32), CONDITION(ALWAYS)},
176 {"axisI", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG2_3S32), CONDITION(ALWAYS)},
177 {"axisD", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(NONZERO_PID_D_0)},
178 {"axisD", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(NONZERO_PID_D_1)},
179 {"axisD", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(NONZERO_PID_D_2)},
180 /* rcCommands are encoded together as a group in P-frames: */
181 {"rcCommand", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_4S16), CONDITION(ALWAYS)},
182 {"rcCommand", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_4S16), CONDITION(ALWAYS)},
183 {"rcCommand", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_4S16), CONDITION(ALWAYS)},
184 /* Throttle is always in the range [minthrottle..maxthrottle]: */
185 {"rcCommand", 3, UNSIGNED, .Ipredict = PREDICT(MINTHROTTLE), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_4S16), CONDITION(ALWAYS)},
187 {"vbatLatest", -1, UNSIGNED, .Ipredict = PREDICT(VBATREF), .Iencode = ENCODING(NEG_14BIT), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_VBAT},
188 {"amperageLatest",-1, UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC},
190 #ifdef MAG
191 {"magADC", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_MAG},
192 {"magADC", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_MAG},
193 {"magADC", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_MAG},
194 #endif
195 #ifdef BARO
196 {"BaroAlt", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_BARO},
197 #endif
198 #ifdef SONAR
199 {"sonarRaw", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_SONAR},
200 #endif
201 {"rssi", -1, UNSIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_RSSI},
203 /* Gyros and accelerometers base their P-predictions on the average of the previous 2 frames to reduce noise impact */
204 {"gyroADC", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
205 {"gyroADC", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
206 {"gyroADC", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
207 {"accSmooth", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
208 {"accSmooth", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
209 {"accSmooth", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
210 {"debug", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
211 {"debug", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
212 {"debug", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
213 {"debug", 3, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
214 /* Motors only rarely drops under minthrottle (when stick falls below mincommand), so predict minthrottle for it and use *unsigned* encoding (which is large for negative numbers but more compact for positive ones): */
215 {"motor", 0, UNSIGNED, .Ipredict = PREDICT(MINTHROTTLE), .Iencode = ENCODING(UNSIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_1)},
216 /* Subsequent motors base their I-frame values on the first one, P-frame values on the average of last two frames: */
217 {"motor", 1, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_2)},
218 {"motor", 2, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_3)},
219 {"motor", 3, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_4)},
220 {"motor", 4, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_5)},
221 {"motor", 5, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_6)},
222 {"motor", 6, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_7)},
223 {"motor", 7, UNSIGNED, .Ipredict = PREDICT(MOTOR_0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), CONDITION(AT_LEAST_MOTORS_8)},
225 /* Tricopter tail servo */
226 {"servo", 5, UNSIGNED, .Ipredict = PREDICT(1500), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(SIGNED_VB), CONDITION(TRICOPTER)}
229 #ifdef GPS
230 // GPS position/vel frame
231 static const blackboxConditionalFieldDefinition_t blackboxGpsGFields[] = {
232 {"time", -1, UNSIGNED, PREDICT(LAST_MAIN_FRAME_TIME), ENCODING(UNSIGNED_VB), CONDITION(NOT_LOGGING_EVERY_FRAME)},
233 {"GPS_numSat", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB), CONDITION(ALWAYS)},
234 {"GPS_coord", 0, SIGNED, PREDICT(HOME_COORD), ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
235 {"GPS_coord", 1, SIGNED, PREDICT(HOME_COORD), ENCODING(SIGNED_VB), CONDITION(ALWAYS)},
236 {"GPS_altitude", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB), CONDITION(ALWAYS)},
237 {"GPS_speed", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB), CONDITION(ALWAYS)},
238 {"GPS_ground_course", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB), CONDITION(ALWAYS)}
241 // GPS home frame
242 static const blackboxSimpleFieldDefinition_t blackboxGpsHFields[] = {
243 {"GPS_home", 0, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)},
244 {"GPS_home", 1, SIGNED, PREDICT(0), ENCODING(SIGNED_VB)}
246 #endif
248 // Rarely-updated fields
249 static const blackboxSimpleFieldDefinition_t blackboxSlowFields[] = {
250 {"flightModeFlags", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
251 {"stateFlags", -1, UNSIGNED, PREDICT(0), ENCODING(UNSIGNED_VB)},
253 {"failsafePhase", -1, UNSIGNED, PREDICT(0), ENCODING(TAG2_3S32)},
254 {"rxSignalReceived", -1, UNSIGNED, PREDICT(0), ENCODING(TAG2_3S32)},
255 {"rxFlightChannelsValid", -1, UNSIGNED, PREDICT(0), ENCODING(TAG2_3S32)}
258 typedef enum BlackboxState {
259 BLACKBOX_STATE_DISABLED = 0,
260 BLACKBOX_STATE_STOPPED,
261 BLACKBOX_STATE_PREPARE_LOG_FILE,
262 BLACKBOX_STATE_SEND_HEADER,
263 BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER,
264 BLACKBOX_STATE_SEND_GPS_H_HEADER,
265 BLACKBOX_STATE_SEND_GPS_G_HEADER,
266 BLACKBOX_STATE_SEND_SLOW_HEADER,
267 BLACKBOX_STATE_SEND_SYSINFO,
268 BLACKBOX_STATE_PAUSED,
269 BLACKBOX_STATE_RUNNING,
270 BLACKBOX_STATE_SHUTTING_DOWN
271 } BlackboxState;
273 #define BLACKBOX_FIRST_HEADER_SENDING_STATE BLACKBOX_STATE_SEND_HEADER
274 #define BLACKBOX_LAST_HEADER_SENDING_STATE BLACKBOX_STATE_SEND_SYSINFO
276 typedef struct blackboxMainState_s {
277 uint32_t time;
279 int32_t axisPID_P[XYZ_AXIS_COUNT], axisPID_I[XYZ_AXIS_COUNT], axisPID_D[XYZ_AXIS_COUNT];
281 int16_t rcCommand[4];
282 int16_t gyroADC[XYZ_AXIS_COUNT];
283 int16_t accSmooth[XYZ_AXIS_COUNT];
284 int16_t debug[4];
285 int16_t motor[MAX_SUPPORTED_MOTORS];
286 int16_t servo[MAX_SUPPORTED_SERVOS];
288 uint16_t vbatLatest;
289 uint16_t amperageLatest;
291 #ifdef BARO
292 int32_t BaroAlt;
293 #endif
294 #ifdef MAG
295 int16_t magADC[XYZ_AXIS_COUNT];
296 #endif
297 #ifdef SONAR
298 int32_t sonarRaw;
299 #endif
300 uint16_t rssi;
301 } blackboxMainState_t;
303 typedef struct blackboxGpsState_s {
304 int32_t GPS_home[2], GPS_coord[2];
305 uint8_t GPS_numSat;
306 } blackboxGpsState_t;
308 // This data is updated really infrequently:
309 typedef struct blackboxSlowState_s {
310 uint16_t flightModeFlags;
311 uint8_t stateFlags;
312 uint8_t failsafePhase;
313 bool rxSignalReceived;
314 bool rxFlightChannelsValid;
315 } __attribute__((__packed__)) blackboxSlowState_t; // We pack this struct so that padding doesn't interfere with memcmp()
317 //From mixer.c:
318 extern uint8_t motorCount;
320 //From mw.c:
321 extern uint32_t currentTime;
323 //From rx.c:
324 extern uint16_t rssi;
326 static BlackboxState blackboxState = BLACKBOX_STATE_DISABLED;
328 static uint32_t blackboxLastArmingBeep = 0;
330 static struct {
331 uint32_t headerIndex;
333 /* Since these fields are used during different blackbox states (never simultaneously) we can
334 * overlap them to save on RAM
336 union {
337 int fieldIndex;
338 uint32_t startTime;
339 } u;
340 } xmitState;
342 // Cache for FLIGHT_LOG_FIELD_CONDITION_* test results:
343 static uint32_t blackboxConditionCache;
345 STATIC_ASSERT((sizeof(blackboxConditionCache) * 8) >= FLIGHT_LOG_FIELD_CONDITION_NEVER, too_many_flight_log_conditions);
347 static uint32_t blackboxIteration;
348 static uint16_t blackboxPFrameIndex, blackboxIFrameIndex;
349 static uint16_t blackboxSlowFrameIterationTimer;
350 static bool blackboxLoggedAnyFrames;
353 * We store voltages in I-frames relative to this, which was the voltage when the blackbox was activated.
354 * This helps out since the voltage is only expected to fall from that point and we can reduce our diffs
355 * to encode:
357 static uint16_t vbatReference;
359 static blackboxGpsState_t gpsHistory;
360 static blackboxSlowState_t slowHistory;
362 // Keep a history of length 2, plus a buffer for MW to store the new values into
363 static blackboxMainState_t blackboxHistoryRing[3];
365 // These point into blackboxHistoryRing, use them to know where to store history of a given age (0, 1 or 2 generations old)
366 static blackboxMainState_t* blackboxHistory[3];
368 static bool blackboxModeActivationConditionPresent = false;
371 * Return true if it is safe to edit the Blackbox configuration in the emasterConfig.
373 bool blackboxMayEditConfig()
375 return blackboxState <= BLACKBOX_STATE_STOPPED;
378 static bool blackboxIsOnlyLoggingIntraframes() {
379 return masterConfig.blackbox_rate_num == 1 && masterConfig.blackbox_rate_denom == 32;
382 static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
384 switch (condition) {
385 case FLIGHT_LOG_FIELD_CONDITION_ALWAYS:
386 return true;
388 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1:
389 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_2:
390 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_3:
391 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_4:
392 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_5:
393 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_6:
394 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7:
395 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8:
396 return motorCount >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1 + 1;
398 case FLIGHT_LOG_FIELD_CONDITION_TRICOPTER:
399 return masterConfig.mixerMode == MIXER_TRI || masterConfig.mixerMode == MIXER_CUSTOM_TRI;
401 case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0:
402 case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1:
403 case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2:
404 if (IS_PID_CONTROLLER_FP_BASED(currentProfile->pidProfile.pidController)) {
405 return currentProfile->pidProfile.D_f[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0] != 0;
406 } else {
407 return currentProfile->pidProfile.D8[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0] != 0;
410 case FLIGHT_LOG_FIELD_CONDITION_MAG:
411 #ifdef MAG
412 return sensors(SENSOR_MAG);
413 #else
414 return false;
415 #endif
417 case FLIGHT_LOG_FIELD_CONDITION_BARO:
418 #ifdef BARO
419 return sensors(SENSOR_BARO);
420 #else
421 return false;
422 #endif
424 case FLIGHT_LOG_FIELD_CONDITION_VBAT:
425 return feature(FEATURE_VBAT);
427 case FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC:
428 return feature(FEATURE_CURRENT_METER) && masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC;
430 case FLIGHT_LOG_FIELD_CONDITION_SONAR:
431 #ifdef SONAR
432 return feature(FEATURE_SONAR);
433 #else
434 return false;
435 #endif
437 case FLIGHT_LOG_FIELD_CONDITION_RSSI:
438 return masterConfig.rxConfig.rssi_channel > 0 || feature(FEATURE_RSSI_ADC);
440 case FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME:
441 return masterConfig.blackbox_rate_num < masterConfig.blackbox_rate_denom;
443 case FLIGHT_LOG_FIELD_CONDITION_NEVER:
444 return false;
445 default:
446 return false;
450 static void blackboxBuildConditionCache()
452 FlightLogFieldCondition cond;
454 blackboxConditionCache = 0;
456 for (cond = FLIGHT_LOG_FIELD_CONDITION_FIRST; cond <= FLIGHT_LOG_FIELD_CONDITION_LAST; cond++) {
457 if (testBlackboxConditionUncached(cond)) {
458 blackboxConditionCache |= 1 << cond;
463 static bool testBlackboxCondition(FlightLogFieldCondition condition)
465 return (blackboxConditionCache & (1 << condition)) != 0;
468 static void blackboxSetState(BlackboxState newState)
470 //Perform initial setup required for the new state
471 switch (newState) {
472 case BLACKBOX_STATE_PREPARE_LOG_FILE:
473 blackboxLoggedAnyFrames = false;
474 break;
475 case BLACKBOX_STATE_SEND_HEADER:
476 blackboxHeaderBudget = 0;
477 xmitState.headerIndex = 0;
478 xmitState.u.startTime = millis();
479 break;
480 case BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER:
481 case BLACKBOX_STATE_SEND_GPS_G_HEADER:
482 case BLACKBOX_STATE_SEND_GPS_H_HEADER:
483 case BLACKBOX_STATE_SEND_SLOW_HEADER:
484 xmitState.headerIndex = 0;
485 xmitState.u.fieldIndex = -1;
486 break;
487 case BLACKBOX_STATE_SEND_SYSINFO:
488 xmitState.headerIndex = 0;
489 break;
490 case BLACKBOX_STATE_RUNNING:
491 blackboxSlowFrameIterationTimer = SLOW_FRAME_INTERVAL; //Force a slow frame to be written on the first iteration
492 break;
493 case BLACKBOX_STATE_SHUTTING_DOWN:
494 xmitState.u.startTime = millis();
495 break;
496 default:
499 blackboxState = newState;
502 static void writeIntraframe(void)
504 blackboxMainState_t *blackboxCurrent = blackboxHistory[0];
505 int x;
507 blackboxWrite('I');
509 blackboxWriteUnsignedVB(blackboxIteration);
510 blackboxWriteUnsignedVB(blackboxCurrent->time);
512 blackboxWriteSignedVBArray(blackboxCurrent->axisPID_P, XYZ_AXIS_COUNT);
513 blackboxWriteSignedVBArray(blackboxCurrent->axisPID_I, XYZ_AXIS_COUNT);
515 // Don't bother writing the current D term if the corresponding PID setting is zero
516 for (x = 0; x < XYZ_AXIS_COUNT; x++) {
517 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0 + x)) {
518 blackboxWriteSignedVB(blackboxCurrent->axisPID_D[x]);
522 // Write roll, pitch and yaw first:
523 blackboxWriteSigned16VBArray(blackboxCurrent->rcCommand, 3);
526 * Write the throttle separately from the rest of the RC data so we can apply a predictor to it.
527 * Throttle lies in range [minthrottle..maxthrottle]:
529 blackboxWriteUnsignedVB(blackboxCurrent->rcCommand[THROTTLE] - masterConfig.escAndServoConfig.minthrottle);
531 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) {
533 * Our voltage is expected to decrease over the course of the flight, so store our difference from
534 * the reference:
536 * Write 14 bits even if the number is negative (which would otherwise result in 32 bits)
538 blackboxWriteUnsignedVB((vbatReference - blackboxCurrent->vbatLatest) & 0x3FFF);
541 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC)) {
542 // 12bit value directly from ADC
543 blackboxWriteUnsignedVB(blackboxCurrent->amperageLatest);
546 #ifdef MAG
547 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_MAG)) {
548 blackboxWriteSigned16VBArray(blackboxCurrent->magADC, XYZ_AXIS_COUNT);
550 #endif
552 #ifdef BARO
553 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_BARO)) {
554 blackboxWriteSignedVB(blackboxCurrent->BaroAlt);
556 #endif
558 #ifdef SONAR
559 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_SONAR)) {
560 blackboxWriteSignedVB(blackboxCurrent->sonarRaw);
562 #endif
564 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_RSSI)) {
565 blackboxWriteUnsignedVB(blackboxCurrent->rssi);
568 blackboxWriteSigned16VBArray(blackboxCurrent->gyroADC, XYZ_AXIS_COUNT);
569 blackboxWriteSigned16VBArray(blackboxCurrent->accSmooth, XYZ_AXIS_COUNT);
570 blackboxWriteSigned16VBArray(blackboxCurrent->debug, 4);
572 //Motors can be below minthrottle when disarmed, but that doesn't happen much
573 blackboxWriteUnsignedVB(blackboxCurrent->motor[0] - masterConfig.escAndServoConfig.minthrottle);
575 //Motors tend to be similar to each other so use the first motor's value as a predictor of the others
576 for (x = 1; x < motorCount; x++) {
577 blackboxWriteSignedVB(blackboxCurrent->motor[x] - blackboxCurrent->motor[0]);
580 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_TRICOPTER)) {
581 //Assume the tail spends most of its time around the center
582 blackboxWriteSignedVB(blackboxCurrent->servo[5] - 1500);
585 //Rotate our history buffers:
587 //The current state becomes the new "before" state
588 blackboxHistory[1] = blackboxHistory[0];
589 //And since we have no other history, we also use it for the "before, before" state
590 blackboxHistory[2] = blackboxHistory[0];
591 //And advance the current state over to a blank space ready to be filled
592 blackboxHistory[0] = ((blackboxHistory[0] - blackboxHistoryRing + 1) % 3) + blackboxHistoryRing;
594 blackboxLoggedAnyFrames = true;
597 static void blackboxWriteMainStateArrayUsingAveragePredictor(int arrOffsetInHistory, int count)
599 int16_t *curr = (int16_t*) ((char*) (blackboxHistory[0]) + arrOffsetInHistory);
600 int16_t *prev1 = (int16_t*) ((char*) (blackboxHistory[1]) + arrOffsetInHistory);
601 int16_t *prev2 = (int16_t*) ((char*) (blackboxHistory[2]) + arrOffsetInHistory);
603 for (int i = 0; i < count; i++) {
604 // Predictor is the average of the previous two history states
605 int32_t predictor = (prev1[i] + prev2[i]) / 2;
607 blackboxWriteSignedVB(curr[i] - predictor);
611 static void writeInterframe(void)
613 int x;
614 int32_t deltas[8];
616 blackboxMainState_t *blackboxCurrent = blackboxHistory[0];
617 blackboxMainState_t *blackboxLast = blackboxHistory[1];
619 blackboxWrite('P');
621 //No need to store iteration count since its delta is always 1
624 * Since the difference between the difference between successive times will be nearly zero (due to consistent
625 * looptime spacing), use second-order differences.
627 blackboxWriteSignedVB((int32_t) (blackboxHistory[0]->time - 2 * blackboxHistory[1]->time + blackboxHistory[2]->time));
629 arraySubInt32(deltas, blackboxCurrent->axisPID_P, blackboxLast->axisPID_P, XYZ_AXIS_COUNT);
630 blackboxWriteSignedVBArray(deltas, XYZ_AXIS_COUNT);
633 * The PID I field changes very slowly, most of the time +-2, so use an encoding
634 * that can pack all three fields into one byte in that situation.
636 arraySubInt32(deltas, blackboxCurrent->axisPID_I, blackboxLast->axisPID_I, XYZ_AXIS_COUNT);
637 blackboxWriteTag2_3S32(deltas);
640 * The PID D term is frequently set to zero for yaw, which makes the result from the calculation
641 * always zero. So don't bother recording D results when PID D terms are zero.
643 for (x = 0; x < XYZ_AXIS_COUNT; x++) {
644 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0 + x)) {
645 blackboxWriteSignedVB(blackboxCurrent->axisPID_D[x] - blackboxLast->axisPID_D[x]);
650 * RC tends to stay the same or fairly small for many frames at a time, so use an encoding that
651 * can pack multiple values per byte:
653 for (x = 0; x < 4; x++) {
654 deltas[x] = blackboxCurrent->rcCommand[x] - blackboxLast->rcCommand[x];
657 blackboxWriteTag8_4S16(deltas);
659 //Check for sensors that are updated periodically (so deltas are normally zero)
660 int optionalFieldCount = 0;
662 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) {
663 deltas[optionalFieldCount++] = (int32_t) blackboxCurrent->vbatLatest - blackboxLast->vbatLatest;
666 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC)) {
667 deltas[optionalFieldCount++] = (int32_t) blackboxCurrent->amperageLatest - blackboxLast->amperageLatest;
670 #ifdef MAG
671 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_MAG)) {
672 for (x = 0; x < XYZ_AXIS_COUNT; x++) {
673 deltas[optionalFieldCount++] = blackboxCurrent->magADC[x] - blackboxLast->magADC[x];
676 #endif
678 #ifdef BARO
679 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_BARO)) {
680 deltas[optionalFieldCount++] = blackboxCurrent->BaroAlt - blackboxLast->BaroAlt;
682 #endif
684 #ifdef SONAR
685 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_SONAR)) {
686 deltas[optionalFieldCount++] = blackboxCurrent->sonarRaw - blackboxLast->sonarRaw;
688 #endif
690 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_RSSI)) {
691 deltas[optionalFieldCount++] = (int32_t) blackboxCurrent->rssi - blackboxLast->rssi;
694 blackboxWriteTag8_8SVB(deltas, optionalFieldCount);
696 //Since gyros, accs and motors are noisy, base their predictions on the average of the history:
697 blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, gyroADC), XYZ_AXIS_COUNT);
698 blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, accSmooth), XYZ_AXIS_COUNT);
699 blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, debug), 4);
700 blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, motor), motorCount);
702 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_TRICOPTER)) {
703 blackboxWriteSignedVB(blackboxCurrent->servo[5] - blackboxLast->servo[5]);
706 //Rotate our history buffers
707 blackboxHistory[2] = blackboxHistory[1];
708 blackboxHistory[1] = blackboxHistory[0];
709 blackboxHistory[0] = ((blackboxHistory[0] - blackboxHistoryRing + 1) % 3) + blackboxHistoryRing;
711 blackboxLoggedAnyFrames = true;
714 /* Write the contents of the global "slowHistory" to the log as an "S" frame. Because this data is logged so
715 * infrequently, delta updates are not reasonable, so we log independent frames. */
716 static void writeSlowFrame(void)
718 int32_t values[3];
720 blackboxWrite('S');
722 blackboxWriteUnsignedVB(slowHistory.flightModeFlags);
723 blackboxWriteUnsignedVB(slowHistory.stateFlags);
726 * Most of the time these three values will be able to pack into one byte for us:
728 values[0] = slowHistory.failsafePhase;
729 values[1] = slowHistory.rxSignalReceived ? 1 : 0;
730 values[2] = slowHistory.rxFlightChannelsValid ? 1 : 0;
731 blackboxWriteTag2_3S32(values);
733 blackboxSlowFrameIterationTimer = 0;
737 * Load rarely-changing values from the FC into the given structure
739 static void loadSlowState(blackboxSlowState_t *slow)
741 slow->flightModeFlags = flightModeFlags;
742 slow->stateFlags = stateFlags;
743 slow->failsafePhase = failsafePhase();
744 slow->rxSignalReceived = rxIsReceivingSignal();
745 slow->rxFlightChannelsValid = rxAreFlightChannelsValid();
749 * If the data in the slow frame has changed, log a slow frame.
751 * If allowPeriodicWrite is true, the frame is also logged if it has been more than SLOW_FRAME_INTERVAL logging iterations
752 * since the field was last logged.
754 static void writeSlowFrameIfNeeded(bool allowPeriodicWrite)
756 // Write the slow frame peridocially so it can be recovered if we ever lose sync
757 bool shouldWrite = allowPeriodicWrite && blackboxSlowFrameIterationTimer >= SLOW_FRAME_INTERVAL;
759 if (shouldWrite) {
760 loadSlowState(&slowHistory);
761 } else {
762 blackboxSlowState_t newSlowState;
764 loadSlowState(&newSlowState);
766 // Only write a slow frame if it was different from the previous state
767 if (memcmp(&newSlowState, &slowHistory, sizeof(slowHistory)) != 0) {
768 // Use the new state as our new history
769 memcpy(&slowHistory, &newSlowState, sizeof(slowHistory));
770 shouldWrite = true;
774 if (shouldWrite) {
775 writeSlowFrame();
779 static int gcd(int num, int denom)
781 if (denom == 0) {
782 return num;
785 return gcd(denom, num % denom);
788 static void validateBlackboxConfig()
790 int div;
792 if (masterConfig.blackbox_rate_num == 0 || masterConfig.blackbox_rate_denom == 0
793 || masterConfig.blackbox_rate_num >= masterConfig.blackbox_rate_denom) {
794 masterConfig.blackbox_rate_num = 1;
795 masterConfig.blackbox_rate_denom = 1;
796 } else {
797 /* Reduce the fraction the user entered as much as possible (makes the recorded/skipped frame pattern repeat
798 * itself more frequently)
800 div = gcd(masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
802 masterConfig.blackbox_rate_num /= div;
803 masterConfig.blackbox_rate_denom /= div;
806 // If we've chosen an unsupported device, change the device to serial
807 switch (masterConfig.blackbox_device) {
808 #ifdef USE_FLASHFS
809 case BLACKBOX_DEVICE_FLASH:
810 #endif
811 #ifdef USE_SDCARD
812 case BLACKBOX_DEVICE_SDCARD:
813 #endif
814 case BLACKBOX_DEVICE_SERIAL:
815 // Device supported, leave the setting alone
816 break;
818 default:
819 masterConfig.blackbox_device = BLACKBOX_DEVICE_SERIAL;
824 * Start Blackbox logging if it is not already running. Intended to be called upon arming.
826 void startBlackbox(void)
828 if (blackboxState == BLACKBOX_STATE_STOPPED) {
829 validateBlackboxConfig();
831 if (!blackboxDeviceOpen()) {
832 blackboxSetState(BLACKBOX_STATE_DISABLED);
833 return;
836 memset(&gpsHistory, 0, sizeof(gpsHistory));
838 blackboxHistory[0] = &blackboxHistoryRing[0];
839 blackboxHistory[1] = &blackboxHistoryRing[1];
840 blackboxHistory[2] = &blackboxHistoryRing[2];
842 vbatReference = vbatLatestADC;
844 //No need to clear the content of blackboxHistoryRing since our first frame will be an intra which overwrites it
847 * We use conditional tests to decide whether or not certain fields should be logged. Since our headers
848 * must always agree with the logged data, the results of these tests must not change during logging. So
849 * cache those now.
851 blackboxBuildConditionCache();
853 blackboxModeActivationConditionPresent = isModeActivationConditionPresent(currentProfile->modeActivationConditions, BOXBLACKBOX);
855 blackboxIteration = 0;
856 blackboxPFrameIndex = 0;
857 blackboxIFrameIndex = 0;
860 * Record the beeper's current idea of the last arming beep time, so that we can detect it changing when
861 * it finally plays the beep for this arming event.
863 blackboxLastArmingBeep = getArmingBeepTimeMicros();
865 blackboxSetState(BLACKBOX_STATE_PREPARE_LOG_FILE);
870 * Begin Blackbox shutdown.
872 void finishBlackbox(void)
874 switch (blackboxState) {
875 case BLACKBOX_STATE_DISABLED:
876 case BLACKBOX_STATE_STOPPED:
877 case BLACKBOX_STATE_SHUTTING_DOWN:
878 // We're already stopped/shutting down
879 break;
881 case BLACKBOX_STATE_RUNNING:
882 case BLACKBOX_STATE_PAUSED:
883 blackboxLogEvent(FLIGHT_LOG_EVENT_LOG_END, NULL);
885 // Fall through
886 default:
887 blackboxSetState(BLACKBOX_STATE_SHUTTING_DOWN);
891 #ifdef GPS
892 static void writeGPSHomeFrame()
894 blackboxWrite('H');
896 blackboxWriteSignedVB(GPS_home[0]);
897 blackboxWriteSignedVB(GPS_home[1]);
898 //TODO it'd be great if we could grab the GPS current time and write that too
900 gpsHistory.GPS_home[0] = GPS_home[0];
901 gpsHistory.GPS_home[1] = GPS_home[1];
904 static void writeGPSFrame()
906 blackboxWrite('G');
909 * If we're logging every frame, then a GPS frame always appears just after a frame with the
910 * currentTime timestamp in the log, so the reader can just use that timestamp for the GPS frame.
912 * If we're not logging every frame, we need to store the time of this GPS frame.
914 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME)) {
915 // Predict the time of the last frame in the main log
916 blackboxWriteUnsignedVB(currentTime - blackboxHistory[1]->time);
919 blackboxWriteUnsignedVB(GPS_numSat);
920 blackboxWriteSignedVB(GPS_coord[0] - gpsHistory.GPS_home[0]);
921 blackboxWriteSignedVB(GPS_coord[1] - gpsHistory.GPS_home[1]);
922 blackboxWriteUnsignedVB(GPS_altitude);
923 blackboxWriteUnsignedVB(GPS_speed);
924 blackboxWriteUnsignedVB(GPS_ground_course);
926 gpsHistory.GPS_numSat = GPS_numSat;
927 gpsHistory.GPS_coord[0] = GPS_coord[0];
928 gpsHistory.GPS_coord[1] = GPS_coord[1];
930 #endif
933 * Fill the current state of the blackbox using values read from the flight controller
935 static void loadMainState(void)
937 blackboxMainState_t *blackboxCurrent = blackboxHistory[0];
938 int i;
940 blackboxCurrent->time = currentTime;
942 for (i = 0; i < XYZ_AXIS_COUNT; i++) {
943 blackboxCurrent->axisPID_P[i] = axisPID_P[i];
945 for (i = 0; i < XYZ_AXIS_COUNT; i++) {
946 blackboxCurrent->axisPID_I[i] = axisPID_I[i];
948 for (i = 0; i < XYZ_AXIS_COUNT; i++) {
949 blackboxCurrent->axisPID_D[i] = axisPID_D[i];
952 for (i = 0; i < 4; i++) {
953 blackboxCurrent->rcCommand[i] = rcCommand[i];
956 for (i = 0; i < XYZ_AXIS_COUNT; i++) {
957 blackboxCurrent->gyroADC[i] = gyroADC[i];
960 for (i = 0; i < XYZ_AXIS_COUNT; i++) {
961 blackboxCurrent->accSmooth[i] = accSmooth[i];
964 for (i = 0; i < 4; i++) {
965 blackboxCurrent->debug[i] = debug[i];
968 for (i = 0; i < motorCount; i++) {
969 blackboxCurrent->motor[i] = motor[i];
972 blackboxCurrent->vbatLatest = vbatLatestADC;
973 blackboxCurrent->amperageLatest = amperageLatestADC;
975 #ifdef MAG
976 for (i = 0; i < XYZ_AXIS_COUNT; i++) {
977 blackboxCurrent->magADC[i] = magADC[i];
979 #endif
981 #ifdef BARO
982 blackboxCurrent->BaroAlt = BaroAlt;
983 #endif
985 #ifdef SONAR
986 // Store the raw sonar value without applying tilt correction
987 blackboxCurrent->sonarRaw = sonarRead();
988 #endif
990 blackboxCurrent->rssi = rssi;
992 #ifdef USE_SERVOS
993 //Tail servo for tricopters
994 blackboxCurrent->servo[5] = servo[5];
995 #endif
999 * Transmit the header information for the given field definitions. Transmitted header lines look like:
1001 * H Field I name:a,b,c
1002 * H Field I predictor:0,1,2
1004 * For all header types, provide a "mainFrameChar" which is the name for the field and will be used to refer to it in the
1005 * header (e.g. P, I etc). For blackboxDeltaField_t fields, also provide deltaFrameChar, otherwise set this to zero.
1007 * Provide an array 'conditions' of FlightLogFieldCondition enums if you want these conditions to decide whether a field
1008 * should be included or not. Otherwise provide NULL for this parameter and NULL for secondCondition.
1010 * Set xmitState.headerIndex to 0 and xmitState.u.fieldIndex to -1 before calling for the first time.
1012 * secondFieldDefinition and secondCondition element pointers need to be provided in order to compute the stride of the
1013 * fieldDefinition and secondCondition arrays.
1015 * Returns true if there is still header left to transmit (so call again to continue transmission).
1017 static bool sendFieldDefinition(char mainFrameChar, char deltaFrameChar, const void *fieldDefinitions,
1018 const void *secondFieldDefinition, int fieldCount, const uint8_t *conditions, const uint8_t *secondCondition)
1020 const blackboxFieldDefinition_t *def;
1021 unsigned int headerCount;
1022 static bool needComma = false;
1023 size_t definitionStride = (char*) secondFieldDefinition - (char*) fieldDefinitions;
1024 size_t conditionsStride = (char*) secondCondition - (char*) conditions;
1026 if (deltaFrameChar) {
1027 headerCount = BLACKBOX_DELTA_FIELD_HEADER_COUNT;
1028 } else {
1029 headerCount = BLACKBOX_SIMPLE_FIELD_HEADER_COUNT;
1033 * We're chunking up the header data so we don't exceed our datarate. So we'll be called multiple times to transmit
1034 * the whole header.
1037 // On our first call we need to print the name of the header and a colon
1038 if (xmitState.u.fieldIndex == -1) {
1039 if (xmitState.headerIndex >= headerCount) {
1040 return false; //Someone probably called us again after we had already completed transmission
1043 uint32_t charsToBeWritten = strlen("H Field x :") + strlen(blackboxFieldHeaderNames[xmitState.headerIndex]);
1045 if (blackboxDeviceReserveBufferSpace(charsToBeWritten) != BLACKBOX_RESERVE_SUCCESS) {
1046 return true; // Try again later
1049 blackboxHeaderBudget -= blackboxPrintf("H Field %c %s:", xmitState.headerIndex >= BLACKBOX_SIMPLE_FIELD_HEADER_COUNT ? deltaFrameChar : mainFrameChar, blackboxFieldHeaderNames[xmitState.headerIndex]);
1051 xmitState.u.fieldIndex++;
1052 needComma = false;
1055 // The longest we expect an integer to be as a string:
1056 const uint32_t LONGEST_INTEGER_STRLEN = 2;
1058 for (; xmitState.u.fieldIndex < fieldCount; xmitState.u.fieldIndex++) {
1059 def = (const blackboxFieldDefinition_t*) ((const char*)fieldDefinitions + definitionStride * xmitState.u.fieldIndex);
1061 if (!conditions || testBlackboxCondition(conditions[conditionsStride * xmitState.u.fieldIndex])) {
1062 // First (over)estimate the length of the string we want to print
1064 int32_t bytesToWrite = 1; // Leading comma
1066 // The first header is a field name
1067 if (xmitState.headerIndex == 0) {
1068 bytesToWrite += strlen(def->name) + strlen("[]") + LONGEST_INTEGER_STRLEN;
1069 } else {
1070 //The other headers are integers
1071 bytesToWrite += LONGEST_INTEGER_STRLEN;
1074 // Now perform the write if the buffer is large enough
1075 if (blackboxDeviceReserveBufferSpace(bytesToWrite) != BLACKBOX_RESERVE_SUCCESS) {
1076 // Ran out of space!
1077 return true;
1080 blackboxHeaderBudget -= bytesToWrite;
1082 if (needComma) {
1083 blackboxWrite(',');
1084 } else {
1085 needComma = true;
1088 // The first header is a field name
1089 if (xmitState.headerIndex == 0) {
1090 blackboxPrint(def->name);
1092 // Do we need to print an index in brackets after the name?
1093 if (def->fieldNameIndex != -1) {
1094 blackboxPrintf("[%d]", def->fieldNameIndex);
1096 } else {
1097 //The other headers are integers
1098 blackboxPrintf("%d", def->arr[xmitState.headerIndex - 1]);
1103 // Did we complete this line?
1104 if (xmitState.u.fieldIndex == fieldCount && blackboxDeviceReserveBufferSpace(1) == BLACKBOX_RESERVE_SUCCESS) {
1105 blackboxHeaderBudget--;
1106 blackboxWrite('\n');
1107 xmitState.headerIndex++;
1108 xmitState.u.fieldIndex = -1;
1111 return xmitState.headerIndex < headerCount;
1115 * Transmit a portion of the system information headers. Call the first time with xmitState.headerIndex == 0. Returns
1116 * true iff transmission is complete, otherwise call again later to continue transmission.
1118 static bool blackboxWriteSysinfo()
1120 // Make sure we have enough room in the buffer for our longest line (as of this writing, the "Firmware date" line)
1121 if (blackboxDeviceReserveBufferSpace(64) != BLACKBOX_RESERVE_SUCCESS) {
1122 return false;
1125 switch (xmitState.headerIndex) {
1126 case 0:
1127 blackboxPrintfHeaderLine("Firmware type:Cleanflight");
1128 break;
1129 case 1:
1130 blackboxPrintfHeaderLine("Firmware revision:%s", shortGitRevision);
1131 break;
1132 case 2:
1133 blackboxPrintfHeaderLine("Firmware date:%s %s", buildDate, buildTime);
1134 break;
1135 case 3:
1136 blackboxPrintfHeaderLine("P interval:%d/%d", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
1137 break;
1138 case 4:
1139 blackboxPrintfHeaderLine("rcRate:%d", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8);
1140 break;
1141 case 5:
1142 blackboxPrintfHeaderLine("minthrottle:%d", masterConfig.escAndServoConfig.minthrottle);
1143 break;
1144 case 6:
1145 blackboxPrintfHeaderLine("maxthrottle:%d", masterConfig.escAndServoConfig.maxthrottle);
1146 break;
1147 case 7:
1148 blackboxPrintfHeaderLine("gyro.scale:0x%x", castFloatBytesToInt(gyro.scale));
1149 break;
1150 case 8:
1151 blackboxPrintfHeaderLine("acc_1G:%u", acc_1G);
1152 break;
1153 case 9:
1154 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) {
1155 blackboxPrintfHeaderLine("vbatscale:%u", masterConfig.batteryConfig.vbatscale);
1156 } else {
1157 xmitState.headerIndex += 2; // Skip the next two vbat fields too
1159 break;
1160 case 10:
1161 blackboxPrintfHeaderLine("vbatcellvoltage:%u,%u,%u", masterConfig.batteryConfig.vbatmincellvoltage,
1162 masterConfig.batteryConfig.vbatwarningcellvoltage, masterConfig.batteryConfig.vbatmaxcellvoltage);
1163 break;
1164 case 11:
1165 blackboxPrintfHeaderLine("vbatref:%u", vbatReference);
1166 break;
1167 case 12:
1168 //Note: Log even if this is a virtual current meter, since the virtual meter uses these parameters too:
1169 if (feature(FEATURE_CURRENT_METER)) {
1170 blackboxPrintfHeaderLine("currentMeter:%d,%d", masterConfig.batteryConfig.currentMeterOffset, masterConfig.batteryConfig.currentMeterScale);
1172 break;
1173 default:
1174 return true;
1177 xmitState.headerIndex++;
1178 return false;
1182 * Write the given event to the log immediately
1184 void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data)
1186 // Only allow events to be logged after headers have been written
1187 if (!(blackboxState == BLACKBOX_STATE_RUNNING || blackboxState == BLACKBOX_STATE_PAUSED)) {
1188 return;
1191 //Shared header for event frames
1192 blackboxWrite('E');
1193 blackboxWrite(event);
1195 //Now serialize the data for this specific frame type
1196 switch (event) {
1197 case FLIGHT_LOG_EVENT_SYNC_BEEP:
1198 blackboxWriteUnsignedVB(data->syncBeep.time);
1199 break;
1200 case FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT:
1201 if (data->inflightAdjustment.floatFlag) {
1202 blackboxWrite(data->inflightAdjustment.adjustmentFunction + FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT_FUNCTION_FLOAT_VALUE_FLAG);
1203 blackboxWriteFloat(data->inflightAdjustment.newFloatValue);
1204 } else {
1205 blackboxWrite(data->inflightAdjustment.adjustmentFunction);
1206 blackboxWriteSignedVB(data->inflightAdjustment.newValue);
1208 break;
1209 case FLIGHT_LOG_EVENT_GTUNE_RESULT:
1210 blackboxWrite(data->gtuneCycleResult.gtuneAxis);
1211 blackboxWriteSignedVB(data->gtuneCycleResult.gtuneGyroAVG);
1212 blackboxWriteS16(data->gtuneCycleResult.gtuneNewP);
1213 break;
1214 case FLIGHT_LOG_EVENT_LOGGING_RESUME:
1215 blackboxWriteUnsignedVB(data->loggingResume.logIteration);
1216 blackboxWriteUnsignedVB(data->loggingResume.currentTime);
1217 break;
1218 case FLIGHT_LOG_EVENT_LOG_END:
1219 blackboxPrint("End of log");
1220 blackboxWrite(0);
1221 break;
1225 /* If an arming beep has played since it was last logged, write the time of the arming beep to the log as a synchronization point */
1226 static void blackboxCheckAndLogArmingBeep()
1228 flightLogEvent_syncBeep_t eventData;
1230 // Use != so that we can still detect a change if the counter wraps
1231 if (getArmingBeepTimeMicros() != blackboxLastArmingBeep) {
1232 blackboxLastArmingBeep = getArmingBeepTimeMicros();
1234 eventData.time = blackboxLastArmingBeep;
1236 blackboxLogEvent(FLIGHT_LOG_EVENT_SYNC_BEEP, (flightLogEventData_t *) &eventData);
1241 * Use the user's num/denom settings to decide if the P-frame of the given index should be logged, allowing the user to control
1242 * the portion of logged loop iterations.
1244 static bool blackboxShouldLogPFrame(uint32_t pFrameIndex)
1246 /* Adding a magic shift of "masterConfig.blackbox_rate_num - 1" in here creates a better spread of
1247 * recorded / skipped frames when the I frame's position is considered:
1249 return (pFrameIndex + masterConfig.blackbox_rate_num - 1) % masterConfig.blackbox_rate_denom < masterConfig.blackbox_rate_num;
1252 static bool blackboxShouldLogIFrame() {
1253 return blackboxPFrameIndex == 0;
1256 // Called once every FC loop in order to keep track of how many FC loop iterations have passed
1257 static void blackboxAdvanceIterationTimers()
1259 blackboxSlowFrameIterationTimer++;
1260 blackboxIteration++;
1261 blackboxPFrameIndex++;
1263 if (blackboxPFrameIndex == BLACKBOX_I_INTERVAL) {
1264 blackboxPFrameIndex = 0;
1265 blackboxIFrameIndex++;
1269 // Called once every FC loop in order to log the current state
1270 static void blackboxLogIteration()
1272 // Write a keyframe every BLACKBOX_I_INTERVAL frames so we can resynchronise upon missing frames
1273 if (blackboxShouldLogIFrame()) {
1275 * Don't log a slow frame if the slow data didn't change ("I" frames are already large enough without adding
1276 * an additional item to write at the same time). Unless we're *only* logging "I" frames, then we have no choice.
1278 writeSlowFrameIfNeeded(blackboxIsOnlyLoggingIntraframes());
1280 loadMainState();
1281 writeIntraframe();
1282 } else {
1283 blackboxCheckAndLogArmingBeep();
1285 if (blackboxShouldLogPFrame(blackboxPFrameIndex)) {
1287 * We assume that slow frames are only interesting in that they aid the interpretation of the main data stream.
1288 * So only log slow frames during loop iterations where we log a main frame.
1290 writeSlowFrameIfNeeded(true);
1292 loadMainState();
1293 writeInterframe();
1295 #ifdef GPS
1296 if (feature(FEATURE_GPS)) {
1298 * If the GPS home point has been updated, or every 128 intraframes (~10 seconds), write the
1299 * GPS home position.
1301 * We write it periodically so that if one Home Frame goes missing, the GPS coordinates can
1302 * still be interpreted correctly.
1304 if (GPS_home[0] != gpsHistory.GPS_home[0] || GPS_home[1] != gpsHistory.GPS_home[1]
1305 || (blackboxPFrameIndex == BLACKBOX_I_INTERVAL / 2 && blackboxIFrameIndex % 128 == 0)) {
1307 writeGPSHomeFrame();
1308 writeGPSFrame();
1309 } else if (GPS_numSat != gpsHistory.GPS_numSat || GPS_coord[0] != gpsHistory.GPS_coord[0]
1310 || GPS_coord[1] != gpsHistory.GPS_coord[1]) {
1311 //We could check for velocity changes as well but I doubt it changes independent of position
1312 writeGPSFrame();
1315 #endif
1318 //Flush every iteration so that our runtime variance is minimized
1319 blackboxDeviceFlush();
1323 * Call each flight loop iteration to perform blackbox logging.
1325 void handleBlackbox(void)
1327 int i;
1329 if (blackboxState >= BLACKBOX_FIRST_HEADER_SENDING_STATE && blackboxState <= BLACKBOX_LAST_HEADER_SENDING_STATE) {
1330 blackboxReplenishHeaderBudget();
1333 switch (blackboxState) {
1334 case BLACKBOX_STATE_PREPARE_LOG_FILE:
1335 if (blackboxDeviceBeginLog()) {
1336 blackboxSetState(BLACKBOX_STATE_SEND_HEADER);
1338 break;
1339 case BLACKBOX_STATE_SEND_HEADER:
1340 //On entry of this state, xmitState.headerIndex is 0 and startTime is intialised
1343 * Once the UART has had time to init, transmit the header in chunks so we don't overflow its transmit
1344 * buffer, overflow the OpenLog's buffer, or keep the main loop busy for too long.
1346 if (millis() > xmitState.u.startTime + 100) {
1347 if (blackboxDeviceReserveBufferSpace(BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION) == BLACKBOX_RESERVE_SUCCESS) {
1348 for (i = 0; i < BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION && blackboxHeader[xmitState.headerIndex] != '\0'; i++, xmitState.headerIndex++) {
1349 blackboxWrite(blackboxHeader[xmitState.headerIndex]);
1350 blackboxHeaderBudget--;
1353 if (blackboxHeader[xmitState.headerIndex] == '\0') {
1354 blackboxSetState(BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER);
1358 break;
1359 case BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER:
1360 //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
1361 if (!sendFieldDefinition('I', 'P', blackboxMainFields, blackboxMainFields + 1, ARRAY_LENGTH(blackboxMainFields),
1362 &blackboxMainFields[0].condition, &blackboxMainFields[1].condition)) {
1363 #ifdef GPS
1364 if (feature(FEATURE_GPS)) {
1365 blackboxSetState(BLACKBOX_STATE_SEND_GPS_H_HEADER);
1366 } else
1367 #endif
1368 blackboxSetState(BLACKBOX_STATE_SEND_SLOW_HEADER);
1370 break;
1371 #ifdef GPS
1372 case BLACKBOX_STATE_SEND_GPS_H_HEADER:
1373 //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
1374 if (!sendFieldDefinition('H', 0, blackboxGpsHFields, blackboxGpsHFields + 1, ARRAY_LENGTH(blackboxGpsHFields),
1375 NULL, NULL)) {
1376 blackboxSetState(BLACKBOX_STATE_SEND_GPS_G_HEADER);
1378 break;
1379 case BLACKBOX_STATE_SEND_GPS_G_HEADER:
1380 //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
1381 if (!sendFieldDefinition('G', 0, blackboxGpsGFields, blackboxGpsGFields + 1, ARRAY_LENGTH(blackboxGpsGFields),
1382 &blackboxGpsGFields[0].condition, &blackboxGpsGFields[1].condition)) {
1383 blackboxSetState(BLACKBOX_STATE_SEND_SLOW_HEADER);
1385 break;
1386 #endif
1387 case BLACKBOX_STATE_SEND_SLOW_HEADER:
1388 //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
1389 if (!sendFieldDefinition('S', 0, blackboxSlowFields, blackboxSlowFields + 1, ARRAY_LENGTH(blackboxSlowFields),
1390 NULL, NULL)) {
1391 blackboxSetState(BLACKBOX_STATE_SEND_SYSINFO);
1393 break;
1394 case BLACKBOX_STATE_SEND_SYSINFO:
1395 //On entry of this state, xmitState.headerIndex is 0
1397 //Keep writing chunks of the system info headers until it returns true to signal completion
1398 if (blackboxWriteSysinfo()) {
1401 * Wait for header buffers to drain completely before data logging begins to ensure reliable header delivery
1402 * (overflowing circular buffers causes all data to be discarded, so the first few logged iterations
1403 * could wipe out the end of the header if we weren't careful)
1405 if (blackboxDeviceFlushForce()) {
1406 blackboxSetState(BLACKBOX_STATE_RUNNING);
1409 break;
1410 case BLACKBOX_STATE_PAUSED:
1411 // Only allow resume to occur during an I-frame iteration, so that we have an "I" base to work from
1412 if (IS_RC_MODE_ACTIVE(BOXBLACKBOX) && blackboxShouldLogIFrame()) {
1413 // Write a log entry so the decoder is aware that our large time/iteration skip is intended
1414 flightLogEvent_loggingResume_t resume;
1416 resume.logIteration = blackboxIteration;
1417 resume.currentTime = currentTime;
1419 blackboxLogEvent(FLIGHT_LOG_EVENT_LOGGING_RESUME, (flightLogEventData_t *) &resume);
1420 blackboxSetState(BLACKBOX_STATE_RUNNING);
1422 blackboxLogIteration();
1425 // Keep the logging timers ticking so our log iteration continues to advance
1426 blackboxAdvanceIterationTimers();
1427 break;
1428 case BLACKBOX_STATE_RUNNING:
1429 // On entry to this state, blackboxIteration, blackboxPFrameIndex and blackboxIFrameIndex are reset to 0
1430 if (blackboxModeActivationConditionPresent && !IS_RC_MODE_ACTIVE(BOXBLACKBOX)) {
1431 blackboxSetState(BLACKBOX_STATE_PAUSED);
1432 } else {
1433 blackboxLogIteration();
1436 blackboxAdvanceIterationTimers();
1437 break;
1438 case BLACKBOX_STATE_SHUTTING_DOWN:
1439 //On entry of this state, startTime is set
1442 * Wait for the log we've transmitted to make its way to the logger before we release the serial port,
1443 * since releasing the port clears the Tx buffer.
1445 * Don't wait longer than it could possibly take if something funky happens.
1447 if (blackboxDeviceEndLog(blackboxLoggedAnyFrames) && (millis() > xmitState.u.startTime + BLACKBOX_SHUTDOWN_TIMEOUT_MILLIS || blackboxDeviceFlushForce())) {
1448 blackboxDeviceClose();
1449 blackboxSetState(BLACKBOX_STATE_STOPPED);
1451 break;
1452 default:
1453 break;
1456 // Did we run out of room on the device? Stop!
1457 if (isBlackboxDeviceFull()) {
1458 blackboxSetState(BLACKBOX_STATE_STOPPED);
1462 static bool canUseBlackboxWithCurrentConfiguration(void)
1464 return feature(FEATURE_BLACKBOX);
1468 * Call during system startup to initialize the blackbox.
1470 void initBlackbox(void)
1472 if (canUseBlackboxWithCurrentConfiguration()) {
1473 blackboxSetState(BLACKBOX_STATE_STOPPED);
1474 } else {
1475 blackboxSetState(BLACKBOX_STATE_DISABLED);
1479 #endif