2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
31 #include "blackbox_encoding.h"
32 #include "blackbox_fielddefs.h"
33 #include "blackbox_io.h"
35 #include "build/build_config.h"
36 #include "build/debug.h"
37 #include "build/version.h"
39 #include "common/axis.h"
40 #include "common/encoding.h"
41 #include "common/maths.h"
42 #include "common/time.h"
43 #include "common/utils.h"
45 #include "config/config.h"
46 #include "config/feature.h"
48 #include "drivers/compass/compass.h"
49 #include "drivers/sensor.h"
50 #include "drivers/time.h"
52 #include "fc/board_info.h"
53 #include "fc/controlrate_profile.h"
54 #include "fc/parameter_names.h"
56 #include "fc/rc_controls.h"
57 #include "fc/rc_modes.h"
58 #include "fc/runtime_config.h"
60 #include "flight/failsafe.h"
61 #include "flight/mixer.h"
62 #include "flight/pid.h"
63 #include "flight/rpm_filter.h"
64 #include "flight/servos.h"
66 #include "io/beeper.h"
68 #include "io/serial.h"
71 #include "pg/pg_ids.h"
77 #include "sensors/acceleration.h"
78 #include "sensors/barometer.h"
79 #include "sensors/battery.h"
80 #include "sensors/compass.h"
81 #include "sensors/gyro.h"
82 #include "sensors/rangefinder.h"
84 #if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
85 #define DEFAULT_BLACKBOX_DEVICE BLACKBOX_DEVICE_FLASH
86 #elif defined(ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT)
87 #define DEFAULT_BLACKBOX_DEVICE BLACKBOX_DEVICE_SDCARD
89 #define DEFAULT_BLACKBOX_DEVICE BLACKBOX_DEVICE_SERIAL
92 PG_REGISTER_WITH_RESET_TEMPLATE(blackboxConfig_t
, blackboxConfig
, PG_BLACKBOX_CONFIG
, 2);
94 PG_RESET_TEMPLATE(blackboxConfig_t
, blackboxConfig
,
95 .sample_rate
= BLACKBOX_RATE_QUARTER
,
96 .device
= DEFAULT_BLACKBOX_DEVICE
,
97 .fields_disabled_mask
= 0, // default log all fields
98 .mode
= BLACKBOX_MODE_NORMAL
101 STATIC_ASSERT((sizeof(blackboxConfig()->fields_disabled_mask
) * 8) >= FLIGHT_LOG_FIELD_SELECT_COUNT
, too_many_flight_log_fields_selections
);
103 #define BLACKBOX_SHUTDOWN_TIMEOUT_MILLIS 200
105 // Some macros to make writing FLIGHT_LOG_FIELD_* constants shorter:
107 #define PREDICT(x) CONCAT(FLIGHT_LOG_FIELD_PREDICTOR_, x)
108 #define ENCODING(x) CONCAT(FLIGHT_LOG_FIELD_ENCODING_, x)
109 #define CONDITION(x) CONCAT(FLIGHT_LOG_FIELD_CONDITION_, x)
110 #define FIELD_SELECT(x) CONCAT(FLIGHT_LOG_FIELD_SELECT_, x)
111 #define UNSIGNED FLIGHT_LOG_FIELD_UNSIGNED
112 #define SIGNED FLIGHT_LOG_FIELD_SIGNED
114 static const char blackboxHeader
[] =
115 "H Product:Blackbox flight data recorder by Nicholas Sherlock\n"
116 "H Data version:2\n";
118 static const char* const blackboxFieldHeaderNames
[] = {
127 /* All field definition structs should look like this (but with longer arrs): */
128 typedef struct blackboxFieldDefinition_s
{
130 // If the field name has a number to be included in square brackets [1] afterwards, set it here, or -1 for no brackets:
131 int8_t fieldNameIndex
;
133 // Each member of this array will be the value to print for this field for the given header index
135 } blackboxFieldDefinition_t
;
137 #define BLACKBOX_DELTA_FIELD_HEADER_COUNT ARRAYLEN(blackboxFieldHeaderNames)
138 #define BLACKBOX_SIMPLE_FIELD_HEADER_COUNT (BLACKBOX_DELTA_FIELD_HEADER_COUNT - 2)
139 #define BLACKBOX_CONDITIONAL_FIELD_HEADER_COUNT (BLACKBOX_DELTA_FIELD_HEADER_COUNT - 2)
141 typedef struct blackboxSimpleFieldDefinition_s
{
143 int8_t fieldNameIndex
;
148 } blackboxSimpleFieldDefinition_t
;
150 typedef struct blackboxConditionalFieldDefinition_s
{
152 int8_t fieldNameIndex
;
157 uint8_t condition
; // Decide whether this field should appear in the log
158 } blackboxConditionalFieldDefinition_t
;
160 typedef struct blackboxDeltaFieldDefinition_s
{
162 int8_t fieldNameIndex
;
169 uint8_t condition
; // Decide whether this field should appear in the log
170 } blackboxDeltaFieldDefinition_t
;
173 * Description of the blackbox fields we are writing in our main intra (I) and inter (P) frames. This description is
174 * written into the flight log header so the log can be properly interpreted (but these definitions don't actually cause
175 * the encoding to happen, we have to encode the flight log ourselves in write{Inter|Intra}frame() in a way that matches
176 * the encoding we've promised here).
178 static const blackboxDeltaFieldDefinition_t blackboxMainFields
[] = {
179 /* loopIteration doesn't appear in P frames since it always increments */
180 {"loopIteration",-1, UNSIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(UNSIGNED_VB
), .Ppredict
= PREDICT(INC
), .Pencode
= FLIGHT_LOG_FIELD_ENCODING_NULL
, CONDITION(ALWAYS
)},
181 /* Time advances pretty steadily so the P-frame prediction is a straight line */
182 {"time", -1, UNSIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(UNSIGNED_VB
), .Ppredict
= PREDICT(STRAIGHT_LINE
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(ALWAYS
)},
183 {"axisP", 0, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(PID
)},
184 {"axisP", 1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(PID
)},
185 {"axisP", 2, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(PID
)},
186 /* I terms get special packed encoding in P frames: */
187 {"axisI", 0, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG2_3S32
), CONDITION(PID
)},
188 {"axisI", 1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG2_3S32
), CONDITION(PID
)},
189 {"axisI", 2, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG2_3S32
), CONDITION(PID
)},
190 {"axisD", 0, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(NONZERO_PID_D_0
)},
191 {"axisD", 1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(NONZERO_PID_D_1
)},
192 {"axisD", 2, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(NONZERO_PID_D_2
)},
193 {"axisF", 0, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(PID
)},
194 {"axisF", 1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(PID
)},
195 {"axisF", 2, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(PID
)},
196 /* rcCommands are encoded together as a group in P-frames: */
197 {"rcCommand", 0, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_4S16
), CONDITION(RC_COMMANDS
)},
198 {"rcCommand", 1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_4S16
), CONDITION(RC_COMMANDS
)},
199 {"rcCommand", 2, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_4S16
), CONDITION(RC_COMMANDS
)},
200 {"rcCommand", 3, UNSIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(UNSIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_4S16
), CONDITION(RC_COMMANDS
)},
202 // setpoint - define 4 fields like rcCommand to use the same encoding. setpoint[4] contains the mixer throttle
203 {"setpoint", 0, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_4S16
), CONDITION(SETPOINT
)},
204 {"setpoint", 1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_4S16
), CONDITION(SETPOINT
)},
205 {"setpoint", 2, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_4S16
), CONDITION(SETPOINT
)},
206 {"setpoint", 3, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_4S16
), CONDITION(SETPOINT
)},
208 {"vbatLatest", -1, UNSIGNED
, .Ipredict
= PREDICT(VBATREF
), .Iencode
= ENCODING(NEG_14BIT
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_8SVB
), CONDITION(VBAT
)},
209 {"amperageLatest",-1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_8SVB
), CONDITION(AMPERAGE_ADC
)},
212 {"magADC", 0, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_8SVB
), CONDITION(MAG
)},
213 {"magADC", 1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_8SVB
), CONDITION(MAG
)},
214 {"magADC", 2, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_8SVB
), CONDITION(MAG
)},
217 {"BaroAlt", -1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_8SVB
), CONDITION(BARO
)},
219 #ifdef USE_RANGEFINDER
220 {"surfaceRaw", -1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_8SVB
), CONDITION(RANGEFINDER
)},
222 {"rssi", -1, UNSIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(UNSIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_8SVB
), CONDITION(RSSI
)},
224 /* Gyros and accelerometers base their P-predictions on the average of the previous 2 frames to reduce noise impact */
225 {"gyroADC", 0, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(GYRO
)},
226 {"gyroADC", 1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(GYRO
)},
227 {"gyroADC", 2, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(GYRO
)},
228 {"accSmooth", 0, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(ACC
)},
229 {"accSmooth", 1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(ACC
)},
230 {"accSmooth", 2, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(ACC
)},
231 {"debug", 0, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(DEBUG_LOG
)},
232 {"debug", 1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(DEBUG_LOG
)},
233 {"debug", 2, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(DEBUG_LOG
)},
234 {"debug", 3, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(DEBUG_LOG
)},
235 /* 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): */
236 {"motor", 0, UNSIGNED
, .Ipredict
= PREDICT(MINMOTOR
), .Iencode
= ENCODING(UNSIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(AT_LEAST_MOTORS_1
)},
237 /* Subsequent motors base their I-frame values on the first one, P-frame values on the average of last two frames: */
238 {"motor", 1, UNSIGNED
, .Ipredict
= PREDICT(MOTOR_0
), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(AT_LEAST_MOTORS_2
)},
239 {"motor", 2, UNSIGNED
, .Ipredict
= PREDICT(MOTOR_0
), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(AT_LEAST_MOTORS_3
)},
240 {"motor", 3, UNSIGNED
, .Ipredict
= PREDICT(MOTOR_0
), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(AT_LEAST_MOTORS_4
)},
241 {"motor", 4, UNSIGNED
, .Ipredict
= PREDICT(MOTOR_0
), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(AT_LEAST_MOTORS_5
)},
242 {"motor", 5, UNSIGNED
, .Ipredict
= PREDICT(MOTOR_0
), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(AT_LEAST_MOTORS_6
)},
243 {"motor", 6, UNSIGNED
, .Ipredict
= PREDICT(MOTOR_0
), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(AT_LEAST_MOTORS_7
)},
244 {"motor", 7, UNSIGNED
, .Ipredict
= PREDICT(MOTOR_0
), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(AT_LEAST_MOTORS_8
)},
246 /* Tricopter tail servo */
247 {"servo", 5, UNSIGNED
, .Ipredict
= PREDICT(1500), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(TRICOPTER
)}
251 // GPS position/vel frame
252 static const blackboxConditionalFieldDefinition_t blackboxGpsGFields
[] = {
253 {"time", -1, UNSIGNED
, PREDICT(LAST_MAIN_FRAME_TIME
), ENCODING(UNSIGNED_VB
), CONDITION(NOT_LOGGING_EVERY_FRAME
)},
254 {"GPS_numSat", -1, UNSIGNED
, PREDICT(0), ENCODING(UNSIGNED_VB
), CONDITION(ALWAYS
)},
255 {"GPS_coord", 0, SIGNED
, PREDICT(HOME_COORD
), ENCODING(SIGNED_VB
), CONDITION(ALWAYS
)},
256 {"GPS_coord", 1, SIGNED
, PREDICT(HOME_COORD
), ENCODING(SIGNED_VB
), CONDITION(ALWAYS
)},
257 {"GPS_altitude", -1, UNSIGNED
, PREDICT(0), ENCODING(UNSIGNED_VB
), CONDITION(ALWAYS
)},
258 {"GPS_speed", -1, UNSIGNED
, PREDICT(0), ENCODING(UNSIGNED_VB
), CONDITION(ALWAYS
)},
259 {"GPS_ground_course", -1, UNSIGNED
, PREDICT(0), ENCODING(UNSIGNED_VB
), CONDITION(ALWAYS
)}
263 static const blackboxSimpleFieldDefinition_t blackboxGpsHFields
[] = {
264 {"GPS_home", 0, SIGNED
, PREDICT(0), ENCODING(SIGNED_VB
)},
265 {"GPS_home", 1, SIGNED
, PREDICT(0), ENCODING(SIGNED_VB
)}
269 // Rarely-updated fields
270 static const blackboxSimpleFieldDefinition_t blackboxSlowFields
[] = {
271 {"flightModeFlags", -1, UNSIGNED
, PREDICT(0), ENCODING(UNSIGNED_VB
)},
272 {"stateFlags", -1, UNSIGNED
, PREDICT(0), ENCODING(UNSIGNED_VB
)},
274 {"failsafePhase", -1, UNSIGNED
, PREDICT(0), ENCODING(TAG2_3S32
)},
275 {"rxSignalReceived", -1, UNSIGNED
, PREDICT(0), ENCODING(TAG2_3S32
)},
276 {"rxFlightChannelsValid", -1, UNSIGNED
, PREDICT(0), ENCODING(TAG2_3S32
)}
279 typedef enum BlackboxState
{
280 BLACKBOX_STATE_DISABLED
= 0,
281 BLACKBOX_STATE_STOPPED
,
282 BLACKBOX_STATE_PREPARE_LOG_FILE
,
283 BLACKBOX_STATE_SEND_HEADER
,
284 BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER
,
285 BLACKBOX_STATE_SEND_GPS_H_HEADER
,
286 BLACKBOX_STATE_SEND_GPS_G_HEADER
,
287 BLACKBOX_STATE_SEND_SLOW_HEADER
,
288 BLACKBOX_STATE_SEND_SYSINFO
,
289 BLACKBOX_STATE_CACHE_FLUSH
,
290 BLACKBOX_STATE_PAUSED
,
291 BLACKBOX_STATE_RUNNING
,
292 BLACKBOX_STATE_SHUTTING_DOWN
,
293 BLACKBOX_STATE_START_ERASE
,
294 BLACKBOX_STATE_ERASING
,
295 BLACKBOX_STATE_ERASED
299 typedef struct blackboxMainState_s
{
302 int32_t axisPID_P
[XYZ_AXIS_COUNT
];
303 int32_t axisPID_I
[XYZ_AXIS_COUNT
];
304 int32_t axisPID_D
[XYZ_AXIS_COUNT
];
305 int32_t axisPID_F
[XYZ_AXIS_COUNT
];
307 int16_t rcCommand
[4];
309 int16_t gyroADC
[XYZ_AXIS_COUNT
];
310 int16_t accADC
[XYZ_AXIS_COUNT
];
311 int16_t debug
[DEBUG16_VALUE_COUNT
];
312 int16_t motor
[MAX_SUPPORTED_MOTORS
];
313 int16_t servo
[MAX_SUPPORTED_SERVOS
];
316 int32_t amperageLatest
;
322 int16_t magADC
[XYZ_AXIS_COUNT
];
324 #ifdef USE_RANGEFINDER
328 } blackboxMainState_t
;
330 typedef struct blackboxGpsState_s
{
332 int32_t GPS_coord
[2];
334 } blackboxGpsState_t
;
336 // This data is updated really infrequently:
337 typedef struct blackboxSlowState_s
{
338 uint32_t flightModeFlags
; // extend this data size (from uint16_t)
340 uint8_t failsafePhase
;
341 bool rxSignalReceived
;
342 bool rxFlightChannelsValid
;
343 } __attribute__((__packed__
)) blackboxSlowState_t
; // We pack this struct so that padding doesn't interfere with memcmp()
346 extern boxBitmask_t rcModeActivationMask
;
348 static BlackboxState blackboxState
= BLACKBOX_STATE_DISABLED
;
350 static uint32_t blackboxLastArmingBeep
= 0;
351 static uint32_t blackboxLastFlightModeFlags
= 0; // New event tracking of flight modes
354 uint32_t headerIndex
;
356 /* Since these fields are used during different blackbox states (never simultaneously) we can
357 * overlap them to save on RAM
365 // Cache for FLIGHT_LOG_FIELD_CONDITION_* test results:
366 static uint32_t blackboxConditionCache
;
368 STATIC_ASSERT((sizeof(blackboxConditionCache
) * 8) >= FLIGHT_LOG_FIELD_CONDITION_LAST
, too_many_flight_log_conditions
);
370 static uint32_t blackboxIteration
;
371 static uint16_t blackboxLoopIndex
;
372 static uint16_t blackboxPFrameIndex
;
373 static uint16_t blackboxIFrameIndex
;
374 // number of flight loop iterations before logging I-frame
375 // typically 32 for 1kHz loop, 64 for 2kHz loop etc
376 STATIC_UNIT_TESTED
int16_t blackboxIInterval
= 0;
377 // number of flight loop iterations before logging P-frame
378 STATIC_UNIT_TESTED
int8_t blackboxPInterval
= 0;
379 STATIC_UNIT_TESTED
int32_t blackboxSInterval
= 0;
380 STATIC_UNIT_TESTED
int32_t blackboxSlowFrameIterationTimer
;
381 static bool blackboxLoggedAnyFrames
;
384 * We store voltages in I-frames relative to this, which was the voltage when the blackbox was activated.
385 * This helps out since the voltage is only expected to fall from that point and we can reduce our diffs
388 static uint16_t vbatReference
;
390 static blackboxGpsState_t gpsHistory
;
391 static blackboxSlowState_t slowHistory
;
393 // Keep a history of length 2, plus a buffer for MW to store the new values into
394 static blackboxMainState_t blackboxHistoryRing
[3];
396 // These point into blackboxHistoryRing, use them to know where to store history of a given age (0, 1 or 2 generations old)
397 static blackboxMainState_t
* blackboxHistory
[3];
399 static bool blackboxModeActivationConditionPresent
= false;
402 * Return true if it is safe to edit the Blackbox configuration.
404 bool blackboxMayEditConfig(void)
406 return blackboxState
<= BLACKBOX_STATE_STOPPED
;
409 static bool blackboxIsOnlyLoggingIntraframes(void)
411 return blackboxPInterval
== 0;
414 static bool isFieldEnabled(FlightLogFieldSelect_e field
)
416 return (blackboxConfig()->fields_disabled_mask
& (1 << field
)) == 0;
419 static bool testBlackboxConditionUncached(FlightLogFieldCondition condition
)
422 case CONDITION(ALWAYS
):
425 case CONDITION(AT_LEAST_MOTORS_1
):
426 case CONDITION(AT_LEAST_MOTORS_2
):
427 case CONDITION(AT_LEAST_MOTORS_3
):
428 case CONDITION(AT_LEAST_MOTORS_4
):
429 case CONDITION(AT_LEAST_MOTORS_5
):
430 case CONDITION(AT_LEAST_MOTORS_6
):
431 case CONDITION(AT_LEAST_MOTORS_7
):
432 case CONDITION(AT_LEAST_MOTORS_8
):
433 return (getMotorCount() >= condition
- FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1
+ 1) && isFieldEnabled(FIELD_SELECT(MOTOR
));
435 case CONDITION(TRICOPTER
):
436 return (mixerConfig()->mixerMode
== MIXER_TRI
|| mixerConfig()->mixerMode
== MIXER_CUSTOM_TRI
) && isFieldEnabled(FIELD_SELECT(MOTOR
));
439 return isFieldEnabled(FIELD_SELECT(PID
));
441 case CONDITION(NONZERO_PID_D_0
):
442 case CONDITION(NONZERO_PID_D_1
):
443 case CONDITION(NONZERO_PID_D_2
):
444 return (currentPidProfile
->pid
[condition
- FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0
].D
!= 0) && isFieldEnabled(FIELD_SELECT(PID
));
446 case CONDITION(RC_COMMANDS
):
447 return isFieldEnabled(FIELD_SELECT(RC_COMMANDS
));
449 case CONDITION(SETPOINT
):
450 return isFieldEnabled(FIELD_SELECT(SETPOINT
));
454 return sensors(SENSOR_MAG
) && isFieldEnabled(FIELD_SELECT(MAG
));
459 case CONDITION(BARO
):
461 return sensors(SENSOR_BARO
) && isFieldEnabled(FIELD_SELECT(ALTITUDE
));
466 case CONDITION(VBAT
):
467 return (batteryConfig()->voltageMeterSource
!= VOLTAGE_METER_NONE
) && isFieldEnabled(FIELD_SELECT(BATTERY
));
469 case CONDITION(AMPERAGE_ADC
):
470 return (batteryConfig()->currentMeterSource
!= CURRENT_METER_NONE
) && (batteryConfig()->currentMeterSource
!= CURRENT_METER_VIRTUAL
) && isFieldEnabled(FIELD_SELECT(BATTERY
));
472 case CONDITION(RANGEFINDER
):
473 #ifdef USE_RANGEFINDER
474 return sensors(SENSOR_RANGEFINDER
) && isFieldEnabled(FIELD_SELECT(ALTITUDE
));
479 case CONDITION(RSSI
):
480 return isRssiConfigured() && isFieldEnabled(FIELD_SELECT(RSSI
));
482 case FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME
:
483 return blackboxPInterval
!= blackboxIInterval
;
485 case CONDITION(GYRO
):
486 return isFieldEnabled(FIELD_SELECT(GYRO
));
489 return sensors(SENSOR_ACC
) && isFieldEnabled(FIELD_SELECT(ACC
));
491 case CONDITION(DEBUG_LOG
):
492 return (debugMode
!= DEBUG_NONE
) && isFieldEnabled(FIELD_SELECT(DEBUG_LOG
));
494 case CONDITION(NEVER
):
502 static void blackboxBuildConditionCache(void)
504 blackboxConditionCache
= 0;
505 for (FlightLogFieldCondition cond
= FLIGHT_LOG_FIELD_CONDITION_FIRST
; cond
<= FLIGHT_LOG_FIELD_CONDITION_LAST
; cond
++) {
506 if (testBlackboxConditionUncached(cond
)) {
507 blackboxConditionCache
|= 1 << cond
;
512 static bool testBlackboxCondition(FlightLogFieldCondition condition
)
514 return (blackboxConditionCache
& (1 << condition
)) != 0;
517 static void blackboxSetState(BlackboxState newState
)
519 //Perform initial setup required for the new state
521 case BLACKBOX_STATE_PREPARE_LOG_FILE
:
522 blackboxLoggedAnyFrames
= false;
524 case BLACKBOX_STATE_SEND_HEADER
:
525 blackboxHeaderBudget
= 0;
526 xmitState
.headerIndex
= 0;
527 xmitState
.u
.startTime
= millis();
529 case BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER
:
530 case BLACKBOX_STATE_SEND_GPS_G_HEADER
:
531 case BLACKBOX_STATE_SEND_GPS_H_HEADER
:
532 case BLACKBOX_STATE_SEND_SLOW_HEADER
:
533 xmitState
.headerIndex
= 0;
534 xmitState
.u
.fieldIndex
= -1;
536 case BLACKBOX_STATE_SEND_SYSINFO
:
537 xmitState
.headerIndex
= 0;
539 case BLACKBOX_STATE_RUNNING
:
540 blackboxSlowFrameIterationTimer
= blackboxSInterval
; //Force a slow frame to be written on the first iteration
542 case BLACKBOX_STATE_SHUTTING_DOWN
:
543 xmitState
.u
.startTime
= millis();
548 blackboxState
= newState
;
551 static void writeIntraframe(void)
553 blackboxMainState_t
*blackboxCurrent
= blackboxHistory
[0];
557 blackboxWriteUnsignedVB(blackboxIteration
);
558 blackboxWriteUnsignedVB(blackboxCurrent
->time
);
560 if (testBlackboxCondition(CONDITION(PID
))) {
561 blackboxWriteSignedVBArray(blackboxCurrent
->axisPID_P
, XYZ_AXIS_COUNT
);
562 blackboxWriteSignedVBArray(blackboxCurrent
->axisPID_I
, XYZ_AXIS_COUNT
);
564 // Don't bother writing the current D term if the corresponding PID setting is zero
565 for (int x
= 0; x
< XYZ_AXIS_COUNT
; x
++) {
566 if (testBlackboxCondition(CONDITION(NONZERO_PID_D_0
) + x
)) {
567 blackboxWriteSignedVB(blackboxCurrent
->axisPID_D
[x
]);
571 blackboxWriteSignedVBArray(blackboxCurrent
->axisPID_F
, XYZ_AXIS_COUNT
);
574 if (testBlackboxCondition(CONDITION(RC_COMMANDS
))) {
575 // Write roll, pitch and yaw first:
576 blackboxWriteSigned16VBArray(blackboxCurrent
->rcCommand
, 3);
579 * Write the throttle separately from the rest of the RC data as it's unsigned.
580 * Throttle lies in range [PWM_RANGE_MIN..PWM_RANGE_MAX]:
582 blackboxWriteUnsignedVB(blackboxCurrent
->rcCommand
[THROTTLE
]);
585 if (testBlackboxCondition(CONDITION(SETPOINT
))) {
586 // Write setpoint roll, pitch, yaw, and throttle
587 blackboxWriteSigned16VBArray(blackboxCurrent
->setpoint
, 4);
590 if (testBlackboxCondition(CONDITION(VBAT
))) {
592 * Our voltage is expected to decrease over the course of the flight, so store our difference from
595 * Write 14 bits even if the number is negative (which would otherwise result in 32 bits)
597 blackboxWriteUnsignedVB((vbatReference
- blackboxCurrent
->vbatLatest
) & 0x3FFF);
600 if (testBlackboxCondition(CONDITION(AMPERAGE_ADC
))) {
601 // 12bit value directly from ADC
602 blackboxWriteSignedVB(blackboxCurrent
->amperageLatest
);
606 if (testBlackboxCondition(CONDITION(MAG
))) {
607 blackboxWriteSigned16VBArray(blackboxCurrent
->magADC
, XYZ_AXIS_COUNT
);
612 if (testBlackboxCondition(CONDITION(BARO
))) {
613 blackboxWriteSignedVB(blackboxCurrent
->BaroAlt
);
617 #ifdef USE_RANGEFINDER
618 if (testBlackboxCondition(CONDITION(RANGEFINDER
))) {
619 blackboxWriteSignedVB(blackboxCurrent
->surfaceRaw
);
623 if (testBlackboxCondition(CONDITION(RSSI
))) {
624 blackboxWriteUnsignedVB(blackboxCurrent
->rssi
);
627 if (testBlackboxCondition(CONDITION(GYRO
))) {
628 blackboxWriteSigned16VBArray(blackboxCurrent
->gyroADC
, XYZ_AXIS_COUNT
);
631 if (testBlackboxCondition(CONDITION(ACC
))) {
632 blackboxWriteSigned16VBArray(blackboxCurrent
->accADC
, XYZ_AXIS_COUNT
);
635 if (testBlackboxCondition(CONDITION(DEBUG_LOG
))) {
636 blackboxWriteSigned16VBArray(blackboxCurrent
->debug
, DEBUG16_VALUE_COUNT
);
639 if (isFieldEnabled(FIELD_SELECT(MOTOR
))) {
640 //Motors can be below minimum output when disarmed, but that doesn't happen much
641 blackboxWriteUnsignedVB(blackboxCurrent
->motor
[0] - getMotorOutputLow());
643 //Motors tend to be similar to each other so use the first motor's value as a predictor of the others
644 const int motorCount
= getMotorCount();
645 for (int x
= 1; x
< motorCount
; x
++) {
646 blackboxWriteSignedVB(blackboxCurrent
->motor
[x
] - blackboxCurrent
->motor
[0]);
649 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_TRICOPTER
)) {
650 //Assume the tail spends most of its time around the center
651 blackboxWriteSignedVB(blackboxCurrent
->servo
[5] - 1500);
655 //Rotate our history buffers:
657 //The current state becomes the new "before" state
658 blackboxHistory
[1] = blackboxHistory
[0];
659 //And since we have no other history, we also use it for the "before, before" state
660 blackboxHistory
[2] = blackboxHistory
[0];
661 //And advance the current state over to a blank space ready to be filled
662 blackboxHistory
[0] = ((blackboxHistory
[0] - blackboxHistoryRing
+ 1) % 3) + blackboxHistoryRing
;
664 blackboxLoggedAnyFrames
= true;
667 static void blackboxWriteMainStateArrayUsingAveragePredictor(int arrOffsetInHistory
, int count
)
669 int16_t *curr
= (int16_t*) ((char*) (blackboxHistory
[0]) + arrOffsetInHistory
);
670 int16_t *prev1
= (int16_t*) ((char*) (blackboxHistory
[1]) + arrOffsetInHistory
);
671 int16_t *prev2
= (int16_t*) ((char*) (blackboxHistory
[2]) + arrOffsetInHistory
);
673 for (int i
= 0; i
< count
; i
++) {
674 // Predictor is the average of the previous two history states
675 int32_t predictor
= (prev1
[i
] + prev2
[i
]) / 2;
677 blackboxWriteSignedVB(curr
[i
] - predictor
);
681 static void writeInterframe(void)
683 blackboxMainState_t
*blackboxCurrent
= blackboxHistory
[0];
684 blackboxMainState_t
*blackboxLast
= blackboxHistory
[1];
688 //No need to store iteration count since its delta is always 1
691 * Since the difference between the difference between successive times will be nearly zero (due to consistent
692 * looptime spacing), use second-order differences.
694 blackboxWriteSignedVB((int32_t) (blackboxHistory
[0]->time
- 2 * blackboxHistory
[1]->time
+ blackboxHistory
[2]->time
));
697 int32_t setpointDeltas
[4];
699 if (testBlackboxCondition(CONDITION(PID
))) {
700 arraySubInt32(deltas
, blackboxCurrent
->axisPID_P
, blackboxLast
->axisPID_P
, XYZ_AXIS_COUNT
);
701 blackboxWriteSignedVBArray(deltas
, XYZ_AXIS_COUNT
);
704 * The PID I field changes very slowly, most of the time +-2, so use an encoding
705 * that can pack all three fields into one byte in that situation.
707 arraySubInt32(deltas
, blackboxCurrent
->axisPID_I
, blackboxLast
->axisPID_I
, XYZ_AXIS_COUNT
);
708 blackboxWriteTag2_3S32(deltas
);
711 * The PID D term is frequently set to zero for yaw, which makes the result from the calculation
712 * always zero. So don't bother recording D results when PID D terms are zero.
714 for (int x
= 0; x
< XYZ_AXIS_COUNT
; x
++) {
715 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0
+ x
)) {
716 blackboxWriteSignedVB(blackboxCurrent
->axisPID_D
[x
] - blackboxLast
->axisPID_D
[x
]);
720 arraySubInt32(deltas
, blackboxCurrent
->axisPID_F
, blackboxLast
->axisPID_F
, XYZ_AXIS_COUNT
);
721 blackboxWriteSignedVBArray(deltas
, XYZ_AXIS_COUNT
);
725 * RC tends to stay the same or fairly small for many frames at a time, so use an encoding that
726 * can pack multiple values per byte:
728 for (int x
= 0; x
< 4; x
++) {
729 deltas
[x
] = blackboxCurrent
->rcCommand
[x
] - blackboxLast
->rcCommand
[x
];
730 setpointDeltas
[x
] = blackboxCurrent
->setpoint
[x
] - blackboxLast
->setpoint
[x
];
733 if (testBlackboxCondition(CONDITION(RC_COMMANDS
))) {
734 blackboxWriteTag8_4S16(deltas
);
736 if (testBlackboxCondition(CONDITION(SETPOINT
))) {
737 blackboxWriteTag8_4S16(setpointDeltas
);
740 //Check for sensors that are updated periodically (so deltas are normally zero)
741 int optionalFieldCount
= 0;
743 if (testBlackboxCondition(CONDITION(VBAT
))) {
744 deltas
[optionalFieldCount
++] = (int32_t) blackboxCurrent
->vbatLatest
- blackboxLast
->vbatLatest
;
747 if (testBlackboxCondition(CONDITION(AMPERAGE_ADC
))) {
748 deltas
[optionalFieldCount
++] = blackboxCurrent
->amperageLatest
- blackboxLast
->amperageLatest
;
752 if (testBlackboxCondition(CONDITION(MAG
))) {
753 for (int x
= 0; x
< XYZ_AXIS_COUNT
; x
++) {
754 deltas
[optionalFieldCount
++] = blackboxCurrent
->magADC
[x
] - blackboxLast
->magADC
[x
];
760 if (testBlackboxCondition(CONDITION(BARO
))) {
761 deltas
[optionalFieldCount
++] = blackboxCurrent
->BaroAlt
- blackboxLast
->BaroAlt
;
765 #ifdef USE_RANGEFINDER
766 if (testBlackboxCondition(CONDITION(RANGEFINDER
))) {
767 deltas
[optionalFieldCount
++] = blackboxCurrent
->surfaceRaw
- blackboxLast
->surfaceRaw
;
771 if (testBlackboxCondition(CONDITION(RSSI
))) {
772 deltas
[optionalFieldCount
++] = (int32_t) blackboxCurrent
->rssi
- blackboxLast
->rssi
;
775 blackboxWriteTag8_8SVB(deltas
, optionalFieldCount
);
777 //Since gyros, accs and motors are noisy, base their predictions on the average of the history:
778 if (testBlackboxCondition(CONDITION(GYRO
))) {
779 blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t
, gyroADC
), XYZ_AXIS_COUNT
);
781 if (testBlackboxCondition(CONDITION(ACC
))) {
782 blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t
, accADC
), XYZ_AXIS_COUNT
);
784 if (testBlackboxCondition(CONDITION(DEBUG_LOG
))) {
785 blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t
, debug
), DEBUG16_VALUE_COUNT
);
788 if (isFieldEnabled(FIELD_SELECT(MOTOR
))) {
789 blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t
, motor
), getMotorCount());
791 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_TRICOPTER
)) {
792 blackboxWriteSignedVB(blackboxCurrent
->servo
[5] - blackboxLast
->servo
[5]);
796 //Rotate our history buffers
797 blackboxHistory
[2] = blackboxHistory
[1];
798 blackboxHistory
[1] = blackboxHistory
[0];
799 blackboxHistory
[0] = ((blackboxHistory
[0] - blackboxHistoryRing
+ 1) % 3) + blackboxHistoryRing
;
801 blackboxLoggedAnyFrames
= true;
804 /* Write the contents of the global "slowHistory" to the log as an "S" frame. Because this data is logged so
805 * infrequently, delta updates are not reasonable, so we log independent frames. */
806 static void writeSlowFrame(void)
812 blackboxWriteUnsignedVB(slowHistory
.flightModeFlags
);
813 blackboxWriteUnsignedVB(slowHistory
.stateFlags
);
816 * Most of the time these three values will be able to pack into one byte for us:
818 values
[0] = slowHistory
.failsafePhase
;
819 values
[1] = slowHistory
.rxSignalReceived
? 1 : 0;
820 values
[2] = slowHistory
.rxFlightChannelsValid
? 1 : 0;
821 blackboxWriteTag2_3S32(values
);
823 blackboxSlowFrameIterationTimer
= 0;
827 * Load rarely-changing values from the FC into the given structure
829 static void loadSlowState(blackboxSlowState_t
*slow
)
831 memcpy(&slow
->flightModeFlags
, &rcModeActivationMask
, sizeof(slow
->flightModeFlags
)); //was flightModeFlags;
832 slow
->stateFlags
= stateFlags
;
833 slow
->failsafePhase
= failsafePhase();
834 slow
->rxSignalReceived
= rxIsReceivingSignal();
835 slow
->rxFlightChannelsValid
= rxAreFlightChannelsValid();
839 * If the data in the slow frame has changed, log a slow frame.
841 * If allowPeriodicWrite is true, the frame is also logged if it has been more than blackboxSInterval logging iterations
842 * since the field was last logged.
844 STATIC_UNIT_TESTED
bool writeSlowFrameIfNeeded(void)
846 // Write the slow frame peridocially so it can be recovered if we ever lose sync
847 bool shouldWrite
= blackboxSlowFrameIterationTimer
>= blackboxSInterval
;
850 loadSlowState(&slowHistory
);
852 blackboxSlowState_t newSlowState
;
854 loadSlowState(&newSlowState
);
856 // Only write a slow frame if it was different from the previous state
857 if (memcmp(&newSlowState
, &slowHistory
, sizeof(slowHistory
)) != 0) {
858 // Use the new state as our new history
859 memcpy(&slowHistory
, &newSlowState
, sizeof(slowHistory
));
870 void blackboxValidateConfig(void)
872 // If we've chosen an unsupported device, change the device to serial
873 switch (blackboxConfig()->device
) {
875 case BLACKBOX_DEVICE_FLASH
:
878 case BLACKBOX_DEVICE_SDCARD
:
880 case BLACKBOX_DEVICE_SERIAL
:
881 // Device supported, leave the setting alone
885 blackboxConfigMutable()->device
= BLACKBOX_DEVICE_SERIAL
;
889 static void blackboxResetIterationTimers(void)
891 blackboxIteration
= 0;
892 blackboxLoopIndex
= 0;
893 blackboxIFrameIndex
= 0;
894 blackboxPFrameIndex
= 0;
895 blackboxSlowFrameIterationTimer
= 0;
899 * Start Blackbox logging if it is not already running. Intended to be called upon arming.
901 static void blackboxStart(void)
903 blackboxValidateConfig();
905 if (!blackboxDeviceOpen()) {
906 blackboxSetState(BLACKBOX_STATE_DISABLED
);
910 memset(&gpsHistory
, 0, sizeof(gpsHistory
));
912 blackboxHistory
[0] = &blackboxHistoryRing
[0];
913 blackboxHistory
[1] = &blackboxHistoryRing
[1];
914 blackboxHistory
[2] = &blackboxHistoryRing
[2];
916 vbatReference
= getBatteryVoltageLatest();
918 //No need to clear the content of blackboxHistoryRing since our first frame will be an intra which overwrites it
921 * We use conditional tests to decide whether or not certain fields should be logged. Since our headers
922 * must always agree with the logged data, the results of these tests must not change during logging. So
925 blackboxBuildConditionCache();
927 blackboxModeActivationConditionPresent
= isModeActivationConditionPresent(BOXBLACKBOX
);
929 blackboxResetIterationTimers();
932 * Record the beeper's current idea of the last arming beep time, so that we can detect it changing when
933 * it finally plays the beep for this arming event.
935 blackboxLastArmingBeep
= getArmingBeepTimeMicros();
936 memcpy(&blackboxLastFlightModeFlags
, &rcModeActivationMask
, sizeof(blackboxLastFlightModeFlags
)); // record startup status
938 blackboxSetState(BLACKBOX_STATE_PREPARE_LOG_FILE
);
942 * Begin Blackbox shutdown.
944 void blackboxFinish(void)
946 switch (blackboxState
) {
947 case BLACKBOX_STATE_DISABLED
:
948 case BLACKBOX_STATE_STOPPED
:
949 case BLACKBOX_STATE_SHUTTING_DOWN
:
950 // We're already stopped/shutting down
952 case BLACKBOX_STATE_RUNNING
:
953 case BLACKBOX_STATE_PAUSED
:
954 blackboxLogEvent(FLIGHT_LOG_EVENT_LOG_END
, NULL
);
957 blackboxSetState(BLACKBOX_STATE_SHUTTING_DOWN
);
962 * Test Motors Blackbox Logging
964 static bool startedLoggingInTestMode
= false;
966 static void startInTestMode(void)
968 if (!startedLoggingInTestMode
) {
969 if (blackboxConfig()->device
== BLACKBOX_DEVICE_SERIAL
) {
970 serialPort_t
*sharedBlackboxAndMspPort
= findSharedSerialPort(FUNCTION_BLACKBOX
, FUNCTION_MSP
);
971 if (sharedBlackboxAndMspPort
) {
972 return; // When in test mode, we cannot share the MSP and serial logger port!
976 startedLoggingInTestMode
= true;
980 static void stopInTestMode(void)
982 if (startedLoggingInTestMode
) {
984 startedLoggingInTestMode
= false;
988 * We are going to monitor the MSP_SET_MOTOR target variables motor_disarmed[] for values other than minthrottle
989 * on reading a value (i.e. the user is testing the motors), then we enable test mode logging;
990 * we monitor when the values return to minthrottle and start a delay timer (5 seconds); if
991 * the test motors are left at minimum throttle for this delay timer, then we assume we are done testing and
992 * shutdown the logger.
994 * Of course, after the 5 seconds and shutdown of the logger, the system will be re-enabled to allow the
995 * test mode to trigger again; its just that the data will be in a second, third, fourth etc log file.
997 static bool inMotorTestMode(void) {
998 static uint32_t resetTime
= 0;
1000 if (!ARMING_FLAG(ARMED
) && areMotorsRunning()) {
1001 resetTime
= millis() + 5000; // add 5 seconds
1004 // Monitor the duration at minimum
1005 return (millis() < resetTime
);
1011 static void writeGPSHomeFrame(void)
1015 blackboxWriteSignedVB(GPS_home
[0]);
1016 blackboxWriteSignedVB(GPS_home
[1]);
1017 //TODO it'd be great if we could grab the GPS current time and write that too
1019 gpsHistory
.GPS_home
[0] = GPS_home
[0];
1020 gpsHistory
.GPS_home
[1] = GPS_home
[1];
1023 static void writeGPSFrame(timeUs_t currentTimeUs
)
1028 * If we're logging every frame, then a GPS frame always appears just after a frame with the
1029 * currentTime timestamp in the log, so the reader can just use that timestamp for the GPS frame.
1031 * If we're not logging every frame, we need to store the time of this GPS frame.
1033 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME
)) {
1034 // Predict the time of the last frame in the main log
1035 blackboxWriteUnsignedVB(currentTimeUs
- blackboxHistory
[1]->time
);
1038 blackboxWriteUnsignedVB(gpsSol
.numSat
);
1039 blackboxWriteSignedVB(gpsSol
.llh
.lat
- gpsHistory
.GPS_home
[GPS_LATITUDE
]);
1040 blackboxWriteSignedVB(gpsSol
.llh
.lon
- gpsHistory
.GPS_home
[GPS_LONGITUDE
]);
1041 blackboxWriteUnsignedVB(gpsSol
.llh
.altCm
/ 10); // was originally designed to transport meters in int16, but +-3276.7m is a good compromise
1042 blackboxWriteUnsignedVB(gpsSol
.groundSpeed
);
1043 blackboxWriteUnsignedVB(gpsSol
.groundCourse
);
1045 gpsHistory
.GPS_numSat
= gpsSol
.numSat
;
1046 gpsHistory
.GPS_coord
[GPS_LATITUDE
] = gpsSol
.llh
.lat
;
1047 gpsHistory
.GPS_coord
[GPS_LONGITUDE
] = gpsSol
.llh
.lon
;
1052 * Fill the current state of the blackbox using values read from the flight controller
1054 static void loadMainState(timeUs_t currentTimeUs
)
1057 blackboxMainState_t
*blackboxCurrent
= blackboxHistory
[0];
1059 blackboxCurrent
->time
= currentTimeUs
;
1061 for (int i
= 0; i
< XYZ_AXIS_COUNT
; i
++) {
1062 blackboxCurrent
->axisPID_P
[i
] = pidData
[i
].P
;
1063 blackboxCurrent
->axisPID_I
[i
] = pidData
[i
].I
;
1064 blackboxCurrent
->axisPID_D
[i
] = pidData
[i
].D
;
1065 blackboxCurrent
->axisPID_F
[i
] = pidData
[i
].F
;
1066 blackboxCurrent
->gyroADC
[i
] = lrintf(gyro
.gyroADCf
[i
]);
1067 #if defined(USE_ACC)
1068 blackboxCurrent
->accADC
[i
] = lrintf(acc
.accADC
[i
]);
1071 blackboxCurrent
->magADC
[i
] = mag
.magADC
[i
];
1075 for (int i
= 0; i
< 4; i
++) {
1076 blackboxCurrent
->rcCommand
[i
] = lrintf(rcCommand
[i
]);
1079 // log the currentPidSetpoint values applied to the PID controller
1080 for (int i
= 0; i
< XYZ_AXIS_COUNT
; i
++) {
1081 blackboxCurrent
->setpoint
[i
] = lrintf(pidGetPreviousSetpoint(i
));
1083 // log the final throttle value used in the mixer
1084 blackboxCurrent
->setpoint
[3] = lrintf(mixerGetThrottle() * 1000);
1086 for (int i
= 0; i
< DEBUG16_VALUE_COUNT
; i
++) {
1087 blackboxCurrent
->debug
[i
] = debug
[i
];
1090 const int motorCount
= getMotorCount();
1091 for (int i
= 0; i
< motorCount
; i
++) {
1092 blackboxCurrent
->motor
[i
] = lrintf(motor
[i
]);
1095 blackboxCurrent
->vbatLatest
= getBatteryVoltageLatest();
1096 blackboxCurrent
->amperageLatest
= getAmperageLatest();
1099 blackboxCurrent
->BaroAlt
= baro
.BaroAlt
;
1102 #ifdef USE_RANGEFINDER
1103 // Store the raw sonar value without applying tilt correction
1104 blackboxCurrent
->surfaceRaw
= rangefinderGetLatestAltitude();
1107 blackboxCurrent
->rssi
= getRssi();
1110 //Tail servo for tricopters
1111 blackboxCurrent
->servo
[5] = servo
[5];
1114 UNUSED(currentTimeUs
);
1119 * Transmit the header information for the given field definitions. Transmitted header lines look like:
1121 * H Field I name:a,b,c
1122 * H Field I predictor:0,1,2
1124 * For all header types, provide a "mainFrameChar" which is the name for the field and will be used to refer to it in the
1125 * header (e.g. P, I etc). For blackboxDeltaField_t fields, also provide deltaFrameChar, otherwise set this to zero.
1127 * Provide an array 'conditions' of FlightLogFieldCondition enums if you want these conditions to decide whether a field
1128 * should be included or not. Otherwise provide NULL for this parameter and NULL for secondCondition.
1130 * Set xmitState.headerIndex to 0 and xmitState.u.fieldIndex to -1 before calling for the first time.
1132 * secondFieldDefinition and secondCondition element pointers need to be provided in order to compute the stride of the
1133 * fieldDefinition and secondCondition arrays.
1135 * Returns true if there is still header left to transmit (so call again to continue transmission).
1137 static bool sendFieldDefinition(char mainFrameChar
, char deltaFrameChar
, const void *fieldDefinitions
,
1138 const void *secondFieldDefinition
, int fieldCount
, const uint8_t *conditions
, const uint8_t *secondCondition
)
1140 const blackboxFieldDefinition_t
*def
;
1141 unsigned int headerCount
;
1142 static bool needComma
= false;
1143 size_t definitionStride
= (char*) secondFieldDefinition
- (char*) fieldDefinitions
;
1144 size_t conditionsStride
= (char*) secondCondition
- (char*) conditions
;
1146 if (deltaFrameChar
) {
1147 headerCount
= BLACKBOX_DELTA_FIELD_HEADER_COUNT
;
1149 headerCount
= BLACKBOX_SIMPLE_FIELD_HEADER_COUNT
;
1153 * We're chunking up the header data so we don't exceed our datarate. So we'll be called multiple times to transmit
1157 // On our first call we need to print the name of the header and a colon
1158 if (xmitState
.u
.fieldIndex
== -1) {
1159 if (xmitState
.headerIndex
>= headerCount
) {
1160 return false; //Someone probably called us again after we had already completed transmission
1163 uint32_t charsToBeWritten
= strlen("H Field x :") + strlen(blackboxFieldHeaderNames
[xmitState
.headerIndex
]);
1165 if (blackboxDeviceReserveBufferSpace(charsToBeWritten
) != BLACKBOX_RESERVE_SUCCESS
) {
1166 return true; // Try again later
1169 blackboxHeaderBudget
-= blackboxPrintf("H Field %c %s:", xmitState
.headerIndex
>= BLACKBOX_SIMPLE_FIELD_HEADER_COUNT
? deltaFrameChar
: mainFrameChar
, blackboxFieldHeaderNames
[xmitState
.headerIndex
]);
1171 xmitState
.u
.fieldIndex
++;
1175 // The longest we expect an integer to be as a string:
1176 const uint32_t LONGEST_INTEGER_STRLEN
= 2;
1178 for (; xmitState
.u
.fieldIndex
< fieldCount
; xmitState
.u
.fieldIndex
++) {
1179 def
= (const blackboxFieldDefinition_t
*) ((const char*)fieldDefinitions
+ definitionStride
* xmitState
.u
.fieldIndex
);
1181 if (!conditions
|| testBlackboxCondition(conditions
[conditionsStride
* xmitState
.u
.fieldIndex
])) {
1182 // First (over)estimate the length of the string we want to print
1184 int32_t bytesToWrite
= 1; // Leading comma
1186 // The first header is a field name
1187 if (xmitState
.headerIndex
== 0) {
1188 bytesToWrite
+= strlen(def
->name
) + strlen("[]") + LONGEST_INTEGER_STRLEN
;
1190 //The other headers are integers
1191 bytesToWrite
+= LONGEST_INTEGER_STRLEN
;
1194 // Now perform the write if the buffer is large enough
1195 if (blackboxDeviceReserveBufferSpace(bytesToWrite
) != BLACKBOX_RESERVE_SUCCESS
) {
1196 // Ran out of space!
1200 blackboxHeaderBudget
-= bytesToWrite
;
1208 // The first header is a field name
1209 if (xmitState
.headerIndex
== 0) {
1210 blackboxWriteString(def
->name
);
1212 // Do we need to print an index in brackets after the name?
1213 if (def
->fieldNameIndex
!= -1) {
1214 blackboxPrintf("[%d]", def
->fieldNameIndex
);
1217 //The other headers are integers
1218 blackboxPrintf("%d", def
->arr
[xmitState
.headerIndex
- 1]);
1223 // Did we complete this line?
1224 if (xmitState
.u
.fieldIndex
== fieldCount
&& blackboxDeviceReserveBufferSpace(1) == BLACKBOX_RESERVE_SUCCESS
) {
1225 blackboxHeaderBudget
--;
1226 blackboxWrite('\n');
1227 xmitState
.headerIndex
++;
1228 xmitState
.u
.fieldIndex
= -1;
1231 return xmitState
.headerIndex
< headerCount
;
1234 // Buf must be at least FORMATTED_DATE_TIME_BUFSIZE
1235 STATIC_UNIT_TESTED
char *blackboxGetStartDateTime(char *buf
)
1239 // rtcGetDateTime will fill dt with 0000-01-01T00:00:00
1240 // when time is not known.
1241 rtcGetDateTime(&dt
);
1242 dateTimeFormatLocal(buf
, &dt
);
1244 buf
= "0000-01-01T00:00:00.000";
1250 #ifndef BLACKBOX_PRINT_HEADER_LINE
1251 #define BLACKBOX_PRINT_HEADER_LINE(name, format, ...) case __COUNTER__: \
1252 blackboxPrintfHeaderLine(name, format, __VA_ARGS__); \
1254 #define BLACKBOX_PRINT_HEADER_LINE_CUSTOM(...) case __COUNTER__: \
1260 * Transmit a portion of the system information headers. Call the first time with xmitState.headerIndex == 0. Returns
1261 * true iff transmission is complete, otherwise call again later to continue transmission.
1263 static bool blackboxWriteSysinfo(void)
1266 const uint16_t motorOutputLowInt
= lrintf(getMotorOutputLow());
1267 const uint16_t motorOutputHighInt
= lrintf(getMotorOutputHigh());
1269 // Make sure we have enough room in the buffer for our longest line (as of this writing, the "Firmware date" line)
1270 if (blackboxDeviceReserveBufferSpace(64) != BLACKBOX_RESERVE_SUCCESS
) {
1274 char buf
[FORMATTED_DATE_TIME_BUFSIZE
];
1276 #ifdef USE_RC_SMOOTHING_FILTER
1277 rcSmoothingFilter_t
*rcSmoothingData
= getRcSmoothingData();
1280 const controlRateConfig_t
*currentControlRateProfile
= controlRateProfiles(systemConfig()->activeRateProfile
);
1281 switch (xmitState
.headerIndex
) {
1282 BLACKBOX_PRINT_HEADER_LINE("Firmware type", "%s", "Cleanflight");
1283 BLACKBOX_PRINT_HEADER_LINE("Firmware revision", "%s %s (%s) %s", FC_FIRMWARE_NAME
, FC_VERSION_STRING
, shortGitRevision
, targetName
);
1284 BLACKBOX_PRINT_HEADER_LINE("Firmware date", "%s %s", buildDate
, buildTime
);
1285 #ifdef USE_BOARD_INFO
1286 BLACKBOX_PRINT_HEADER_LINE("Board information", "%s %s", getManufacturerId(), getBoardName());
1288 BLACKBOX_PRINT_HEADER_LINE("Log start datetime", "%s", blackboxGetStartDateTime(buf
));
1289 BLACKBOX_PRINT_HEADER_LINE("Craft name", "%s", pilotConfig()->name
);
1290 BLACKBOX_PRINT_HEADER_LINE("I interval", "%d", blackboxIInterval
);
1291 BLACKBOX_PRINT_HEADER_LINE("P interval", "%d", blackboxPInterval
);
1292 BLACKBOX_PRINT_HEADER_LINE("P ratio", "%d", (uint16_t)(blackboxIInterval
/ blackboxPInterval
));
1293 BLACKBOX_PRINT_HEADER_LINE("minthrottle", "%d", motorConfig()->minthrottle
);
1294 BLACKBOX_PRINT_HEADER_LINE("maxthrottle", "%d", motorConfig()->maxthrottle
);
1295 BLACKBOX_PRINT_HEADER_LINE("gyro_scale","0x%x", castFloatBytesToInt(1.0f
));
1296 BLACKBOX_PRINT_HEADER_LINE("motorOutput", "%d,%d", motorOutputLowInt
, motorOutputHighInt
);
1297 #if defined(USE_ACC)
1298 BLACKBOX_PRINT_HEADER_LINE("acc_1G", "%u", acc
.dev
.acc_1G
);
1301 BLACKBOX_PRINT_HEADER_LINE_CUSTOM(
1302 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT
)) {
1303 blackboxPrintfHeaderLine("vbat_scale", "%u", voltageSensorADCConfig(VOLTAGE_SENSOR_ADC_VBAT
)->vbatscale
);
1305 xmitState
.headerIndex
+= 2; // Skip the next two vbat fields too
1309 BLACKBOX_PRINT_HEADER_LINE("vbatcellvoltage", "%u,%u,%u", batteryConfig()->vbatmincellvoltage
,
1310 batteryConfig()->vbatwarningcellvoltage
,
1311 batteryConfig()->vbatmaxcellvoltage
);
1312 BLACKBOX_PRINT_HEADER_LINE("vbatref", "%u", vbatReference
);
1314 BLACKBOX_PRINT_HEADER_LINE_CUSTOM(
1315 if (batteryConfig()->currentMeterSource
== CURRENT_METER_ADC
) {
1316 blackboxPrintfHeaderLine("currentSensor", "%d,%d",currentSensorADCConfig()->offset
, currentSensorADCConfig()->scale
);
1320 BLACKBOX_PRINT_HEADER_LINE("looptime", "%d", gyro
.sampleLooptime
);
1321 BLACKBOX_PRINT_HEADER_LINE("gyro_sync_denom", "%d", 1);
1322 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_PID_PROCESS_DENOM
, "%d", activePidLoopDenom
);
1323 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_THR_MID
, "%d", currentControlRateProfile
->thrMid8
);
1324 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_THR_EXPO
, "%d", currentControlRateProfile
->thrExpo8
);
1325 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_TPA_RATE
, "%d", currentControlRateProfile
->tpa_rate
);
1326 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_TPA_BREAKPOINT
, "%d", currentControlRateProfile
->tpa_breakpoint
);
1327 BLACKBOX_PRINT_HEADER_LINE("rc_rates", "%d,%d,%d", currentControlRateProfile
->rcRates
[ROLL
],
1328 currentControlRateProfile
->rcRates
[PITCH
],
1329 currentControlRateProfile
->rcRates
[YAW
]);
1330 BLACKBOX_PRINT_HEADER_LINE("rc_expo", "%d,%d,%d", currentControlRateProfile
->rcExpo
[ROLL
],
1331 currentControlRateProfile
->rcExpo
[PITCH
],
1332 currentControlRateProfile
->rcExpo
[YAW
]);
1333 BLACKBOX_PRINT_HEADER_LINE("rates", "%d,%d,%d", currentControlRateProfile
->rates
[ROLL
],
1334 currentControlRateProfile
->rates
[PITCH
],
1335 currentControlRateProfile
->rates
[YAW
]);
1336 BLACKBOX_PRINT_HEADER_LINE("rate_limits", "%d,%d,%d", currentControlRateProfile
->rate_limit
[ROLL
],
1337 currentControlRateProfile
->rate_limit
[PITCH
],
1338 currentControlRateProfile
->rate_limit
[YAW
]);
1339 BLACKBOX_PRINT_HEADER_LINE("rollPID", "%d,%d,%d", currentPidProfile
->pid
[PID_ROLL
].P
,
1340 currentPidProfile
->pid
[PID_ROLL
].I
,
1341 currentPidProfile
->pid
[PID_ROLL
].D
);
1342 BLACKBOX_PRINT_HEADER_LINE("pitchPID", "%d,%d,%d", currentPidProfile
->pid
[PID_PITCH
].P
,
1343 currentPidProfile
->pid
[PID_PITCH
].I
,
1344 currentPidProfile
->pid
[PID_PITCH
].D
);
1345 BLACKBOX_PRINT_HEADER_LINE("yawPID", "%d,%d,%d", currentPidProfile
->pid
[PID_YAW
].P
,
1346 currentPidProfile
->pid
[PID_YAW
].I
,
1347 currentPidProfile
->pid
[PID_YAW
].D
);
1348 BLACKBOX_PRINT_HEADER_LINE("levelPID", "%d,%d,%d", currentPidProfile
->pid
[PID_LEVEL
].P
,
1349 currentPidProfile
->pid
[PID_LEVEL
].I
,
1350 currentPidProfile
->pid
[PID_LEVEL
].D
);
1351 BLACKBOX_PRINT_HEADER_LINE("magPID", "%d", currentPidProfile
->pid
[PID_MAG
].P
);
1353 BLACKBOX_PRINT_HEADER_LINE("d_min", "%d,%d,%d", currentPidProfile
->d_min
[ROLL
],
1354 currentPidProfile
->d_min
[PITCH
],
1355 currentPidProfile
->d_min
[YAW
]);
1356 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_D_MAX_GAIN
, "%d", currentPidProfile
->d_min_gain
);
1357 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_D_MAX_ADVANCE
, "%d", currentPidProfile
->d_min_advance
);
1359 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DTERM_LPF1_TYPE
, "%d", currentPidProfile
->dterm_lpf1_type
);
1360 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DTERM_LPF1_STATIC_HZ
, "%d", currentPidProfile
->dterm_lpf1_static_hz
);
1362 BLACKBOX_PRINT_HEADER_LINE("dterm_lpf1_dyn_hz", "%d,%d", currentPidProfile
->dterm_lpf1_dyn_min_hz
,
1363 currentPidProfile
->dterm_lpf1_dyn_max_hz
);
1365 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DTERM_LPF2_TYPE
, "%d", currentPidProfile
->dterm_lpf2_type
);
1366 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DTERM_LPF2_STATIC_HZ
, "%d", currentPidProfile
->dterm_lpf2_static_hz
);
1367 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_YAW_LOWPASS_HZ
, "%d", currentPidProfile
->yaw_lowpass_hz
);
1368 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DTERM_NOTCH_HZ
, "%d", currentPidProfile
->dterm_notch_hz
);
1369 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DTERM_NOTCH_CUTOFF
, "%d", currentPidProfile
->dterm_notch_cutoff
);
1370 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ITERM_WINDUP
, "%d", currentPidProfile
->itermWindupPointPercent
);
1371 #if defined(USE_ITERM_RELAX)
1372 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ITERM_RELAX
, "%d", currentPidProfile
->iterm_relax
);
1373 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ITERM_RELAX_TYPE
, "%d", currentPidProfile
->iterm_relax_type
);
1374 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ITERM_RELAX_CUTOFF
, "%d", currentPidProfile
->iterm_relax_cutoff
);
1376 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_PID_AT_MIN_THROTTLE
, "%d", currentPidProfile
->pidAtMinThrottle
);
1378 // Betaflight PID controller parameters
1379 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ANTI_GRAVITY_MODE
, "%d", currentPidProfile
->antiGravityMode
);
1380 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ANTI_GRAVITY_THRESHOLD
, "%d", currentPidProfile
->itermThrottleThreshold
);
1381 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ANTI_GRAVITY_GAIN
, "%d", currentPidProfile
->itermAcceleratorGain
);
1382 #ifdef USE_ABSOLUTE_CONTROL
1383 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ABS_CONTROL_GAIN
, "%d", currentPidProfile
->abs_control_gain
);
1385 #ifdef USE_INTEGRATED_YAW_CONTROL
1386 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_USE_INTEGRATED_YAW
, "%d", currentPidProfile
->use_integrated_yaw
);
1388 BLACKBOX_PRINT_HEADER_LINE("ff_weight", "%d,%d,%d", currentPidProfile
->pid
[PID_ROLL
].F
,
1389 currentPidProfile
->pid
[PID_PITCH
].F
,
1390 currentPidProfile
->pid
[PID_YAW
].F
);
1391 #ifdef USE_FEEDFORWARD
1392 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_FEEDFORWARD_TRANSITION
, "%d", currentPidProfile
->feedforward_transition
);
1393 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_FEEDFORWARD_AVERAGING
, "%d", currentPidProfile
->feedforward_averaging
);
1394 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_FEEDFORWARD_SMOOTH_FACTOR
, "%d", currentPidProfile
->feedforward_smooth_factor
);
1395 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_FEEDFORWARD_JITTER_FACTOR
, "%d", currentPidProfile
->feedforward_jitter_factor
);
1396 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_FEEDFORWARD_BOOST
, "%d", currentPidProfile
->feedforward_boost
);
1397 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_FEEDFORWARD_MAX_RATE_LIMIT
, "%d", currentPidProfile
->feedforward_max_rate_limit
);
1400 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ACC_LIMIT_YAW
, "%d", currentPidProfile
->yawRateAccelLimit
);
1401 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ACC_LIMIT
, "%d", currentPidProfile
->rateAccelLimit
);
1402 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_PIDSUM_LIMIT
, "%d", currentPidProfile
->pidSumLimit
);
1403 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_PIDSUM_LIMIT_YAW
, "%d", currentPidProfile
->pidSumLimitYaw
);
1404 // End of Betaflight controller parameters
1406 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DEADBAND
, "%d", rcControlsConfig()->deadband
);
1407 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_YAW_DEADBAND
, "%d", rcControlsConfig()->yaw_deadband
);
1409 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GYRO_HARDWARE_LPF
, "%d", gyroConfig()->gyro_hardware_lpf
);
1410 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GYRO_LPF1_TYPE
, "%d", gyroConfig()->gyro_lpf1_type
);
1411 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GYRO_LPF1_STATIC_HZ
, "%d", gyroConfig()->gyro_lpf1_static_hz
);
1413 BLACKBOX_PRINT_HEADER_LINE("gyro_lpf1_dyn_hz", "%d,%d", gyroConfig()->gyro_lpf1_dyn_min_hz
,
1414 gyroConfig()->gyro_lpf1_dyn_max_hz
);
1416 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GYRO_LPF2_TYPE
, "%d", gyroConfig()->gyro_lpf2_type
);
1417 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GYRO_LPF2_STATIC_HZ
, "%d", gyroConfig()->gyro_lpf2_static_hz
);
1418 BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz", "%d,%d", gyroConfig()->gyro_soft_notch_hz_1
,
1419 gyroConfig()->gyro_soft_notch_hz_2
);
1420 BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff", "%d,%d", gyroConfig()->gyro_soft_notch_cutoff_1
,
1421 gyroConfig()->gyro_soft_notch_cutoff_2
);
1422 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GYRO_TO_USE
, "%d", gyroConfig()->gyro_to_use
);
1423 #ifdef USE_DYN_NOTCH_FILTER
1424 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DYN_NOTCH_MAX_HZ
, "%d", dynNotchConfig()->dyn_notch_max_hz
);
1425 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DYN_NOTCH_COUNT
, "%d", dynNotchConfig()->dyn_notch_count
);
1426 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DYN_NOTCH_Q
, "%d", dynNotchConfig()->dyn_notch_q
);
1427 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DYN_NOTCH_MIN_HZ
, "%d", dynNotchConfig()->dyn_notch_min_hz
);
1429 #ifdef USE_DSHOT_TELEMETRY
1430 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DSHOT_BIDIR
, "%d", motorConfig()->dev
.useDshotTelemetry
);
1431 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_MOTOR_POLES
, "%d", motorConfig()->motorPoleCount
);
1433 #ifdef USE_RPM_FILTER
1434 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_RPM_FILTER_HARMONICS
, "%d", rpmFilterConfig()->rpm_filter_harmonics
);
1435 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_RPM_FILTER_Q
, "%d", rpmFilterConfig()->rpm_filter_q
);
1436 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_RPM_FILTER_MIN_HZ
, "%d", rpmFilterConfig()->rpm_filter_min_hz
);
1437 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_RPM_FILTER_FADE_RANGE_HZ
, "%d", rpmFilterConfig()->rpm_filter_fade_range_hz
);
1438 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_RPM_FILTER_LPF_HZ
, "%d", rpmFilterConfig()->rpm_filter_lpf_hz
);
1440 #if defined(USE_ACC)
1441 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ACC_LPF_HZ
, "%d", (int)(accelerometerConfig()->acc_lpf_hz
* 100.0f
));
1442 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_ACC_HARDWARE
, "%d", accelerometerConfig()->acc_hardware
);
1445 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_BARO_HARDWARE
, "%d", barometerConfig()->baro_hardware
);
1448 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_MAG_HARDWARE
, "%d", compassConfig()->mag_hardware
);
1450 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GYRO_CAL_ON_FIRST_ARM
, "%d", armingConfig()->gyro_cal_on_first_arm
);
1451 BLACKBOX_PRINT_HEADER_LINE("airmode_activate_throttle", "%d", rxConfig()->airModeActivateThreshold
);
1452 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_SERIAL_RX_PROVIDER
, "%d", rxConfig()->serialrx_provider
);
1453 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_USE_UNSYNCED_PWM
, "%d", motorConfig()->dev
.useUnsyncedPwm
);
1454 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_MOTOR_PWM_PROTOCOL
, "%d", motorConfig()->dev
.motorPwmProtocol
);
1455 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_MOTOR_PWM_RATE
, "%d", motorConfig()->dev
.motorPwmRate
);
1456 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DSHOT_IDLE_VALUE
, "%d", motorConfig()->digitalIdleOffsetValue
);
1457 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DEBUG_MODE
, "%d", debugMode
);
1458 BLACKBOX_PRINT_HEADER_LINE("features", "%d", featureConfig()->enabledFeatures
);
1460 #ifdef USE_RC_SMOOTHING_FILTER
1461 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_RC_SMOOTHING
, "%d", rxConfig()->rc_smoothing_mode
);
1462 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_RC_SMOOTHING_AUTO_FACTOR
, "%d", rxConfig()->rc_smoothing_auto_factor_rpy
);
1463 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_RC_SMOOTHING_AUTO_FACTOR_THROTTLE
, "%d", rxConfig()->rc_smoothing_auto_factor_throttle
);
1465 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_RC_SMOOTHING_FEEDFORWARD_CUTOFF
, "%d", rcSmoothingData
->ffCutoffSetting
);
1466 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_RC_SMOOTHING_SETPOINT_CUTOFF
, "%d", rcSmoothingData
->setpointCutoffSetting
);
1467 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_RC_SMOOTHING_THROTTLE_CUTOFF
, "%d", rcSmoothingData
->throttleCutoffSetting
);
1468 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_RC_SMOOTHING_DEBUG_AXIS
, "%d", rcSmoothingData
->debugAxis
);
1469 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_RC_SMOOTHING_ACTIVE_CUTOFFS
, "%d,%d,%d", rcSmoothingData
->feedforwardCutoffFrequency
,
1470 rcSmoothingData
->setpointCutoffFrequency
,
1471 rcSmoothingData
->throttleCutoffFrequency
);
1472 BLACKBOX_PRINT_HEADER_LINE("rc_smoothing_rx_average", "%d", rcSmoothingData
->averageFrameTimeUs
);
1473 #endif // USE_RC_SMOOTHING_FILTER
1474 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_RATES_TYPE
, "%d", currentControlRateProfile
->rates_type
);
1476 BLACKBOX_PRINT_HEADER_LINE("fields_disabled_mask", "%d", blackboxConfig()->fields_disabled_mask
);
1478 #ifdef USE_BATTERY_VOLTAGE_SAG_COMPENSATION
1479 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_VBAT_SAG_COMPENSATION
, "%d", currentPidProfile
->vbat_sag_compensation
);
1482 #if defined(USE_DYN_IDLE)
1483 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DYN_IDLE_MIN_RPM
, "%d", currentPidProfile
->dyn_idle_min_rpm
);
1484 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DYN_IDLE_P_GAIN
, "%d", currentPidProfile
->dyn_idle_p_gain
);
1485 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DYN_IDLE_I_GAIN
, "%d", currentPidProfile
->dyn_idle_i_gain
);
1486 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DYN_IDLE_D_GAIN
, "%d", currentPidProfile
->dyn_idle_d_gain
);
1487 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_DYN_IDLE_MAX_INCREASE
, "%d", currentPidProfile
->dyn_idle_max_increase
);
1490 #ifdef USE_SIMPLIFIED_TUNING
1491 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_SIMPLIFIED_PIDS_MODE
, "%d", currentPidProfile
->simplified_pids_mode
);
1492 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_SIMPLIFIED_MASTER_MULTIPLIER
, "%d", currentPidProfile
->simplified_master_multiplier
);
1493 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_SIMPLIFIED_I_GAIN
, "%d", currentPidProfile
->simplified_i_gain
);
1494 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_SIMPLIFIED_D_GAIN
, "%d", currentPidProfile
->simplified_d_gain
);
1495 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_SIMPLIFIED_PI_GAIN
, "%d", currentPidProfile
->simplified_pi_gain
);
1496 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_SIMPLIFIED_DMAX_GAIN
, "%d", currentPidProfile
->simplified_dmin_ratio
);
1497 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_SIMPLIFIED_FEEDFORWARD_GAIN
, "%d", currentPidProfile
->simplified_feedforward_gain
);
1498 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_SIMPLIFIED_PITCH_D_GAIN
, "%d", currentPidProfile
->simplified_roll_pitch_ratio
);
1499 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_SIMPLIFIED_PITCH_PI_GAIN
, "%d", currentPidProfile
->simplified_pitch_pi_gain
);
1500 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_SIMPLIFIED_DTERM_FILTER
, "%d", currentPidProfile
->simplified_dterm_filter
);
1501 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_SIMPLIFIED_DTERM_FILTER_MULTIPLIER
, "%d", currentPidProfile
->simplified_dterm_filter_multiplier
);
1502 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_SIMPLIFIED_GYRO_FILTER
, "%d", gyroConfig()->simplified_gyro_filter
);
1503 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_SIMPLIFIED_GYRO_FILTER_MULTIPLIER
, "%d", gyroConfig()->simplified_gyro_filter_multiplier
);
1506 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_MOTOR_OUTPUT_LIMIT
, "%d", currentPidProfile
->motor_output_limit
);
1507 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_THROTTLE_LIMIT_TYPE
, "%d", currentControlRateProfile
->throttle_limit_type
);
1508 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_THROTTLE_LIMIT_PERCENT
, "%d", currentControlRateProfile
->throttle_limit_percent
);
1509 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_THROTTLE_BOOST
, "%d", currentPidProfile
->throttle_boost
);
1510 BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_THROTTLE_BOOST_CUTOFF
, "%d", currentPidProfile
->throttle_boost_cutoff
)
1516 xmitState
.headerIndex
++;
1522 * Write the given event to the log immediately
1524 void blackboxLogEvent(FlightLogEvent event
, flightLogEventData_t
*data
)
1526 // Only allow events to be logged after headers have been written
1527 if (!(blackboxState
== BLACKBOX_STATE_RUNNING
|| blackboxState
== BLACKBOX_STATE_PAUSED
)) {
1531 //Shared header for event frames
1533 blackboxWrite(event
);
1535 //Now serialize the data for this specific frame type
1537 case FLIGHT_LOG_EVENT_SYNC_BEEP
:
1538 blackboxWriteUnsignedVB(data
->syncBeep
.time
);
1540 case FLIGHT_LOG_EVENT_FLIGHTMODE
: // New flightmode flags write
1541 blackboxWriteUnsignedVB(data
->flightMode
.flags
);
1542 blackboxWriteUnsignedVB(data
->flightMode
.lastFlags
);
1544 case FLIGHT_LOG_EVENT_DISARM
:
1545 blackboxWriteUnsignedVB(data
->disarm
.reason
);
1547 case FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT
:
1548 if (data
->inflightAdjustment
.floatFlag
) {
1549 blackboxWrite(data
->inflightAdjustment
.adjustmentFunction
+ FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT_FUNCTION_FLOAT_VALUE_FLAG
);
1550 blackboxWriteFloat(data
->inflightAdjustment
.newFloatValue
);
1552 blackboxWrite(data
->inflightAdjustment
.adjustmentFunction
);
1553 blackboxWriteSignedVB(data
->inflightAdjustment
.newValue
);
1556 case FLIGHT_LOG_EVENT_LOGGING_RESUME
:
1557 blackboxWriteUnsignedVB(data
->loggingResume
.logIteration
);
1558 blackboxWriteUnsignedVB(data
->loggingResume
.currentTime
);
1560 case FLIGHT_LOG_EVENT_LOG_END
:
1561 blackboxWriteString("End of log");
1569 /* 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 */
1570 static void blackboxCheckAndLogArmingBeep(void)
1572 // Use != so that we can still detect a change if the counter wraps
1573 if (getArmingBeepTimeMicros() != blackboxLastArmingBeep
) {
1574 blackboxLastArmingBeep
= getArmingBeepTimeMicros();
1575 flightLogEvent_syncBeep_t eventData
;
1576 eventData
.time
= blackboxLastArmingBeep
;
1577 blackboxLogEvent(FLIGHT_LOG_EVENT_SYNC_BEEP
, (flightLogEventData_t
*)&eventData
);
1581 /* monitor the flight mode event status and trigger an event record if the state changes */
1582 static void blackboxCheckAndLogFlightMode(void)
1584 // Use != so that we can still detect a change if the counter wraps
1585 if (memcmp(&rcModeActivationMask
, &blackboxLastFlightModeFlags
, sizeof(blackboxLastFlightModeFlags
))) {
1586 flightLogEvent_flightMode_t eventData
; // Add new data for current flight mode flags
1587 eventData
.lastFlags
= blackboxLastFlightModeFlags
;
1588 memcpy(&blackboxLastFlightModeFlags
, &rcModeActivationMask
, sizeof(blackboxLastFlightModeFlags
));
1589 memcpy(&eventData
.flags
, &rcModeActivationMask
, sizeof(eventData
.flags
));
1590 blackboxLogEvent(FLIGHT_LOG_EVENT_FLIGHTMODE
, (flightLogEventData_t
*)&eventData
);
1594 STATIC_UNIT_TESTED
bool blackboxShouldLogPFrame(void)
1596 return blackboxPFrameIndex
== 0 && blackboxPInterval
!= 0;
1599 STATIC_UNIT_TESTED
bool blackboxShouldLogIFrame(void)
1601 return blackboxLoopIndex
== 0;
1605 * If the GPS home point has been updated, or every 128 I-frames (~10 seconds), write the
1606 * GPS home position.
1608 * We write it periodically so that if one Home Frame goes missing, the GPS coordinates can
1609 * still be interpreted correctly.
1612 STATIC_UNIT_TESTED
bool blackboxShouldLogGpsHomeFrame(void)
1614 if ((GPS_home
[0] != gpsHistory
.GPS_home
[0] || GPS_home
[1] != gpsHistory
.GPS_home
[1]
1615 || (blackboxPFrameIndex
== blackboxIInterval
/ 2 && blackboxIFrameIndex
% 128 == 0)) && isFieldEnabled(FIELD_SELECT(GPS
))) {
1622 // Called once every FC loop in order to keep track of how many FC loop iterations have passed
1623 STATIC_UNIT_TESTED
void blackboxAdvanceIterationTimers(void)
1625 ++blackboxSlowFrameIterationTimer
;
1626 ++blackboxIteration
;
1628 if (++blackboxLoopIndex
>= blackboxIInterval
) {
1629 blackboxLoopIndex
= 0;
1630 blackboxIFrameIndex
++;
1631 blackboxPFrameIndex
= 0;
1632 } else if (++blackboxPFrameIndex
>= blackboxPInterval
) {
1633 blackboxPFrameIndex
= 0;
1637 // Called once every FC loop in order to log the current state
1638 STATIC_UNIT_TESTED
void blackboxLogIteration(timeUs_t currentTimeUs
)
1640 // Write a keyframe every blackboxIInterval frames so we can resynchronise upon missing frames
1641 if (blackboxShouldLogIFrame()) {
1643 * Don't log a slow frame if the slow data didn't change ("I" frames are already large enough without adding
1644 * an additional item to write at the same time). Unless we're *only* logging "I" frames, then we have no choice.
1646 if (blackboxIsOnlyLoggingIntraframes()) {
1647 writeSlowFrameIfNeeded();
1650 loadMainState(currentTimeUs
);
1653 blackboxCheckAndLogArmingBeep();
1654 blackboxCheckAndLogFlightMode(); // Check for FlightMode status change event
1656 if (blackboxShouldLogPFrame()) {
1658 * We assume that slow frames are only interesting in that they aid the interpretation of the main data stream.
1659 * So only log slow frames during loop iterations where we log a main frame.
1661 writeSlowFrameIfNeeded();
1663 loadMainState(currentTimeUs
);
1667 if (featureIsEnabled(FEATURE_GPS
) && isFieldEnabled(FIELD_SELECT(GPS
))) {
1668 if (blackboxShouldLogGpsHomeFrame()) {
1669 writeGPSHomeFrame();
1670 writeGPSFrame(currentTimeUs
);
1671 } else if (gpsSol
.numSat
!= gpsHistory
.GPS_numSat
1672 || gpsSol
.llh
.lat
!= gpsHistory
.GPS_coord
[GPS_LATITUDE
]
1673 || gpsSol
.llh
.lon
!= gpsHistory
.GPS_coord
[GPS_LONGITUDE
]) {
1674 //We could check for velocity changes as well but I doubt it changes independent of position
1675 writeGPSFrame(currentTimeUs
);
1681 //Flush every iteration so that our runtime variance is minimized
1682 blackboxDeviceFlush();
1686 * Call each flight loop iteration to perform blackbox logging.
1688 void blackboxUpdate(timeUs_t currentTimeUs
)
1690 static BlackboxState cacheFlushNextState
;
1692 switch (blackboxState
) {
1693 case BLACKBOX_STATE_STOPPED
:
1694 if (ARMING_FLAG(ARMED
)) {
1699 if (IS_RC_MODE_ACTIVE(BOXBLACKBOXERASE
)) {
1700 blackboxSetState(BLACKBOX_STATE_START_ERASE
);
1704 case BLACKBOX_STATE_PREPARE_LOG_FILE
:
1705 if (blackboxDeviceBeginLog()) {
1706 blackboxSetState(BLACKBOX_STATE_SEND_HEADER
);
1709 case BLACKBOX_STATE_SEND_HEADER
:
1710 blackboxReplenishHeaderBudget();
1711 //On entry of this state, xmitState.headerIndex is 0 and startTime is intialised
1714 * Once the UART has had time to init, transmit the header in chunks so we don't overflow its transmit
1715 * buffer, overflow the OpenLog's buffer, or keep the main loop busy for too long.
1717 if (millis() > xmitState
.u
.startTime
+ 100) {
1718 if (blackboxDeviceReserveBufferSpace(BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION
) == BLACKBOX_RESERVE_SUCCESS
) {
1719 for (int i
= 0; i
< BLACKBOX_TARGET_HEADER_BUDGET_PER_ITERATION
&& blackboxHeader
[xmitState
.headerIndex
] != '\0'; i
++, xmitState
.headerIndex
++) {
1720 blackboxWrite(blackboxHeader
[xmitState
.headerIndex
]);
1721 blackboxHeaderBudget
--;
1723 if (blackboxHeader
[xmitState
.headerIndex
] == '\0') {
1724 blackboxSetState(BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER
);
1729 case BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER
:
1730 blackboxReplenishHeaderBudget();
1731 //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
1732 if (!sendFieldDefinition('I', 'P', blackboxMainFields
, blackboxMainFields
+ 1, ARRAYLEN(blackboxMainFields
),
1733 &blackboxMainFields
[0].condition
, &blackboxMainFields
[1].condition
)) {
1735 if (featureIsEnabled(FEATURE_GPS
) && isFieldEnabled(FIELD_SELECT(GPS
))) {
1736 blackboxSetState(BLACKBOX_STATE_SEND_GPS_H_HEADER
);
1739 blackboxSetState(BLACKBOX_STATE_SEND_SLOW_HEADER
);
1743 case BLACKBOX_STATE_SEND_GPS_H_HEADER
:
1744 blackboxReplenishHeaderBudget();
1745 //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
1746 if (!sendFieldDefinition('H', 0, blackboxGpsHFields
, blackboxGpsHFields
+ 1, ARRAYLEN(blackboxGpsHFields
),
1747 NULL
, NULL
) && isFieldEnabled(FIELD_SELECT(GPS
))) {
1748 blackboxSetState(BLACKBOX_STATE_SEND_GPS_G_HEADER
);
1751 case BLACKBOX_STATE_SEND_GPS_G_HEADER
:
1752 blackboxReplenishHeaderBudget();
1753 //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
1754 if (!sendFieldDefinition('G', 0, blackboxGpsGFields
, blackboxGpsGFields
+ 1, ARRAYLEN(blackboxGpsGFields
),
1755 &blackboxGpsGFields
[0].condition
, &blackboxGpsGFields
[1].condition
) && isFieldEnabled(FIELD_SELECT(GPS
))) {
1756 blackboxSetState(BLACKBOX_STATE_SEND_SLOW_HEADER
);
1760 case BLACKBOX_STATE_SEND_SLOW_HEADER
:
1761 blackboxReplenishHeaderBudget();
1762 //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
1763 if (!sendFieldDefinition('S', 0, blackboxSlowFields
, blackboxSlowFields
+ 1, ARRAYLEN(blackboxSlowFields
),
1765 cacheFlushNextState
= BLACKBOX_STATE_SEND_SYSINFO
;
1766 blackboxSetState(BLACKBOX_STATE_CACHE_FLUSH
);
1769 case BLACKBOX_STATE_SEND_SYSINFO
:
1770 blackboxReplenishHeaderBudget();
1771 //On entry of this state, xmitState.headerIndex is 0
1773 //Keep writing chunks of the system info headers until it returns true to signal completion
1774 if (blackboxWriteSysinfo()) {
1776 * Wait for header buffers to drain completely before data logging begins to ensure reliable header delivery
1777 * (overflowing circular buffers causes all data to be discarded, so the first few logged iterations
1778 * could wipe out the end of the header if we weren't careful)
1780 cacheFlushNextState
= BLACKBOX_STATE_RUNNING
;
1781 blackboxSetState(BLACKBOX_STATE_CACHE_FLUSH
);
1784 case BLACKBOX_STATE_CACHE_FLUSH
:
1785 // Flush the cache and wait until all possible entries have been written to the media
1786 if (blackboxDeviceFlushForceComplete()) {
1787 blackboxSetState(cacheFlushNextState
);
1790 case BLACKBOX_STATE_PAUSED
:
1791 // Only allow resume to occur during an I-frame iteration, so that we have an "I" base to work from
1792 if (IS_RC_MODE_ACTIVE(BOXBLACKBOX
) && blackboxShouldLogIFrame()) {
1793 // Write a log entry so the decoder is aware that our large time/iteration skip is intended
1794 flightLogEvent_loggingResume_t resume
;
1796 resume
.logIteration
= blackboxIteration
;
1797 resume
.currentTime
= currentTimeUs
;
1799 blackboxLogEvent(FLIGHT_LOG_EVENT_LOGGING_RESUME
, (flightLogEventData_t
*) &resume
);
1800 blackboxSetState(BLACKBOX_STATE_RUNNING
);
1802 blackboxLogIteration(currentTimeUs
);
1804 // Keep the logging timers ticking so our log iteration continues to advance
1805 blackboxAdvanceIterationTimers();
1807 case BLACKBOX_STATE_RUNNING
:
1808 // On entry to this state, blackboxIteration, blackboxPFrameIndex and blackboxIFrameIndex are reset to 0
1809 // Prevent the Pausing of the log on the mode switch if in Motor Test Mode
1810 if (blackboxModeActivationConditionPresent
&& !IS_RC_MODE_ACTIVE(BOXBLACKBOX
) && !startedLoggingInTestMode
) {
1811 blackboxSetState(BLACKBOX_STATE_PAUSED
);
1813 blackboxLogIteration(currentTimeUs
);
1815 blackboxAdvanceIterationTimers();
1817 case BLACKBOX_STATE_SHUTTING_DOWN
:
1818 //On entry of this state, startTime is set
1820 * Wait for the log we've transmitted to make its way to the logger before we release the serial port,
1821 * since releasing the port clears the Tx buffer.
1823 * Don't wait longer than it could possibly take if something funky happens.
1825 if (blackboxDeviceEndLog(blackboxLoggedAnyFrames
) && (millis() > xmitState
.u
.startTime
+ BLACKBOX_SHUTDOWN_TIMEOUT_MILLIS
|| blackboxDeviceFlushForce())) {
1826 blackboxDeviceClose();
1827 blackboxSetState(BLACKBOX_STATE_STOPPED
);
1831 case BLACKBOX_STATE_START_ERASE
:
1833 blackboxSetState(BLACKBOX_STATE_ERASING
);
1834 beeper(BEEPER_BLACKBOX_ERASE
);
1836 case BLACKBOX_STATE_ERASING
:
1837 if (isBlackboxErased()) {
1839 blackboxSetState(BLACKBOX_STATE_ERASED
);
1840 beeper(BEEPER_BLACKBOX_ERASE
);
1843 case BLACKBOX_STATE_ERASED
:
1844 if (!IS_RC_MODE_ACTIVE(BOXBLACKBOXERASE
)) {
1845 blackboxSetState(BLACKBOX_STATE_STOPPED
);
1853 // Did we run out of room on the device? Stop!
1854 if (isBlackboxDeviceFull()) {
1856 if (blackboxState
!= BLACKBOX_STATE_ERASING
1857 && blackboxState
!= BLACKBOX_STATE_START_ERASE
1858 && blackboxState
!= BLACKBOX_STATE_ERASED
)
1861 blackboxSetState(BLACKBOX_STATE_STOPPED
);
1862 // ensure we reset the test mode flag if we stop due to full memory card
1863 if (startedLoggingInTestMode
) {
1864 startedLoggingInTestMode
= false;
1867 } else { // Only log in test mode if there is room!
1868 switch (blackboxConfig()->mode
) {
1869 case BLACKBOX_MODE_MOTOR_TEST
:
1870 // Handle Motor Test Mode
1871 if (inMotorTestMode()) {
1872 if (blackboxState
==BLACKBOX_STATE_STOPPED
) {
1876 if (blackboxState
!=BLACKBOX_STATE_STOPPED
) {
1882 case BLACKBOX_MODE_ALWAYS_ON
:
1883 if (blackboxState
==BLACKBOX_STATE_STOPPED
) {
1888 case BLACKBOX_MODE_NORMAL
:
1896 int blackboxCalculatePDenom(int rateNum
, int rateDenom
)
1898 return blackboxIInterval
* rateNum
/ rateDenom
;
1901 uint8_t blackboxGetRateDenom(void)
1903 return blackboxPInterval
;
1907 uint16_t blackboxGetPRatio(void) {
1908 return blackboxIInterval
/ blackboxPInterval
;
1911 uint8_t blackboxCalculateSampleRate(uint16_t pRatio
) {
1912 return LOG2(32000 / (targetPidLooptime
* pRatio
));
1916 * Call during system startup to initialize the blackbox.
1918 void blackboxInit(void)
1920 blackboxResetIterationTimers();
1922 // an I-frame is written every 32ms
1923 // blackboxUpdate() is run in synchronisation with the PID loop
1924 // targetPidLooptime is 1000 for 1kHz loop, 500 for 2kHz loop etc, targetPidLooptime is rounded for short looptimes
1925 blackboxIInterval
= (uint16_t)(32 * 1000 / targetPidLooptime
);
1927 blackboxPInterval
= 1 << blackboxConfig()->sample_rate
;
1928 if (blackboxPInterval
> blackboxIInterval
) {
1929 blackboxPInterval
= 0; // log only I frames if logging frequency is too low
1932 if (blackboxConfig()->device
) {
1933 blackboxSetState(BLACKBOX_STATE_STOPPED
);
1935 blackboxSetState(BLACKBOX_STATE_DISABLED
);
1937 blackboxSInterval
= blackboxIInterval
* 256; // S-frame is written every 256*32 = 8192ms, approx every 8 seconds