If RSSI Channel is set to Disabled when using S.Bus then generate RSS… (#5090)
[betaflight.git] / src / main / blackbox / blackbox.c
blob2fb23d149908a7b22e557b2b1c7dd1ab82d7541e
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 <stdint.h>
20 #include <string.h>
21 #include <math.h>
23 #include "platform.h"
25 #ifdef USE_BLACKBOX
27 #include "blackbox.h"
28 #include "blackbox_encoding.h"
29 #include "blackbox_fielddefs.h"
30 #include "blackbox_io.h"
32 #include "build/build_config.h"
33 #include "build/debug.h"
34 #include "build/version.h"
36 #include "common/axis.h"
37 #include "common/encoding.h"
38 #include "common/maths.h"
39 #include "common/time.h"
40 #include "common/utils.h"
42 #include "config/feature.h"
43 #include "pg/pg.h"
44 #include "pg/pg_ids.h"
46 #include "drivers/compass/compass.h"
47 #include "drivers/sensor.h"
48 #include "drivers/time.h"
50 #include "fc/config.h"
51 #include "fc/controlrate_profile.h"
52 #include "fc/rc_controls.h"
53 #include "fc/rc_modes.h"
54 #include "fc/runtime_config.h"
56 #include "flight/failsafe.h"
57 #include "flight/mixer.h"
58 #include "flight/pid.h"
59 #include "flight/servos.h"
61 #include "io/beeper.h"
62 #include "io/gps.h"
63 #include "io/serial.h"
65 #include "rx/rx.h"
67 #include "sensors/acceleration.h"
68 #include "sensors/barometer.h"
69 #include "sensors/battery.h"
70 #include "sensors/compass.h"
71 #include "sensors/gyro.h"
72 #include "sensors/rangefinder.h"
74 #if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
75 #define DEFAULT_BLACKBOX_DEVICE BLACKBOX_DEVICE_FLASH
76 #elif defined(ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT)
77 #define DEFAULT_BLACKBOX_DEVICE BLACKBOX_DEVICE_SDCARD
78 #else
79 #define DEFAULT_BLACKBOX_DEVICE BLACKBOX_DEVICE_SERIAL
80 #endif
82 PG_REGISTER_WITH_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 1);
84 PG_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig,
85 .p_denom = 32,
86 .device = DEFAULT_BLACKBOX_DEVICE,
87 .record_acc = 1,
88 .mode = BLACKBOX_MODE_NORMAL
91 #define BLACKBOX_SHUTDOWN_TIMEOUT_MILLIS 200
93 // Some macros to make writing FLIGHT_LOG_FIELD_* constants shorter:
95 #define PREDICT(x) CONCAT(FLIGHT_LOG_FIELD_PREDICTOR_, x)
96 #define ENCODING(x) CONCAT(FLIGHT_LOG_FIELD_ENCODING_, x)
97 #define CONDITION(x) CONCAT(FLIGHT_LOG_FIELD_CONDITION_, x)
98 #define UNSIGNED FLIGHT_LOG_FIELD_UNSIGNED
99 #define SIGNED FLIGHT_LOG_FIELD_SIGNED
101 static const char blackboxHeader[] =
102 "H Product:Blackbox flight data recorder by Nicholas Sherlock\n"
103 "H Data version:2\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 ARRAYLEN(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 USE_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 USE_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 USE_RANGEFINDER
199 {"surfaceRaw", -1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(PREVIOUS), .Pencode = ENCODING(TAG8_8SVB), FLIGHT_LOG_FIELD_CONDITION_RANGEFINDER},
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), FLIGHT_LOG_FIELD_CONDITION_ACC},
208 {"accSmooth", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_ACC},
209 {"accSmooth", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_ACC},
210 {"debug", 0, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_DEBUG},
211 {"debug", 1, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_DEBUG},
212 {"debug", 2, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_DEBUG},
213 {"debug", 3, SIGNED, .Ipredict = PREDICT(0), .Iencode = ENCODING(SIGNED_VB), .Ppredict = PREDICT(AVERAGE_2), .Pencode = ENCODING(SIGNED_VB), FLIGHT_LOG_FIELD_CONDITION_DEBUG},
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(MINMOTOR), .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 USE_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 BLACKBOX_STATE_START_ERASE,
272 BLACKBOX_STATE_ERASING,
273 BLACKBOX_STATE_ERASED
274 } BlackboxState;
277 typedef struct blackboxMainState_s {
278 uint32_t time;
280 int32_t axisPID_P[XYZ_AXIS_COUNT];
281 int32_t axisPID_I[XYZ_AXIS_COUNT];
282 int32_t axisPID_D[XYZ_AXIS_COUNT];
284 int16_t rcCommand[4];
285 int16_t gyroADC[XYZ_AXIS_COUNT];
286 int16_t accADC[XYZ_AXIS_COUNT];
287 int16_t debug[DEBUG16_VALUE_COUNT];
288 int16_t motor[MAX_SUPPORTED_MOTORS];
289 int16_t servo[MAX_SUPPORTED_SERVOS];
291 uint16_t vbatLatest;
292 uint16_t amperageLatest;
294 #ifdef USE_BARO
295 int32_t BaroAlt;
296 #endif
297 #ifdef USE_MAG
298 int16_t magADC[XYZ_AXIS_COUNT];
299 #endif
300 #ifdef USE_RANGEFINDER
301 int32_t surfaceRaw;
302 #endif
303 uint16_t rssi;
304 } blackboxMainState_t;
306 typedef struct blackboxGpsState_s {
307 int32_t GPS_home[2];
308 int32_t GPS_coord[2];
309 uint8_t GPS_numSat;
310 } blackboxGpsState_t;
312 // This data is updated really infrequently:
313 typedef struct blackboxSlowState_s {
314 uint32_t flightModeFlags; // extend this data size (from uint16_t)
315 uint8_t stateFlags;
316 uint8_t failsafePhase;
317 bool rxSignalReceived;
318 bool rxFlightChannelsValid;
319 } __attribute__((__packed__)) blackboxSlowState_t; // We pack this struct so that padding doesn't interfere with memcmp()
321 //From rc_controls.c
322 extern boxBitmask_t rcModeActivationMask;
324 static BlackboxState blackboxState = BLACKBOX_STATE_DISABLED;
326 static uint32_t blackboxLastArmingBeep = 0;
327 static uint32_t blackboxLastFlightModeFlags = 0; // New event tracking of flight modes
329 static struct {
330 uint32_t headerIndex;
332 /* Since these fields are used during different blackbox states (never simultaneously) we can
333 * overlap them to save on RAM
335 union {
336 int fieldIndex;
337 uint32_t startTime;
338 } u;
339 } xmitState;
341 // Cache for FLIGHT_LOG_FIELD_CONDITION_* test results:
342 static uint32_t blackboxConditionCache;
344 STATIC_ASSERT((sizeof(blackboxConditionCache) * 8) >= FLIGHT_LOG_FIELD_CONDITION_LAST, too_many_flight_log_conditions);
346 static uint32_t blackboxIteration;
347 static uint16_t blackboxLoopIndex;
348 static uint16_t blackboxPFrameIndex;
349 static uint16_t blackboxIFrameIndex;
350 // number of flight loop iterations before logging I-frame
351 // typically 32 for 1kHz loop, 64 for 2kHz loop etc
352 STATIC_UNIT_TESTED int16_t blackboxIInterval = 0;
353 // number of flight loop iterations before logging P-frame
354 STATIC_UNIT_TESTED int16_t blackboxPInterval = 0;
355 STATIC_UNIT_TESTED int32_t blackboxSInterval = 0;
356 STATIC_UNIT_TESTED int32_t blackboxSlowFrameIterationTimer;
357 static bool blackboxLoggedAnyFrames;
360 * We store voltages in I-frames relative to this, which was the voltage when the blackbox was activated.
361 * This helps out since the voltage is only expected to fall from that point and we can reduce our diffs
362 * to encode:
364 static uint16_t vbatReference;
366 static blackboxGpsState_t gpsHistory;
367 static blackboxSlowState_t slowHistory;
369 // Keep a history of length 2, plus a buffer for MW to store the new values into
370 static blackboxMainState_t blackboxHistoryRing[3];
372 // These point into blackboxHistoryRing, use them to know where to store history of a given age (0, 1 or 2 generations old)
373 static blackboxMainState_t* blackboxHistory[3];
375 static bool blackboxModeActivationConditionPresent = false;
378 * Return true if it is safe to edit the Blackbox configuration.
380 bool blackboxMayEditConfig(void)
382 return blackboxState <= BLACKBOX_STATE_STOPPED;
385 static bool blackboxIsOnlyLoggingIntraframes(void)
387 return blackboxConfig()->p_denom == 0;
390 static bool testBlackboxConditionUncached(FlightLogFieldCondition condition)
392 switch (condition) {
393 case FLIGHT_LOG_FIELD_CONDITION_ALWAYS:
394 return true;
396 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1:
397 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_2:
398 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_3:
399 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_4:
400 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_5:
401 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_6:
402 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7:
403 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8:
404 return getMotorCount() >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1 + 1;
406 case FLIGHT_LOG_FIELD_CONDITION_TRICOPTER:
407 return mixerConfig()->mixerMode == MIXER_TRI || mixerConfig()->mixerMode == MIXER_CUSTOM_TRI;
409 case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0:
410 case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1:
411 case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2:
412 return currentPidProfile->pid[condition - FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0].D != 0;
414 case FLIGHT_LOG_FIELD_CONDITION_MAG:
415 #ifdef USE_MAG
416 return sensors(SENSOR_MAG);
417 #else
418 return false;
419 #endif
421 case FLIGHT_LOG_FIELD_CONDITION_BARO:
422 #ifdef USE_BARO
423 return sensors(SENSOR_BARO);
424 #else
425 return false;
426 #endif
428 case FLIGHT_LOG_FIELD_CONDITION_VBAT:
429 return batteryConfig()->voltageMeterSource != VOLTAGE_METER_NONE;
431 case FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC:
432 return (batteryConfig()->currentMeterSource != CURRENT_METER_NONE) && (batteryConfig()->currentMeterSource != CURRENT_METER_VIRTUAL);
434 case FLIGHT_LOG_FIELD_CONDITION_RANGEFINDER:
435 #ifdef USE_RANGEFINDER
436 return sensors(SENSOR_RANGEFINDER);
437 #else
438 return false;
439 #endif
441 case FLIGHT_LOG_FIELD_CONDITION_RSSI:
442 return rxConfig()->rssi_channel > 0 || feature(FEATURE_RSSI_ADC);
444 case FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME:
445 return blackboxConfig()->p_denom != 1;
447 case FLIGHT_LOG_FIELD_CONDITION_ACC:
448 return sensors(SENSOR_ACC) && blackboxConfig()->record_acc;
450 case FLIGHT_LOG_FIELD_CONDITION_DEBUG:
451 return debugMode != DEBUG_NONE;
453 case FLIGHT_LOG_FIELD_CONDITION_NEVER:
454 return false;
456 default:
457 return false;
461 static void blackboxBuildConditionCache(void)
463 blackboxConditionCache = 0;
464 for (FlightLogFieldCondition cond = FLIGHT_LOG_FIELD_CONDITION_FIRST; cond <= FLIGHT_LOG_FIELD_CONDITION_LAST; cond++) {
465 if (testBlackboxConditionUncached(cond)) {
466 blackboxConditionCache |= 1 << cond;
471 static bool testBlackboxCondition(FlightLogFieldCondition condition)
473 return (blackboxConditionCache & (1 << condition)) != 0;
476 static void blackboxSetState(BlackboxState newState)
478 //Perform initial setup required for the new state
479 switch (newState) {
480 case BLACKBOX_STATE_PREPARE_LOG_FILE:
481 blackboxLoggedAnyFrames = false;
482 break;
483 case BLACKBOX_STATE_SEND_HEADER:
484 blackboxHeaderBudget = 0;
485 xmitState.headerIndex = 0;
486 xmitState.u.startTime = millis();
487 break;
488 case BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER:
489 case BLACKBOX_STATE_SEND_GPS_G_HEADER:
490 case BLACKBOX_STATE_SEND_GPS_H_HEADER:
491 case BLACKBOX_STATE_SEND_SLOW_HEADER:
492 xmitState.headerIndex = 0;
493 xmitState.u.fieldIndex = -1;
494 break;
495 case BLACKBOX_STATE_SEND_SYSINFO:
496 xmitState.headerIndex = 0;
497 break;
498 case BLACKBOX_STATE_RUNNING:
499 blackboxSlowFrameIterationTimer = blackboxSInterval; //Force a slow frame to be written on the first iteration
500 break;
501 case BLACKBOX_STATE_SHUTTING_DOWN:
502 xmitState.u.startTime = millis();
503 break;
504 default:
507 blackboxState = newState;
510 static void writeIntraframe(void)
512 blackboxMainState_t *blackboxCurrent = blackboxHistory[0];
514 blackboxWrite('I');
516 blackboxWriteUnsignedVB(blackboxIteration);
517 blackboxWriteUnsignedVB(blackboxCurrent->time);
519 blackboxWriteSignedVBArray(blackboxCurrent->axisPID_P, XYZ_AXIS_COUNT);
520 blackboxWriteSignedVBArray(blackboxCurrent->axisPID_I, XYZ_AXIS_COUNT);
522 // Don't bother writing the current D term if the corresponding PID setting is zero
523 for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
524 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0 + x)) {
525 blackboxWriteSignedVB(blackboxCurrent->axisPID_D[x]);
529 // Write roll, pitch and yaw first:
530 blackboxWriteSigned16VBArray(blackboxCurrent->rcCommand, 3);
533 * Write the throttle separately from the rest of the RC data so we can apply a predictor to it.
534 * Throttle lies in range [minthrottle..maxthrottle]:
536 blackboxWriteUnsignedVB(blackboxCurrent->rcCommand[THROTTLE] - motorConfig()->minthrottle);
538 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) {
540 * Our voltage is expected to decrease over the course of the flight, so store our difference from
541 * the reference:
543 * Write 14 bits even if the number is negative (which would otherwise result in 32 bits)
545 blackboxWriteUnsignedVB((vbatReference - blackboxCurrent->vbatLatest) & 0x3FFF);
548 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC)) {
549 // 12bit value directly from ADC
550 blackboxWriteUnsignedVB(blackboxCurrent->amperageLatest);
553 #ifdef USE_MAG
554 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_MAG)) {
555 blackboxWriteSigned16VBArray(blackboxCurrent->magADC, XYZ_AXIS_COUNT);
557 #endif
559 #ifdef USE_BARO
560 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_BARO)) {
561 blackboxWriteSignedVB(blackboxCurrent->BaroAlt);
563 #endif
565 #ifdef USE_RANGEFINDER
566 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_RANGEFINDER)) {
567 blackboxWriteSignedVB(blackboxCurrent->surfaceRaw);
569 #endif
571 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_RSSI)) {
572 blackboxWriteUnsignedVB(blackboxCurrent->rssi);
575 blackboxWriteSigned16VBArray(blackboxCurrent->gyroADC, XYZ_AXIS_COUNT);
576 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_ACC)) {
577 blackboxWriteSigned16VBArray(blackboxCurrent->accADC, XYZ_AXIS_COUNT);
580 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_DEBUG)) {
581 blackboxWriteSigned16VBArray(blackboxCurrent->debug, DEBUG16_VALUE_COUNT);
584 //Motors can be below minimum output when disarmed, but that doesn't happen much
585 blackboxWriteUnsignedVB(blackboxCurrent->motor[0] - motorOutputLow);
587 //Motors tend to be similar to each other so use the first motor's value as a predictor of the others
588 const int motorCount = getMotorCount();
589 for (int x = 1; x < motorCount; x++) {
590 blackboxWriteSignedVB(blackboxCurrent->motor[x] - blackboxCurrent->motor[0]);
593 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_TRICOPTER)) {
594 //Assume the tail spends most of its time around the center
595 blackboxWriteSignedVB(blackboxCurrent->servo[5] - 1500);
598 //Rotate our history buffers:
600 //The current state becomes the new "before" state
601 blackboxHistory[1] = blackboxHistory[0];
602 //And since we have no other history, we also use it for the "before, before" state
603 blackboxHistory[2] = blackboxHistory[0];
604 //And advance the current state over to a blank space ready to be filled
605 blackboxHistory[0] = ((blackboxHistory[0] - blackboxHistoryRing + 1) % 3) + blackboxHistoryRing;
607 blackboxLoggedAnyFrames = true;
610 static void blackboxWriteMainStateArrayUsingAveragePredictor(int arrOffsetInHistory, int count)
612 int16_t *curr = (int16_t*) ((char*) (blackboxHistory[0]) + arrOffsetInHistory);
613 int16_t *prev1 = (int16_t*) ((char*) (blackboxHistory[1]) + arrOffsetInHistory);
614 int16_t *prev2 = (int16_t*) ((char*) (blackboxHistory[2]) + arrOffsetInHistory);
616 for (int i = 0; i < count; i++) {
617 // Predictor is the average of the previous two history states
618 int32_t predictor = (prev1[i] + prev2[i]) / 2;
620 blackboxWriteSignedVB(curr[i] - predictor);
624 static void writeInterframe(void)
626 blackboxMainState_t *blackboxCurrent = blackboxHistory[0];
627 blackboxMainState_t *blackboxLast = blackboxHistory[1];
629 blackboxWrite('P');
631 //No need to store iteration count since its delta is always 1
634 * Since the difference between the difference between successive times will be nearly zero (due to consistent
635 * looptime spacing), use second-order differences.
637 blackboxWriteSignedVB((int32_t) (blackboxHistory[0]->time - 2 * blackboxHistory[1]->time + blackboxHistory[2]->time));
639 int32_t deltas[8];
640 arraySubInt32(deltas, blackboxCurrent->axisPID_P, blackboxLast->axisPID_P, XYZ_AXIS_COUNT);
641 blackboxWriteSignedVBArray(deltas, XYZ_AXIS_COUNT);
644 * The PID I field changes very slowly, most of the time +-2, so use an encoding
645 * that can pack all three fields into one byte in that situation.
647 arraySubInt32(deltas, blackboxCurrent->axisPID_I, blackboxLast->axisPID_I, XYZ_AXIS_COUNT);
648 blackboxWriteTag2_3S32(deltas);
651 * The PID D term is frequently set to zero for yaw, which makes the result from the calculation
652 * always zero. So don't bother recording D results when PID D terms are zero.
654 for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
655 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0 + x)) {
656 blackboxWriteSignedVB(blackboxCurrent->axisPID_D[x] - blackboxLast->axisPID_D[x]);
661 * RC tends to stay the same or fairly small for many frames at a time, so use an encoding that
662 * can pack multiple values per byte:
664 for (int x = 0; x < 4; x++) {
665 deltas[x] = blackboxCurrent->rcCommand[x] - blackboxLast->rcCommand[x];
668 blackboxWriteTag8_4S16(deltas);
670 //Check for sensors that are updated periodically (so deltas are normally zero)
671 int optionalFieldCount = 0;
673 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) {
674 deltas[optionalFieldCount++] = (int32_t) blackboxCurrent->vbatLatest - blackboxLast->vbatLatest;
677 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC)) {
678 deltas[optionalFieldCount++] = (int32_t) blackboxCurrent->amperageLatest - blackboxLast->amperageLatest;
681 #ifdef USE_MAG
682 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_MAG)) {
683 for (int x = 0; x < XYZ_AXIS_COUNT; x++) {
684 deltas[optionalFieldCount++] = blackboxCurrent->magADC[x] - blackboxLast->magADC[x];
687 #endif
689 #ifdef USE_BARO
690 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_BARO)) {
691 deltas[optionalFieldCount++] = blackboxCurrent->BaroAlt - blackboxLast->BaroAlt;
693 #endif
695 #ifdef USE_RANGEFINDER
696 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_RANGEFINDER)) {
697 deltas[optionalFieldCount++] = blackboxCurrent->surfaceRaw - blackboxLast->surfaceRaw;
699 #endif
701 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_RSSI)) {
702 deltas[optionalFieldCount++] = (int32_t) blackboxCurrent->rssi - blackboxLast->rssi;
705 blackboxWriteTag8_8SVB(deltas, optionalFieldCount);
707 //Since gyros, accs and motors are noisy, base their predictions on the average of the history:
708 blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, gyroADC), XYZ_AXIS_COUNT);
709 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_ACC)) {
710 blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, accADC), XYZ_AXIS_COUNT);
712 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_DEBUG)) {
713 blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, debug), DEBUG16_VALUE_COUNT);
715 blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t, motor), getMotorCount());
717 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_TRICOPTER)) {
718 blackboxWriteSignedVB(blackboxCurrent->servo[5] - blackboxLast->servo[5]);
721 //Rotate our history buffers
722 blackboxHistory[2] = blackboxHistory[1];
723 blackboxHistory[1] = blackboxHistory[0];
724 blackboxHistory[0] = ((blackboxHistory[0] - blackboxHistoryRing + 1) % 3) + blackboxHistoryRing;
726 blackboxLoggedAnyFrames = true;
729 /* Write the contents of the global "slowHistory" to the log as an "S" frame. Because this data is logged so
730 * infrequently, delta updates are not reasonable, so we log independent frames. */
731 static void writeSlowFrame(void)
733 int32_t values[3];
735 blackboxWrite('S');
737 blackboxWriteUnsignedVB(slowHistory.flightModeFlags);
738 blackboxWriteUnsignedVB(slowHistory.stateFlags);
741 * Most of the time these three values will be able to pack into one byte for us:
743 values[0] = slowHistory.failsafePhase;
744 values[1] = slowHistory.rxSignalReceived ? 1 : 0;
745 values[2] = slowHistory.rxFlightChannelsValid ? 1 : 0;
746 blackboxWriteTag2_3S32(values);
748 blackboxSlowFrameIterationTimer = 0;
752 * Load rarely-changing values from the FC into the given structure
754 static void loadSlowState(blackboxSlowState_t *slow)
756 memcpy(&slow->flightModeFlags, &rcModeActivationMask, sizeof(slow->flightModeFlags)); //was flightModeFlags;
757 slow->stateFlags = stateFlags;
758 slow->failsafePhase = failsafePhase();
759 slow->rxSignalReceived = rxIsReceivingSignal();
760 slow->rxFlightChannelsValid = rxAreFlightChannelsValid();
764 * If the data in the slow frame has changed, log a slow frame.
766 * If allowPeriodicWrite is true, the frame is also logged if it has been more than blackboxSInterval logging iterations
767 * since the field was last logged.
769 STATIC_UNIT_TESTED bool writeSlowFrameIfNeeded(void)
771 // Write the slow frame peridocially so it can be recovered if we ever lose sync
772 bool shouldWrite = blackboxSlowFrameIterationTimer >= blackboxSInterval;
774 if (shouldWrite) {
775 loadSlowState(&slowHistory);
776 } else {
777 blackboxSlowState_t newSlowState;
779 loadSlowState(&newSlowState);
781 // Only write a slow frame if it was different from the previous state
782 if (memcmp(&newSlowState, &slowHistory, sizeof(slowHistory)) != 0) {
783 // Use the new state as our new history
784 memcpy(&slowHistory, &newSlowState, sizeof(slowHistory));
785 shouldWrite = true;
789 if (shouldWrite) {
790 writeSlowFrame();
792 return shouldWrite;
795 void blackboxValidateConfig(void)
797 // If we've chosen an unsupported device, change the device to serial
798 switch (blackboxConfig()->device) {
799 #ifdef USE_FLASHFS
800 case BLACKBOX_DEVICE_FLASH:
801 #endif
802 #ifdef USE_SDCARD
803 case BLACKBOX_DEVICE_SDCARD:
804 #endif
805 case BLACKBOX_DEVICE_SERIAL:
806 // Device supported, leave the setting alone
807 break;
809 default:
810 blackboxConfigMutable()->device = BLACKBOX_DEVICE_SERIAL;
814 static void blackboxResetIterationTimers(void)
816 blackboxIteration = 0;
817 blackboxLoopIndex = 0;
818 blackboxIFrameIndex = 0;
819 blackboxPFrameIndex = 0;
820 blackboxSlowFrameIterationTimer = 0;
824 * Start Blackbox logging if it is not already running. Intended to be called upon arming.
826 static void blackboxStart(void)
828 blackboxValidateConfig();
830 if (!blackboxDeviceOpen()) {
831 blackboxSetState(BLACKBOX_STATE_DISABLED);
832 return;
835 memset(&gpsHistory, 0, sizeof(gpsHistory));
837 blackboxHistory[0] = &blackboxHistoryRing[0];
838 blackboxHistory[1] = &blackboxHistoryRing[1];
839 blackboxHistory[2] = &blackboxHistoryRing[2];
841 vbatReference = getBatteryVoltageLatest();
843 //No need to clear the content of blackboxHistoryRing since our first frame will be an intra which overwrites it
846 * We use conditional tests to decide whether or not certain fields should be logged. Since our headers
847 * must always agree with the logged data, the results of these tests must not change during logging. So
848 * cache those now.
850 blackboxBuildConditionCache();
852 blackboxModeActivationConditionPresent = isModeActivationConditionPresent(BOXBLACKBOX);
854 blackboxResetIterationTimers();
857 * Record the beeper's current idea of the last arming beep time, so that we can detect it changing when
858 * it finally plays the beep for this arming event.
860 blackboxLastArmingBeep = getArmingBeepTimeMicros();
861 memcpy(&blackboxLastFlightModeFlags, &rcModeActivationMask, sizeof(blackboxLastFlightModeFlags)); // record startup status
863 blackboxSetState(BLACKBOX_STATE_PREPARE_LOG_FILE);
867 * Begin Blackbox shutdown.
869 void blackboxFinish(void)
871 switch (blackboxState) {
872 case BLACKBOX_STATE_DISABLED:
873 case BLACKBOX_STATE_STOPPED:
874 case BLACKBOX_STATE_SHUTTING_DOWN:
875 // We're already stopped/shutting down
876 break;
877 case BLACKBOX_STATE_RUNNING:
878 case BLACKBOX_STATE_PAUSED:
879 blackboxLogEvent(FLIGHT_LOG_EVENT_LOG_END, NULL);
880 FALLTHROUGH;
881 default:
882 blackboxSetState(BLACKBOX_STATE_SHUTTING_DOWN);
887 * Test Motors Blackbox Logging
889 static bool startedLoggingInTestMode = false;
891 static void startInTestMode(void)
893 if (!startedLoggingInTestMode) {
894 if (blackboxConfig()->device == BLACKBOX_DEVICE_SERIAL) {
895 serialPort_t *sharedBlackboxAndMspPort = findSharedSerialPort(FUNCTION_BLACKBOX, FUNCTION_MSP);
896 if (sharedBlackboxAndMspPort) {
897 return; // When in test mode, we cannot share the MSP and serial logger port!
900 blackboxStart();
901 startedLoggingInTestMode = true;
905 static void stopInTestMode(void)
907 if (startedLoggingInTestMode) {
908 blackboxFinish();
909 startedLoggingInTestMode = false;
913 * We are going to monitor the MSP_SET_MOTOR target variables motor_disarmed[] for values other than minthrottle
914 * on reading a value (i.e. the user is testing the motors), then we enable test mode logging;
915 * we monitor when the values return to minthrottle and start a delay timer (5 seconds); if
916 * the test motors are left at minimum throttle for this delay timer, then we assume we are done testing and
917 * shutdown the logger.
919 * Of course, after the 5 seconds and shutdown of the logger, the system will be re-enabled to allow the
920 * test mode to trigger again; its just that the data will be in a second, third, fourth etc log file.
922 static bool inMotorTestMode(void) {
923 static uint32_t resetTime = 0;
925 if (!ARMING_FLAG(ARMED) && areMotorsRunning()) {
926 resetTime = millis() + 5000; // add 5 seconds
927 return true;
928 } else {
929 // Monitor the duration at minimum
930 return (millis() < resetTime);
932 return false;
935 #ifdef USE_GPS
936 static void writeGPSHomeFrame(void)
938 blackboxWrite('H');
940 blackboxWriteSignedVB(GPS_home[0]);
941 blackboxWriteSignedVB(GPS_home[1]);
942 //TODO it'd be great if we could grab the GPS current time and write that too
944 gpsHistory.GPS_home[0] = GPS_home[0];
945 gpsHistory.GPS_home[1] = GPS_home[1];
948 static void writeGPSFrame(timeUs_t currentTimeUs)
950 blackboxWrite('G');
953 * If we're logging every frame, then a GPS frame always appears just after a frame with the
954 * currentTime timestamp in the log, so the reader can just use that timestamp for the GPS frame.
956 * If we're not logging every frame, we need to store the time of this GPS frame.
958 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME)) {
959 // Predict the time of the last frame in the main log
960 blackboxWriteUnsignedVB(currentTimeUs - blackboxHistory[1]->time);
963 blackboxWriteUnsignedVB(gpsSol.numSat);
964 blackboxWriteSignedVB(gpsSol.llh.lat - gpsHistory.GPS_home[LAT]);
965 blackboxWriteSignedVB(gpsSol.llh.lon - gpsHistory.GPS_home[LON]);
966 blackboxWriteUnsignedVB(gpsSol.llh.alt);
967 blackboxWriteUnsignedVB(gpsSol.groundSpeed);
968 blackboxWriteUnsignedVB(gpsSol.groundCourse);
970 gpsHistory.GPS_numSat = gpsSol.numSat;
971 gpsHistory.GPS_coord[LAT] = gpsSol.llh.lat;
972 gpsHistory.GPS_coord[LON] = gpsSol.llh.lon;
974 #endif
977 * Fill the current state of the blackbox using values read from the flight controller
979 static void loadMainState(timeUs_t currentTimeUs)
981 #ifndef UNIT_TEST
982 blackboxMainState_t *blackboxCurrent = blackboxHistory[0];
984 blackboxCurrent->time = currentTimeUs;
986 for (int i = 0; i < XYZ_AXIS_COUNT; i++) {
987 blackboxCurrent->axisPID_P[i] = axisPID_P[i];
988 blackboxCurrent->axisPID_I[i] = axisPID_I[i];
989 blackboxCurrent->axisPID_D[i] = axisPID_D[i];
990 blackboxCurrent->gyroADC[i] = lrintf(gyro.gyroADCf[i]);
991 blackboxCurrent->accADC[i] = lrintf(acc.accADC[i]);
992 #ifdef USE_MAG
993 blackboxCurrent->magADC[i] = mag.magADC[i];
994 #endif
997 for (int i = 0; i < 4; i++) {
998 blackboxCurrent->rcCommand[i] = rcCommand[i];
1001 for (int i = 0; i < DEBUG16_VALUE_COUNT; i++) {
1002 blackboxCurrent->debug[i] = debug[i];
1005 const int motorCount = getMotorCount();
1006 for (int i = 0; i < motorCount; i++) {
1007 blackboxCurrent->motor[i] = motor[i];
1010 blackboxCurrent->vbatLatest = getBatteryVoltageLatest();
1011 blackboxCurrent->amperageLatest = getAmperageLatest();
1013 #ifdef USE_BARO
1014 blackboxCurrent->BaroAlt = baro.BaroAlt;
1015 #endif
1017 #ifdef USE_RANGEFINDER
1018 // Store the raw sonar value without applying tilt correction
1019 blackboxCurrent->surfaceRaw = rangefinderGetLatestAltitude();
1020 #endif
1022 blackboxCurrent->rssi = getRssi();
1024 #ifdef USE_SERVOS
1025 //Tail servo for tricopters
1026 blackboxCurrent->servo[5] = servo[5];
1027 #endif
1028 #else
1029 UNUSED(currentTimeUs);
1030 #endif // UNIT_TEST
1034 * Transmit the header information for the given field definitions. Transmitted header lines look like:
1036 * H Field I name:a,b,c
1037 * H Field I predictor:0,1,2
1039 * For all header types, provide a "mainFrameChar" which is the name for the field and will be used to refer to it in the
1040 * header (e.g. P, I etc). For blackboxDeltaField_t fields, also provide deltaFrameChar, otherwise set this to zero.
1042 * Provide an array 'conditions' of FlightLogFieldCondition enums if you want these conditions to decide whether a field
1043 * should be included or not. Otherwise provide NULL for this parameter and NULL for secondCondition.
1045 * Set xmitState.headerIndex to 0 and xmitState.u.fieldIndex to -1 before calling for the first time.
1047 * secondFieldDefinition and secondCondition element pointers need to be provided in order to compute the stride of the
1048 * fieldDefinition and secondCondition arrays.
1050 * Returns true if there is still header left to transmit (so call again to continue transmission).
1052 static bool sendFieldDefinition(char mainFrameChar, char deltaFrameChar, const void *fieldDefinitions,
1053 const void *secondFieldDefinition, int fieldCount, const uint8_t *conditions, const uint8_t *secondCondition)
1055 const blackboxFieldDefinition_t *def;
1056 unsigned int headerCount;
1057 static bool needComma = false;
1058 size_t definitionStride = (char*) secondFieldDefinition - (char*) fieldDefinitions;
1059 size_t conditionsStride = (char*) secondCondition - (char*) conditions;
1061 if (deltaFrameChar) {
1062 headerCount = BLACKBOX_DELTA_FIELD_HEADER_COUNT;
1063 } else {
1064 headerCount = BLACKBOX_SIMPLE_FIELD_HEADER_COUNT;
1068 * We're chunking up the header data so we don't exceed our datarate. So we'll be called multiple times to transmit
1069 * the whole header.
1072 // On our first call we need to print the name of the header and a colon
1073 if (xmitState.u.fieldIndex == -1) {
1074 if (xmitState.headerIndex >= headerCount) {
1075 return false; //Someone probably called us again after we had already completed transmission
1078 uint32_t charsToBeWritten = strlen("H Field x :") + strlen(blackboxFieldHeaderNames[xmitState.headerIndex]);
1080 if (blackboxDeviceReserveBufferSpace(charsToBeWritten) != BLACKBOX_RESERVE_SUCCESS) {
1081 return true; // Try again later
1084 blackboxHeaderBudget -= blackboxPrintf("H Field %c %s:", xmitState.headerIndex >= BLACKBOX_SIMPLE_FIELD_HEADER_COUNT ? deltaFrameChar : mainFrameChar, blackboxFieldHeaderNames[xmitState.headerIndex]);
1086 xmitState.u.fieldIndex++;
1087 needComma = false;
1090 // The longest we expect an integer to be as a string:
1091 const uint32_t LONGEST_INTEGER_STRLEN = 2;
1093 for (; xmitState.u.fieldIndex < fieldCount; xmitState.u.fieldIndex++) {
1094 def = (const blackboxFieldDefinition_t*) ((const char*)fieldDefinitions + definitionStride * xmitState.u.fieldIndex);
1096 if (!conditions || testBlackboxCondition(conditions[conditionsStride * xmitState.u.fieldIndex])) {
1097 // First (over)estimate the length of the string we want to print
1099 int32_t bytesToWrite = 1; // Leading comma
1101 // The first header is a field name
1102 if (xmitState.headerIndex == 0) {
1103 bytesToWrite += strlen(def->name) + strlen("[]") + LONGEST_INTEGER_STRLEN;
1104 } else {
1105 //The other headers are integers
1106 bytesToWrite += LONGEST_INTEGER_STRLEN;
1109 // Now perform the write if the buffer is large enough
1110 if (blackboxDeviceReserveBufferSpace(bytesToWrite) != BLACKBOX_RESERVE_SUCCESS) {
1111 // Ran out of space!
1112 return true;
1115 blackboxHeaderBudget -= bytesToWrite;
1117 if (needComma) {
1118 blackboxWrite(',');
1119 } else {
1120 needComma = true;
1123 // The first header is a field name
1124 if (xmitState.headerIndex == 0) {
1125 blackboxWriteString(def->name);
1127 // Do we need to print an index in brackets after the name?
1128 if (def->fieldNameIndex != -1) {
1129 blackboxPrintf("[%d]", def->fieldNameIndex);
1131 } else {
1132 //The other headers are integers
1133 blackboxPrintf("%d", def->arr[xmitState.headerIndex - 1]);
1138 // Did we complete this line?
1139 if (xmitState.u.fieldIndex == fieldCount && blackboxDeviceReserveBufferSpace(1) == BLACKBOX_RESERVE_SUCCESS) {
1140 blackboxHeaderBudget--;
1141 blackboxWrite('\n');
1142 xmitState.headerIndex++;
1143 xmitState.u.fieldIndex = -1;
1146 return xmitState.headerIndex < headerCount;
1149 // Buf must be at least FORMATTED_DATE_TIME_BUFSIZE
1150 STATIC_UNIT_TESTED char *blackboxGetStartDateTime(char *buf)
1152 #ifdef USE_RTC_TIME
1153 dateTime_t dt;
1154 // rtcGetDateTime will fill dt with 0000-01-01T00:00:00
1155 // when time is not known.
1156 rtcGetDateTime(&dt);
1157 dateTimeFormatLocal(buf, &dt);
1158 #else
1159 buf = "0000-01-01T00:00:00.000";
1160 #endif
1162 return buf;
1165 #ifndef BLACKBOX_PRINT_HEADER_LINE
1166 #define BLACKBOX_PRINT_HEADER_LINE(name, format, ...) case __COUNTER__: \
1167 blackboxPrintfHeaderLine(name, format, __VA_ARGS__); \
1168 break;
1169 #define BLACKBOX_PRINT_HEADER_LINE_CUSTOM(...) case __COUNTER__: \
1170 {__VA_ARGS__}; \
1171 break;
1172 #endif
1175 * Transmit a portion of the system information headers. Call the first time with xmitState.headerIndex == 0. Returns
1176 * true iff transmission is complete, otherwise call again later to continue transmission.
1178 static bool blackboxWriteSysinfo(void)
1180 #ifndef UNIT_TEST
1181 const uint16_t motorOutputLowInt = lrintf(motorOutputLow);
1182 const uint16_t motorOutputHighInt = lrintf(motorOutputHigh);
1184 // Make sure we have enough room in the buffer for our longest line (as of this writing, the "Firmware date" line)
1185 if (blackboxDeviceReserveBufferSpace(64) != BLACKBOX_RESERVE_SUCCESS) {
1186 return false;
1189 char buf[FORMATTED_DATE_TIME_BUFSIZE];
1191 const controlRateConfig_t *currentControlRateProfile = controlRateProfiles(systemConfig()->activeRateProfile);
1192 switch (xmitState.headerIndex) {
1193 BLACKBOX_PRINT_HEADER_LINE("Firmware type", "%s", "Cleanflight");
1194 BLACKBOX_PRINT_HEADER_LINE("Firmware revision", "%s %s (%s) %s", FC_FIRMWARE_NAME, FC_VERSION_STRING, shortGitRevision, targetName);
1195 BLACKBOX_PRINT_HEADER_LINE("Firmware date", "%s %s", buildDate, buildTime);
1196 BLACKBOX_PRINT_HEADER_LINE("Log start datetime", "%s", blackboxGetStartDateTime(buf));
1197 BLACKBOX_PRINT_HEADER_LINE("Craft name", "%s", pilotConfig()->name);
1198 BLACKBOX_PRINT_HEADER_LINE("I interval", "%d", blackboxIInterval);
1199 BLACKBOX_PRINT_HEADER_LINE("P interval", "%d/%d", blackboxGetRateNum(), blackboxGetRateDenom());
1200 BLACKBOX_PRINT_HEADER_LINE("P denom", "%d", blackboxConfig()->p_denom);
1201 BLACKBOX_PRINT_HEADER_LINE("minthrottle", "%d", motorConfig()->minthrottle);
1202 BLACKBOX_PRINT_HEADER_LINE("maxthrottle", "%d", motorConfig()->maxthrottle);
1203 BLACKBOX_PRINT_HEADER_LINE("gyro_scale","0x%x", castFloatBytesToInt(1.0f));
1204 BLACKBOX_PRINT_HEADER_LINE("motorOutput", "%d,%d", motorOutputLowInt,motorOutputHighInt);
1205 BLACKBOX_PRINT_HEADER_LINE("acc_1G", "%u", acc.dev.acc_1G);
1207 BLACKBOX_PRINT_HEADER_LINE_CUSTOM(
1208 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) {
1209 blackboxPrintfHeaderLine("vbat_scale", "%u", voltageSensorADCConfig(VOLTAGE_SENSOR_ADC_VBAT)->vbatscale);
1210 } else {
1211 xmitState.headerIndex += 2; // Skip the next two vbat fields too
1215 BLACKBOX_PRINT_HEADER_LINE("vbatcellvoltage", "%u,%u,%u", batteryConfig()->vbatmincellvoltage,
1216 batteryConfig()->vbatwarningcellvoltage,
1217 batteryConfig()->vbatmaxcellvoltage);
1218 BLACKBOX_PRINT_HEADER_LINE("vbatref", "%u", vbatReference);
1220 BLACKBOX_PRINT_HEADER_LINE_CUSTOM(
1221 if (batteryConfig()->currentMeterSource == CURRENT_METER_ADC) {
1222 blackboxPrintfHeaderLine("currentSensor", "%d,%d",currentSensorADCConfig()->offset, currentSensorADCConfig()->scale);
1226 BLACKBOX_PRINT_HEADER_LINE("looptime", "%d", gyro.targetLooptime);
1227 BLACKBOX_PRINT_HEADER_LINE("gyro_sync_denom", "%d", gyroConfig()->gyro_sync_denom);
1228 BLACKBOX_PRINT_HEADER_LINE("pid_process_denom", "%d", pidConfig()->pid_process_denom);
1229 BLACKBOX_PRINT_HEADER_LINE("thr_mid", "%d", currentControlRateProfile->thrMid8);
1230 BLACKBOX_PRINT_HEADER_LINE("thr_expo", "%d", currentControlRateProfile->thrExpo8);
1231 BLACKBOX_PRINT_HEADER_LINE("tpa_rate", "%d", currentControlRateProfile->dynThrPID);
1232 BLACKBOX_PRINT_HEADER_LINE("tpa_breakpoint", "%d", currentControlRateProfile->tpa_breakpoint);
1233 BLACKBOX_PRINT_HEADER_LINE("rc_rates", "%d,%d,%d", currentControlRateProfile->rcRates[ROLL],
1234 currentControlRateProfile->rcRates[PITCH],
1235 currentControlRateProfile->rcRates[YAW]);
1236 BLACKBOX_PRINT_HEADER_LINE("rc_expo", "%d,%d,%d", currentControlRateProfile->rcExpo[ROLL],
1237 currentControlRateProfile->rcExpo[PITCH],
1238 currentControlRateProfile->rcExpo[YAW]);
1239 BLACKBOX_PRINT_HEADER_LINE("rates", "%d,%d,%d", currentControlRateProfile->rates[ROLL],
1240 currentControlRateProfile->rates[PITCH],
1241 currentControlRateProfile->rates[YAW]);
1242 BLACKBOX_PRINT_HEADER_LINE("rollPID", "%d,%d,%d", currentPidProfile->pid[PID_ROLL].P,
1243 currentPidProfile->pid[PID_ROLL].I,
1244 currentPidProfile->pid[PID_ROLL].D);
1245 BLACKBOX_PRINT_HEADER_LINE("pitchPID", "%d,%d,%d", currentPidProfile->pid[PID_PITCH].P,
1246 currentPidProfile->pid[PID_PITCH].I,
1247 currentPidProfile->pid[PID_PITCH].D);
1248 BLACKBOX_PRINT_HEADER_LINE("yawPID", "%d,%d,%d", currentPidProfile->pid[PID_YAW].P,
1249 currentPidProfile->pid[PID_YAW].I,
1250 currentPidProfile->pid[PID_YAW].D);
1251 BLACKBOX_PRINT_HEADER_LINE("altPID", "%d,%d,%d", currentPidProfile->pid[PID_ALT].P,
1252 currentPidProfile->pid[PID_ALT].I,
1253 currentPidProfile->pid[PID_ALT].D);
1254 BLACKBOX_PRINT_HEADER_LINE("posPID", "%d,%d,%d", currentPidProfile->pid[PID_POS].P,
1255 currentPidProfile->pid[PID_POS].I,
1256 currentPidProfile->pid[PID_POS].D);
1257 BLACKBOX_PRINT_HEADER_LINE("posrPID", "%d,%d,%d", currentPidProfile->pid[PID_POSR].P,
1258 currentPidProfile->pid[PID_POSR].I,
1259 currentPidProfile->pid[PID_POSR].D);
1260 BLACKBOX_PRINT_HEADER_LINE("navrPID", "%d,%d,%d", currentPidProfile->pid[PID_NAVR].P,
1261 currentPidProfile->pid[PID_NAVR].I,
1262 currentPidProfile->pid[PID_NAVR].D);
1263 BLACKBOX_PRINT_HEADER_LINE("levelPID", "%d,%d,%d", currentPidProfile->pid[PID_LEVEL].P,
1264 currentPidProfile->pid[PID_LEVEL].I,
1265 currentPidProfile->pid[PID_LEVEL].D);
1266 BLACKBOX_PRINT_HEADER_LINE("magPID", "%d", currentPidProfile->pid[PID_MAG].P);
1267 BLACKBOX_PRINT_HEADER_LINE("velPID", "%d,%d,%d", currentPidProfile->pid[PID_VEL].P,
1268 currentPidProfile->pid[PID_VEL].I,
1269 currentPidProfile->pid[PID_VEL].D);
1270 BLACKBOX_PRINT_HEADER_LINE("dterm_filter_type", "%d", currentPidProfile->dterm_filter_type);
1271 BLACKBOX_PRINT_HEADER_LINE("dterm_lowpass_hz", "%d", currentPidProfile->dterm_lowpass_hz);
1272 BLACKBOX_PRINT_HEADER_LINE("yaw_lowpass_hz", "%d", currentPidProfile->yaw_lowpass_hz);
1273 BLACKBOX_PRINT_HEADER_LINE("dterm_notch_hz", "%d", currentPidProfile->dterm_notch_hz);
1274 BLACKBOX_PRINT_HEADER_LINE("dterm_notch_cutoff", "%d", currentPidProfile->dterm_notch_cutoff);
1275 BLACKBOX_PRINT_HEADER_LINE("iterm_windup", "%d", currentPidProfile->itermWindupPointPercent);
1276 BLACKBOX_PRINT_HEADER_LINE("vbat_pid_gain", "%d", currentPidProfile->vbatPidCompensation);
1277 BLACKBOX_PRINT_HEADER_LINE("pidAtMinThrottle", "%d", currentPidProfile->pidAtMinThrottle);
1279 // Betaflight PID controller parameters
1280 BLACKBOX_PRINT_HEADER_LINE("anti_gravity_threshold", "%d", currentPidProfile->itermThrottleThreshold);
1281 BLACKBOX_PRINT_HEADER_LINE("anti_gravity_gain", "%d", currentPidProfile->itermAcceleratorGain);
1282 BLACKBOX_PRINT_HEADER_LINE("setpoint_relaxation_ratio", "%d", currentPidProfile->setpointRelaxRatio);
1283 BLACKBOX_PRINT_HEADER_LINE("dterm_setpoint_weight", "%d", currentPidProfile->dtermSetpointWeight);
1284 BLACKBOX_PRINT_HEADER_LINE("acc_limit_yaw", "%d", currentPidProfile->yawRateAccelLimit);
1285 BLACKBOX_PRINT_HEADER_LINE("acc_limit", "%d", currentPidProfile->rateAccelLimit);
1286 BLACKBOX_PRINT_HEADER_LINE("pidsum_limit", "%d", currentPidProfile->pidSumLimit);
1287 BLACKBOX_PRINT_HEADER_LINE("pidsum_limit_yaw", "%d", currentPidProfile->pidSumLimitYaw);
1288 // End of Betaflight controller parameters
1290 BLACKBOX_PRINT_HEADER_LINE("deadband", "%d", rcControlsConfig()->deadband);
1291 BLACKBOX_PRINT_HEADER_LINE("yaw_deadband", "%d", rcControlsConfig()->yaw_deadband);
1292 BLACKBOX_PRINT_HEADER_LINE("gyro_lpf", "%d", gyroConfig()->gyro_lpf);
1293 BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_type", "%d", gyroConfig()->gyro_soft_lpf_type);
1294 BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_hz", "%d", gyroConfig()->gyro_soft_lpf_hz);
1295 BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz", "%d,%d", gyroConfig()->gyro_soft_notch_hz_1,
1296 gyroConfig()->gyro_soft_notch_hz_2);
1297 BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff", "%d,%d", gyroConfig()->gyro_soft_notch_cutoff_1,
1298 gyroConfig()->gyro_soft_notch_cutoff_2);
1299 BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz", "%d", (int)(accelerometerConfig()->acc_lpf_hz * 100.0f));
1300 BLACKBOX_PRINT_HEADER_LINE("acc_hardware", "%d", accelerometerConfig()->acc_hardware);
1301 BLACKBOX_PRINT_HEADER_LINE("baro_hardware", "%d", barometerConfig()->baro_hardware);
1302 BLACKBOX_PRINT_HEADER_LINE("mag_hardware", "%d", compassConfig()->mag_hardware);
1303 BLACKBOX_PRINT_HEADER_LINE("gyro_cal_on_first_arm", "%d", armingConfig()->gyro_cal_on_first_arm);
1304 BLACKBOX_PRINT_HEADER_LINE("rc_interpolation", "%d", rxConfig()->rcInterpolation);
1305 BLACKBOX_PRINT_HEADER_LINE("rc_interpolation_interval", "%d", rxConfig()->rcInterpolationInterval);
1306 BLACKBOX_PRINT_HEADER_LINE("airmode_activate_throttle", "%d", rxConfig()->airModeActivateThreshold);
1307 BLACKBOX_PRINT_HEADER_LINE("serialrx_provider", "%d", rxConfig()->serialrx_provider);
1308 BLACKBOX_PRINT_HEADER_LINE("use_unsynced_pwm", "%d", motorConfig()->dev.useUnsyncedPwm);
1309 BLACKBOX_PRINT_HEADER_LINE("motor_pwm_protocol", "%d", motorConfig()->dev.motorPwmProtocol);
1310 BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate", "%d", motorConfig()->dev.motorPwmRate);
1311 BLACKBOX_PRINT_HEADER_LINE("dshot_idle_value", "%d", motorConfig()->digitalIdleOffsetValue);
1312 BLACKBOX_PRINT_HEADER_LINE("debug_mode", "%d", systemConfig()->debug_mode);
1313 BLACKBOX_PRINT_HEADER_LINE("features", "%d", featureConfig()->enabledFeatures);
1315 default:
1316 return true;
1319 xmitState.headerIndex++;
1320 #endif // UNIT_TEST
1321 return false;
1325 * Write the given event to the log immediately
1327 void blackboxLogEvent(FlightLogEvent event, flightLogEventData_t *data)
1329 // Only allow events to be logged after headers have been written
1330 if (!(blackboxState == BLACKBOX_STATE_RUNNING || blackboxState == BLACKBOX_STATE_PAUSED)) {
1331 return;
1334 //Shared header for event frames
1335 blackboxWrite('E');
1336 blackboxWrite(event);
1338 //Now serialize the data for this specific frame type
1339 switch (event) {
1340 case FLIGHT_LOG_EVENT_SYNC_BEEP:
1341 blackboxWriteUnsignedVB(data->syncBeep.time);
1342 break;
1343 case FLIGHT_LOG_EVENT_FLIGHTMODE: // New flightmode flags write
1344 blackboxWriteUnsignedVB(data->flightMode.flags);
1345 blackboxWriteUnsignedVB(data->flightMode.lastFlags);
1346 break;
1347 case FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT:
1348 if (data->inflightAdjustment.floatFlag) {
1349 blackboxWrite(data->inflightAdjustment.adjustmentFunction + FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT_FUNCTION_FLOAT_VALUE_FLAG);
1350 blackboxWriteFloat(data->inflightAdjustment.newFloatValue);
1351 } else {
1352 blackboxWrite(data->inflightAdjustment.adjustmentFunction);
1353 blackboxWriteSignedVB(data->inflightAdjustment.newValue);
1355 break;
1356 case FLIGHT_LOG_EVENT_LOGGING_RESUME:
1357 blackboxWriteUnsignedVB(data->loggingResume.logIteration);
1358 blackboxWriteUnsignedVB(data->loggingResume.currentTime);
1359 break;
1360 case FLIGHT_LOG_EVENT_LOG_END:
1361 blackboxWriteString("End of log");
1362 blackboxWrite(0);
1363 break;
1367 /* 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 */
1368 static void blackboxCheckAndLogArmingBeep(void)
1370 // Use != so that we can still detect a change if the counter wraps
1371 if (getArmingBeepTimeMicros() != blackboxLastArmingBeep) {
1372 blackboxLastArmingBeep = getArmingBeepTimeMicros();
1373 flightLogEvent_syncBeep_t eventData;
1374 eventData.time = blackboxLastArmingBeep;
1375 blackboxLogEvent(FLIGHT_LOG_EVENT_SYNC_BEEP, (flightLogEventData_t *)&eventData);
1379 /* monitor the flight mode event status and trigger an event record if the state changes */
1380 static void blackboxCheckAndLogFlightMode(void)
1382 // Use != so that we can still detect a change if the counter wraps
1383 if (memcmp(&rcModeActivationMask, &blackboxLastFlightModeFlags, sizeof(blackboxLastFlightModeFlags))) {
1384 flightLogEvent_flightMode_t eventData; // Add new data for current flight mode flags
1385 eventData.lastFlags = blackboxLastFlightModeFlags;
1386 memcpy(&blackboxLastFlightModeFlags, &rcModeActivationMask, sizeof(blackboxLastFlightModeFlags));
1387 memcpy(&eventData.flags, &rcModeActivationMask, sizeof(eventData.flags));
1388 blackboxLogEvent(FLIGHT_LOG_EVENT_FLIGHTMODE, (flightLogEventData_t *)&eventData);
1392 STATIC_UNIT_TESTED bool blackboxShouldLogPFrame(void)
1394 return blackboxPFrameIndex == 0 && blackboxConfig()->p_denom != 0;
1397 STATIC_UNIT_TESTED bool blackboxShouldLogIFrame(void)
1399 return blackboxLoopIndex == 0;
1403 * If the GPS home point has been updated, or every 128 I-frames (~10 seconds), write the
1404 * GPS home position.
1406 * We write it periodically so that if one Home Frame goes missing, the GPS coordinates can
1407 * still be interpreted correctly.
1409 #ifdef USE_GPS
1410 STATIC_UNIT_TESTED bool blackboxShouldLogGpsHomeFrame(void)
1412 if (GPS_home[0] != gpsHistory.GPS_home[0] || GPS_home[1] != gpsHistory.GPS_home[1]
1413 || (blackboxPFrameIndex == blackboxIInterval / 2 && blackboxIFrameIndex % 128 == 0)) {
1414 return true;
1416 return false;
1418 #endif // GPS
1420 // Called once every FC loop in order to keep track of how many FC loop iterations have passed
1421 STATIC_UNIT_TESTED void blackboxAdvanceIterationTimers(void)
1423 ++blackboxSlowFrameIterationTimer;
1424 ++blackboxIteration;
1426 if (++blackboxLoopIndex >= blackboxIInterval) {
1427 blackboxLoopIndex = 0;
1428 blackboxIFrameIndex++;
1429 blackboxPFrameIndex = 0;
1430 } else if (++blackboxPFrameIndex >= blackboxPInterval) {
1431 blackboxPFrameIndex = 0;
1435 // Called once every FC loop in order to log the current state
1436 STATIC_UNIT_TESTED void blackboxLogIteration(timeUs_t currentTimeUs)
1438 // Write a keyframe every blackboxIInterval frames so we can resynchronise upon missing frames
1439 if (blackboxShouldLogIFrame()) {
1441 * Don't log a slow frame if the slow data didn't change ("I" frames are already large enough without adding
1442 * an additional item to write at the same time). Unless we're *only* logging "I" frames, then we have no choice.
1444 if (blackboxIsOnlyLoggingIntraframes()) {
1445 writeSlowFrameIfNeeded();
1448 loadMainState(currentTimeUs);
1449 writeIntraframe();
1450 } else {
1451 blackboxCheckAndLogArmingBeep();
1452 blackboxCheckAndLogFlightMode(); // Check for FlightMode status change event
1454 if (blackboxShouldLogPFrame()) {
1456 * We assume that slow frames are only interesting in that they aid the interpretation of the main data stream.
1457 * So only log slow frames during loop iterations where we log a main frame.
1459 writeSlowFrameIfNeeded();
1461 loadMainState(currentTimeUs);
1462 writeInterframe();
1464 #ifdef USE_GPS
1465 if (feature(FEATURE_GPS)) {
1466 if (blackboxShouldLogGpsHomeFrame()) {
1467 writeGPSHomeFrame();
1468 writeGPSFrame(currentTimeUs);
1469 } else if (gpsSol.numSat != gpsHistory.GPS_numSat
1470 || gpsSol.llh.lat != gpsHistory.GPS_coord[LAT]
1471 || gpsSol.llh.lon != gpsHistory.GPS_coord[LON]) {
1472 //We could check for velocity changes as well but I doubt it changes independent of position
1473 writeGPSFrame(currentTimeUs);
1476 #endif
1479 //Flush every iteration so that our runtime variance is minimized
1480 blackboxDeviceFlush();
1484 * Call each flight loop iteration to perform blackbox logging.
1486 void blackboxUpdate(timeUs_t currentTimeUs)
1488 switch (blackboxState) {
1489 case BLACKBOX_STATE_STOPPED:
1490 if (ARMING_FLAG(ARMED)) {
1491 blackboxOpen();
1492 blackboxStart();
1494 #ifdef USE_FLASHFS
1495 if (IS_RC_MODE_ACTIVE(BOXBLACKBOXERASE)) {
1496 blackboxSetState(BLACKBOX_STATE_START_ERASE);
1498 #endif
1499 break;
1500 case BLACKBOX_STATE_PREPARE_LOG_FILE:
1501 if (blackboxDeviceBeginLog()) {
1502 blackboxSetState(BLACKBOX_STATE_SEND_HEADER);
1504 break;
1505 case BLACKBOX_STATE_SEND_HEADER:
1506 blackboxReplenishHeaderBudget();
1507 //On entry of this state, xmitState.headerIndex is 0 and startTime is intialised
1510 * Once the UART has had time to init, transmit the header in chunks so we don't overflow its transmit
1511 * buffer, overflow the OpenLog's buffer, or keep the main loop busy for too long.
1513 if (millis() > xmitState.u.startTime + 100) {
1514 if (blackboxDeviceReserveBufferSpace(BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION) == BLACKBOX_RESERVE_SUCCESS) {
1515 for (int i = 0; i < BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION && blackboxHeader[xmitState.headerIndex] != '\0'; i++, xmitState.headerIndex++) {
1516 blackboxWrite(blackboxHeader[xmitState.headerIndex]);
1517 blackboxHeaderBudget--;
1519 if (blackboxHeader[xmitState.headerIndex] == '\0') {
1520 blackboxSetState(BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER);
1524 break;
1525 case BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER:
1526 blackboxReplenishHeaderBudget();
1527 //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
1528 if (!sendFieldDefinition('I', 'P', blackboxMainFields, blackboxMainFields + 1, ARRAYLEN(blackboxMainFields),
1529 &blackboxMainFields[0].condition, &blackboxMainFields[1].condition)) {
1530 #ifdef USE_GPS
1531 if (feature(FEATURE_GPS)) {
1532 blackboxSetState(BLACKBOX_STATE_SEND_GPS_H_HEADER);
1533 } else
1534 #endif
1535 blackboxSetState(BLACKBOX_STATE_SEND_SLOW_HEADER);
1537 break;
1538 #ifdef USE_GPS
1539 case BLACKBOX_STATE_SEND_GPS_H_HEADER:
1540 blackboxReplenishHeaderBudget();
1541 //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
1542 if (!sendFieldDefinition('H', 0, blackboxGpsHFields, blackboxGpsHFields + 1, ARRAYLEN(blackboxGpsHFields),
1543 NULL, NULL)) {
1544 blackboxSetState(BLACKBOX_STATE_SEND_GPS_G_HEADER);
1546 break;
1547 case BLACKBOX_STATE_SEND_GPS_G_HEADER:
1548 blackboxReplenishHeaderBudget();
1549 //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
1550 if (!sendFieldDefinition('G', 0, blackboxGpsGFields, blackboxGpsGFields + 1, ARRAYLEN(blackboxGpsGFields),
1551 &blackboxGpsGFields[0].condition, &blackboxGpsGFields[1].condition)) {
1552 blackboxSetState(BLACKBOX_STATE_SEND_SLOW_HEADER);
1554 break;
1555 #endif
1556 case BLACKBOX_STATE_SEND_SLOW_HEADER:
1557 blackboxReplenishHeaderBudget();
1558 //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
1559 if (!sendFieldDefinition('S', 0, blackboxSlowFields, blackboxSlowFields + 1, ARRAYLEN(blackboxSlowFields),
1560 NULL, NULL)) {
1561 blackboxSetState(BLACKBOX_STATE_SEND_SYSINFO);
1563 break;
1564 case BLACKBOX_STATE_SEND_SYSINFO:
1565 blackboxReplenishHeaderBudget();
1566 //On entry of this state, xmitState.headerIndex is 0
1568 //Keep writing chunks of the system info headers until it returns true to signal completion
1569 if (blackboxWriteSysinfo()) {
1571 * Wait for header buffers to drain completely before data logging begins to ensure reliable header delivery
1572 * (overflowing circular buffers causes all data to be discarded, so the first few logged iterations
1573 * could wipe out the end of the header if we weren't careful)
1575 if (blackboxDeviceFlushForce()) {
1576 blackboxSetState(BLACKBOX_STATE_RUNNING);
1579 break;
1580 case BLACKBOX_STATE_PAUSED:
1581 // Only allow resume to occur during an I-frame iteration, so that we have an "I" base to work from
1582 if (IS_RC_MODE_ACTIVE(BOXBLACKBOX) && blackboxShouldLogIFrame()) {
1583 // Write a log entry so the decoder is aware that our large time/iteration skip is intended
1584 flightLogEvent_loggingResume_t resume;
1586 resume.logIteration = blackboxIteration;
1587 resume.currentTime = currentTimeUs;
1589 blackboxLogEvent(FLIGHT_LOG_EVENT_LOGGING_RESUME, (flightLogEventData_t *) &resume);
1590 blackboxSetState(BLACKBOX_STATE_RUNNING);
1592 blackboxLogIteration(currentTimeUs);
1594 // Keep the logging timers ticking so our log iteration continues to advance
1595 blackboxAdvanceIterationTimers();
1596 break;
1597 case BLACKBOX_STATE_RUNNING:
1598 // On entry to this state, blackboxIteration, blackboxPFrameIndex and blackboxIFrameIndex are reset to 0
1599 // Prevent the Pausing of the log on the mode switch if in Motor Test Mode
1600 if (blackboxModeActivationConditionPresent && !IS_RC_MODE_ACTIVE(BOXBLACKBOX) && !startedLoggingInTestMode) {
1601 blackboxSetState(BLACKBOX_STATE_PAUSED);
1602 } else {
1603 blackboxLogIteration(currentTimeUs);
1605 blackboxAdvanceIterationTimers();
1606 break;
1607 case BLACKBOX_STATE_SHUTTING_DOWN:
1608 //On entry of this state, startTime is set
1610 * Wait for the log we've transmitted to make its way to the logger before we release the serial port,
1611 * since releasing the port clears the Tx buffer.
1613 * Don't wait longer than it could possibly take if something funky happens.
1615 if (blackboxDeviceEndLog(blackboxLoggedAnyFrames) && (millis() > xmitState.u.startTime + BLACKBOX_SHUTDOWN_TIMEOUT_MILLIS || blackboxDeviceFlushForce())) {
1616 blackboxDeviceClose();
1617 blackboxSetState(BLACKBOX_STATE_STOPPED);
1619 break;
1620 #ifdef USE_FLASHFS
1621 case BLACKBOX_STATE_START_ERASE:
1622 blackboxEraseAll();
1623 blackboxSetState(BLACKBOX_STATE_ERASING);
1624 beeper(BEEPER_BLACKBOX_ERASE);
1625 break;
1626 case BLACKBOX_STATE_ERASING:
1627 if (isBlackboxErased()) {
1628 //Done erasing
1629 blackboxSetState(BLACKBOX_STATE_ERASED);
1630 beeper(BEEPER_BLACKBOX_ERASE);
1632 break;
1633 case BLACKBOX_STATE_ERASED:
1634 if (!IS_RC_MODE_ACTIVE(BOXBLACKBOXERASE)) {
1635 blackboxSetState(BLACKBOX_STATE_STOPPED);
1637 break;
1638 #endif
1639 default:
1640 break;
1643 // Did we run out of room on the device? Stop!
1644 if (isBlackboxDeviceFull()) {
1645 #ifdef USE_FLASHFS
1646 if (blackboxState != BLACKBOX_STATE_ERASING
1647 && blackboxState != BLACKBOX_STATE_START_ERASE
1648 && blackboxState != BLACKBOX_STATE_ERASED) {
1649 #endif
1650 blackboxSetState(BLACKBOX_STATE_STOPPED);
1651 // ensure we reset the test mode flag if we stop due to full memory card
1652 if (startedLoggingInTestMode) {
1653 startedLoggingInTestMode = false;
1655 #ifdef USE_FLASHFS
1657 #endif
1658 } else { // Only log in test mode if there is room!
1659 switch (blackboxConfig()->mode) {
1660 case BLACKBOX_MODE_MOTOR_TEST:
1661 // Handle Motor Test Mode
1662 if (inMotorTestMode()) {
1663 if (blackboxState==BLACKBOX_STATE_STOPPED) {
1664 startInTestMode();
1666 } else {
1667 if (blackboxState!=BLACKBOX_STATE_STOPPED) {
1668 stopInTestMode();
1672 break;
1673 case BLACKBOX_MODE_ALWAYS_ON:
1674 if (blackboxState==BLACKBOX_STATE_STOPPED) {
1675 startInTestMode();
1678 break;
1679 case BLACKBOX_MODE_NORMAL:
1680 default:
1682 break;
1687 int blackboxCalculatePDenom(int rateNum, int rateDenom)
1689 return blackboxIInterval * rateNum / rateDenom;
1692 uint8_t blackboxGetRateNum(void)
1694 return blackboxGetRateDenom() * blackboxConfig()->p_denom / blackboxIInterval;
1697 uint8_t blackboxGetRateDenom(void)
1699 return gcd(blackboxIInterval, blackboxPInterval);
1703 * Call during system startup to initialize the blackbox.
1705 void blackboxInit(void)
1707 blackboxResetIterationTimers();
1709 // an I-frame is written every 32ms
1710 // gyro.targetLooptime is 1000 for 1kHz loop, 500 for 2kHz loop etc, gyro.targetLooptime is rounded for short looptimes
1711 if (gyro.targetLooptime == 31) { // rounded from 31.25us
1712 blackboxIInterval = 1024;
1713 } else if (gyro.targetLooptime == 63) { // rounded from 62.5us
1714 blackboxIInterval = 512;
1715 } else {
1716 blackboxIInterval = (uint16_t)(32 * 1000 / gyro.targetLooptime);
1718 // by default p_denom is 32 and a P-frame is written every 1ms
1719 // if p_denom is zero then no P-frames are logged
1720 if (blackboxConfig()->p_denom == 0) {
1721 blackboxPInterval = 0; // blackboxPInterval not used when p_denom is zero, so just set it to zero
1722 } else if (blackboxConfig()->p_denom > blackboxIInterval && blackboxIInterval >= 32) {
1723 blackboxPInterval = 1;
1724 } else {
1725 blackboxPInterval = blackboxIInterval / blackboxConfig()->p_denom;
1727 if (blackboxConfig()->device) {
1728 blackboxSetState(BLACKBOX_STATE_STOPPED);
1729 } else {
1730 blackboxSetState(BLACKBOX_STATE_DISABLED);
1732 blackboxSInterval = blackboxIInterval * 256; // S-frame is written every 256*32 = 8192ms, approx every 8 seconds
1734 #endif