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/>.
26 #include "common/maths.h"
27 #include "common/axis.h"
28 #include "common/color.h"
29 #include "common/encoding.h"
30 #include "common/utils.h"
32 #include "drivers/gpio.h"
33 #include "drivers/sensor.h"
34 #include "drivers/system.h"
35 #include "drivers/serial.h"
36 #include "drivers/compass.h"
37 #include "drivers/timer.h"
38 #include "drivers/pwm_rx.h"
39 #include "drivers/accgyro.h"
40 #include "drivers/light_led.h"
42 #include "sensors/sensors.h"
43 #include "sensors/boardalignment.h"
44 #include "sensors/sonar.h"
45 #include "sensors/compass.h"
46 #include "sensors/acceleration.h"
47 #include "sensors/barometer.h"
48 #include "sensors/gyro.h"
49 #include "sensors/battery.h"
51 #include "io/beeper.h"
52 #include "io/display.h"
53 #include "io/escservo.h"
54 #include "io/rc_controls.h"
55 #include "io/gimbal.h"
57 #include "io/ledstrip.h"
58 #include "io/serial.h"
59 #include "io/serial_cli.h"
60 #include "io/serial_msp.h"
61 #include "io/statusindicator.h"
66 #include "telemetry/telemetry.h"
68 #include "flight/mixer.h"
69 #include "flight/altitudehold.h"
70 #include "flight/failsafe.h"
71 #include "flight/imu.h"
72 #include "flight/navigation.h"
74 #include "config/runtime_config.h"
75 #include "config/config.h"
76 #include "config/config_profile.h"
77 #include "config/config_master.h"
80 #include "blackbox_io.h"
82 #define BLACKBOX_I_INTERVAL 32
83 #define BLACKBOX_SHUTDOWN_TIMEOUT_MILLIS 200
84 #define SLOW_FRAME_INTERVAL 4096
86 #define ARRAY_LENGTH(x) (sizeof((x))/sizeof((x)[0]))
88 #define STATIC_ASSERT(condition, name ) \
89 typedef char assert_failed_ ## name [(condition) ? 1 : -1 ]
91 // Some macros to make writing FLIGHT_LOG_FIELD_* constants shorter:
93 #define PREDICT(x) CONCAT(FLIGHT_LOG_FIELD_PREDICTOR_, x)
94 #define ENCODING(x) CONCAT(FLIGHT_LOG_FIELD_ENCODING_, x)
95 #define CONDITION(x) CONCAT(FLIGHT_LOG_FIELD_CONDITION_, x)
96 #define UNSIGNED FLIGHT_LOG_FIELD_UNSIGNED
97 #define SIGNED FLIGHT_LOG_FIELD_SIGNED
99 static const char blackboxHeader
[] =
100 "H Product:Blackbox flight data recorder by Nicholas Sherlock\n"
102 "H I interval:" STR(BLACKBOX_I_INTERVAL
) "\n";
104 static const char* const blackboxFieldHeaderNames
[] = {
113 /* All field definition structs should look like this (but with longer arrs): */
114 typedef struct blackboxFieldDefinition_s
{
116 // If the field name has a number to be included in square brackets [1] afterwards, set it here, or -1 for no brackets:
117 int8_t fieldNameIndex
;
119 // Each member of this array will be the value to print for this field for the given header index
121 } blackboxFieldDefinition_t
;
123 #define BLACKBOX_DELTA_FIELD_HEADER_COUNT ARRAY_LENGTH(blackboxFieldHeaderNames)
124 #define BLACKBOX_SIMPLE_FIELD_HEADER_COUNT (BLACKBOX_DELTA_FIELD_HEADER_COUNT - 2)
125 #define BLACKBOX_CONDITIONAL_FIELD_HEADER_COUNT (BLACKBOX_DELTA_FIELD_HEADER_COUNT - 2)
127 typedef struct blackboxSimpleFieldDefinition_s
{
129 int8_t fieldNameIndex
;
134 } blackboxSimpleFieldDefinition_t
;
136 typedef struct blackboxConditionalFieldDefinition_s
{
138 int8_t fieldNameIndex
;
143 uint8_t condition
; // Decide whether this field should appear in the log
144 } blackboxConditionalFieldDefinition_t
;
146 typedef struct blackboxDeltaFieldDefinition_s
{
148 int8_t fieldNameIndex
;
155 uint8_t condition
; // Decide whether this field should appear in the log
156 } blackboxDeltaFieldDefinition_t
;
159 * Description of the blackbox fields we are writing in our main intra (I) and inter (P) frames. This description is
160 * written into the flight log header so the log can be properly interpreted (but these definitions don't actually cause
161 * the encoding to happen, we have to encode the flight log ourselves in write{Inter|Intra}frame() in a way that matches
162 * the encoding we've promised here).
164 static const blackboxDeltaFieldDefinition_t blackboxMainFields
[] = {
165 /* loopIteration doesn't appear in P frames since it always increments */
166 {"loopIteration",-1, UNSIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(UNSIGNED_VB
), .Ppredict
= PREDICT(INC
), .Pencode
= FLIGHT_LOG_FIELD_ENCODING_NULL
, CONDITION(ALWAYS
)},
167 /* Time advances pretty steadily so the P-frame prediction is a straight line */
168 {"time", -1, UNSIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(UNSIGNED_VB
), .Ppredict
= PREDICT(STRAIGHT_LINE
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(ALWAYS
)},
169 {"axisP", 0, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(ALWAYS
)},
170 {"axisP", 1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(ALWAYS
)},
171 {"axisP", 2, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(ALWAYS
)},
172 /* I terms get special packed encoding in P frames: */
173 {"axisI", 0, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG2_3S32
), CONDITION(ALWAYS
)},
174 {"axisI", 1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG2_3S32
), CONDITION(ALWAYS
)},
175 {"axisI", 2, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG2_3S32
), CONDITION(ALWAYS
)},
176 {"axisD", 0, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(NONZERO_PID_D_0
)},
177 {"axisD", 1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(NONZERO_PID_D_1
)},
178 {"axisD", 2, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(NONZERO_PID_D_2
)},
179 /* rcCommands are encoded together as a group in P-frames: */
180 {"rcCommand", 0, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_4S16
), CONDITION(ALWAYS
)},
181 {"rcCommand", 1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_4S16
), CONDITION(ALWAYS
)},
182 {"rcCommand", 2, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_4S16
), CONDITION(ALWAYS
)},
183 /* Throttle is always in the range [minthrottle..maxthrottle]: */
184 {"rcCommand", 3, UNSIGNED
, .Ipredict
= PREDICT(MINTHROTTLE
), .Iencode
= ENCODING(UNSIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_4S16
), CONDITION(ALWAYS
)},
186 {"vbatLatest", -1, UNSIGNED
, .Ipredict
= PREDICT(VBATREF
), .Iencode
= ENCODING(NEG_14BIT
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_8SVB
), FLIGHT_LOG_FIELD_CONDITION_VBAT
},
187 {"amperageLatest",-1, UNSIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(UNSIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_8SVB
), FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC
},
190 {"magADC", 0, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_8SVB
), FLIGHT_LOG_FIELD_CONDITION_MAG
},
191 {"magADC", 1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_8SVB
), FLIGHT_LOG_FIELD_CONDITION_MAG
},
192 {"magADC", 2, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_8SVB
), FLIGHT_LOG_FIELD_CONDITION_MAG
},
195 {"BaroAlt", -1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_8SVB
), FLIGHT_LOG_FIELD_CONDITION_BARO
},
198 {"sonarRaw", -1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_8SVB
), FLIGHT_LOG_FIELD_CONDITION_SONAR
},
200 {"rssi", -1, UNSIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(UNSIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(TAG8_8SVB
), FLIGHT_LOG_FIELD_CONDITION_RSSI
},
202 /* Gyros and accelerometers base their P-predictions on the average of the previous 2 frames to reduce noise impact */
203 {"gyroADC", 0, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(ALWAYS
)},
204 {"gyroADC", 1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(ALWAYS
)},
205 {"gyroADC", 2, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(ALWAYS
)},
206 {"accSmooth", 0, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(ALWAYS
)},
207 {"accSmooth", 1, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(ALWAYS
)},
208 {"accSmooth", 2, SIGNED
, .Ipredict
= PREDICT(0), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(ALWAYS
)},
209 /* 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): */
210 {"motor", 0, UNSIGNED
, .Ipredict
= PREDICT(MINTHROTTLE
), .Iencode
= ENCODING(UNSIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(AT_LEAST_MOTORS_1
)},
211 /* Subsequent motors base their I-frame values on the first one, P-frame values on the average of last two frames: */
212 {"motor", 1, UNSIGNED
, .Ipredict
= PREDICT(MOTOR_0
), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(AT_LEAST_MOTORS_2
)},
213 {"motor", 2, UNSIGNED
, .Ipredict
= PREDICT(MOTOR_0
), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(AT_LEAST_MOTORS_3
)},
214 {"motor", 3, UNSIGNED
, .Ipredict
= PREDICT(MOTOR_0
), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(AT_LEAST_MOTORS_4
)},
215 {"motor", 4, UNSIGNED
, .Ipredict
= PREDICT(MOTOR_0
), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(AT_LEAST_MOTORS_5
)},
216 {"motor", 5, UNSIGNED
, .Ipredict
= PREDICT(MOTOR_0
), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(AT_LEAST_MOTORS_6
)},
217 {"motor", 6, UNSIGNED
, .Ipredict
= PREDICT(MOTOR_0
), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(AT_LEAST_MOTORS_7
)},
218 {"motor", 7, UNSIGNED
, .Ipredict
= PREDICT(MOTOR_0
), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(AVERAGE_2
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(AT_LEAST_MOTORS_8
)},
220 /* Tricopter tail servo */
221 {"servo", 5, UNSIGNED
, .Ipredict
= PREDICT(1500), .Iencode
= ENCODING(SIGNED_VB
), .Ppredict
= PREDICT(PREVIOUS
), .Pencode
= ENCODING(SIGNED_VB
), CONDITION(TRICOPTER
)}
225 // GPS position/vel frame
226 static const blackboxConditionalFieldDefinition_t blackboxGpsGFields
[] = {
227 {"time", -1, UNSIGNED
, PREDICT(LAST_MAIN_FRAME_TIME
), ENCODING(UNSIGNED_VB
), CONDITION(NOT_LOGGING_EVERY_FRAME
)},
228 {"GPS_numSat", -1, UNSIGNED
, PREDICT(0), ENCODING(UNSIGNED_VB
), CONDITION(ALWAYS
)},
229 {"GPS_coord", 0, SIGNED
, PREDICT(HOME_COORD
), ENCODING(SIGNED_VB
), CONDITION(ALWAYS
)},
230 {"GPS_coord", 1, SIGNED
, PREDICT(HOME_COORD
), ENCODING(SIGNED_VB
), CONDITION(ALWAYS
)},
231 {"GPS_altitude", -1, UNSIGNED
, PREDICT(0), ENCODING(UNSIGNED_VB
), CONDITION(ALWAYS
)},
232 {"GPS_speed", -1, UNSIGNED
, PREDICT(0), ENCODING(UNSIGNED_VB
), CONDITION(ALWAYS
)},
233 {"GPS_ground_course", -1, UNSIGNED
, PREDICT(0), ENCODING(UNSIGNED_VB
), CONDITION(ALWAYS
)}
237 static const blackboxSimpleFieldDefinition_t blackboxGpsHFields
[] = {
238 {"GPS_home", 0, SIGNED
, PREDICT(0), ENCODING(SIGNED_VB
)},
239 {"GPS_home", 1, SIGNED
, PREDICT(0), ENCODING(SIGNED_VB
)}
243 // Rarely-updated fields
244 static const blackboxSimpleFieldDefinition_t blackboxSlowFields
[] = {
245 {"flightModeFlags", -1, UNSIGNED
, PREDICT(0), ENCODING(UNSIGNED_VB
)},
246 {"stateFlags", -1, UNSIGNED
, PREDICT(0), ENCODING(UNSIGNED_VB
)},
248 {"failsafePhase", -1, UNSIGNED
, PREDICT(0), ENCODING(TAG2_3S32
)},
249 {"rxSignalReceived", -1, UNSIGNED
, PREDICT(0), ENCODING(TAG2_3S32
)},
250 {"rxFlightChannelsValid", -1, UNSIGNED
, PREDICT(0), ENCODING(TAG2_3S32
)}
253 typedef enum BlackboxState
{
254 BLACKBOX_STATE_DISABLED
= 0,
255 BLACKBOX_STATE_STOPPED
,
256 BLACKBOX_STATE_SEND_HEADER
,
257 BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER
,
258 BLACKBOX_STATE_SEND_GPS_H_HEADER
,
259 BLACKBOX_STATE_SEND_GPS_G_HEADER
,
260 BLACKBOX_STATE_SEND_SLOW_HEADER
,
261 BLACKBOX_STATE_SEND_SYSINFO
,
262 BLACKBOX_STATE_PAUSED
,
263 BLACKBOX_STATE_RUNNING
,
264 BLACKBOX_STATE_SHUTTING_DOWN
267 typedef struct blackboxMainState_s
{
270 int32_t axisPID_P
[XYZ_AXIS_COUNT
], axisPID_I
[XYZ_AXIS_COUNT
], axisPID_D
[XYZ_AXIS_COUNT
];
272 int16_t rcCommand
[4];
273 int16_t gyroADC
[XYZ_AXIS_COUNT
];
274 int16_t accSmooth
[XYZ_AXIS_COUNT
];
275 int16_t motor
[MAX_SUPPORTED_MOTORS
];
276 int16_t servo
[MAX_SUPPORTED_SERVOS
];
279 uint16_t amperageLatest
;
285 int16_t magADC
[XYZ_AXIS_COUNT
];
291 } blackboxMainState_t
;
293 typedef struct blackboxGpsState_s
{
294 int32_t GPS_home
[2], GPS_coord
[2];
296 } blackboxGpsState_t
;
298 // This data is updated really infrequently:
299 typedef struct blackboxSlowState_s
{
300 uint16_t flightModeFlags
;
302 uint8_t failsafePhase
;
303 bool rxSignalReceived
;
304 bool rxFlightChannelsValid
;
305 } __attribute__((__packed__
)) blackboxSlowState_t
; // We pack this struct so that padding doesn't interfere with memcmp()
308 extern uint8_t motorCount
;
311 extern uint32_t currentTime
;
314 extern uint16_t rssi
;
316 static BlackboxState blackboxState
= BLACKBOX_STATE_DISABLED
;
318 static uint32_t blackboxLastArmingBeep
= 0;
321 uint32_t headerIndex
;
323 /* Since these fields are used during different blackbox states (never simultaneously) we can
324 * overlap them to save on RAM
333 // Cache for FLIGHT_LOG_FIELD_CONDITION_* test results:
334 static uint32_t blackboxConditionCache
;
336 STATIC_ASSERT((sizeof(blackboxConditionCache
) * 8) >= FLIGHT_LOG_FIELD_CONDITION_NEVER
, too_many_flight_log_conditions
);
338 static uint32_t blackboxIteration
;
339 static uint16_t blackboxPFrameIndex
, blackboxIFrameIndex
;
340 static uint16_t blackboxSlowFrameIterationTimer
;
343 * We store voltages in I-frames relative to this, which was the voltage when the blackbox was activated.
344 * This helps out since the voltage is only expected to fall from that point and we can reduce our diffs
347 static uint16_t vbatReference
;
349 static blackboxGpsState_t gpsHistory
;
350 static blackboxSlowState_t slowHistory
;
352 // Keep a history of length 2, plus a buffer for MW to store the new values into
353 static blackboxMainState_t blackboxHistoryRing
[3];
355 // These point into blackboxHistoryRing, use them to know where to store history of a given age (0, 1 or 2 generations old)
356 static blackboxMainState_t
* blackboxHistory
[3];
358 static bool blackboxModeActivationConditionPresent
= false;
360 static bool blackboxIsOnlyLoggingIntraframes() {
361 return masterConfig
.blackbox_rate_num
== 1 && masterConfig
.blackbox_rate_denom
== 32;
364 static bool testBlackboxConditionUncached(FlightLogFieldCondition condition
)
367 case FLIGHT_LOG_FIELD_CONDITION_ALWAYS
:
370 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1
:
371 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_2
:
372 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_3
:
373 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_4
:
374 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_5
:
375 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_6
:
376 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7
:
377 case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8
:
378 return motorCount
>= condition
- FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1
+ 1;
380 case FLIGHT_LOG_FIELD_CONDITION_TRICOPTER
:
381 return masterConfig
.mixerMode
== MIXER_TRI
|| masterConfig
.mixerMode
== MIXER_CUSTOM_TRI
;
383 case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0
:
384 case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1
:
385 case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_2
:
386 if (IS_PID_CONTROLLER_FP_BASED(currentProfile
->pidProfile
.pidController
)) {
387 return currentProfile
->pidProfile
.D_f
[condition
- FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0
] != 0;
389 return currentProfile
->pidProfile
.D8
[condition
- FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0
] != 0;
392 case FLIGHT_LOG_FIELD_CONDITION_MAG
:
394 return sensors(SENSOR_MAG
);
399 case FLIGHT_LOG_FIELD_CONDITION_BARO
:
401 return sensors(SENSOR_BARO
);
406 case FLIGHT_LOG_FIELD_CONDITION_VBAT
:
407 return feature(FEATURE_VBAT
);
409 case FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC
:
410 return feature(FEATURE_CURRENT_METER
) && masterConfig
.batteryConfig
.currentMeterType
== CURRENT_SENSOR_ADC
;
412 case FLIGHT_LOG_FIELD_CONDITION_SONAR
:
414 return feature(FEATURE_SONAR
);
419 case FLIGHT_LOG_FIELD_CONDITION_RSSI
:
420 return masterConfig
.rxConfig
.rssi_channel
> 0 || feature(FEATURE_RSSI_ADC
);
422 case FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME
:
423 return masterConfig
.blackbox_rate_num
< masterConfig
.blackbox_rate_denom
;
425 case FLIGHT_LOG_FIELD_CONDITION_NEVER
:
432 static void blackboxBuildConditionCache()
434 FlightLogFieldCondition cond
;
436 blackboxConditionCache
= 0;
438 for (cond
= FLIGHT_LOG_FIELD_CONDITION_FIRST
; cond
<= FLIGHT_LOG_FIELD_CONDITION_LAST
; cond
++) {
439 if (testBlackboxConditionUncached(cond
)) {
440 blackboxConditionCache
|= 1 << cond
;
445 static bool testBlackboxCondition(FlightLogFieldCondition condition
)
447 return (blackboxConditionCache
& (1 << condition
)) != 0;
450 static void blackboxSetState(BlackboxState newState
)
452 //Perform initial setup required for the new state
454 case BLACKBOX_STATE_SEND_HEADER
:
455 xmitState
.headerIndex
= 0;
456 xmitState
.u
.startTime
= millis();
458 case BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER
:
459 case BLACKBOX_STATE_SEND_GPS_G_HEADER
:
460 case BLACKBOX_STATE_SEND_GPS_H_HEADER
:
461 case BLACKBOX_STATE_SEND_SLOW_HEADER
:
462 xmitState
.headerIndex
= 0;
463 xmitState
.u
.fieldIndex
= -1;
465 case BLACKBOX_STATE_SEND_SYSINFO
:
466 xmitState
.headerIndex
= 0;
468 case BLACKBOX_STATE_RUNNING
:
469 blackboxSlowFrameIterationTimer
= SLOW_FRAME_INTERVAL
; //Force a slow frame to be written on the first iteration
471 case BLACKBOX_STATE_SHUTTING_DOWN
:
472 xmitState
.u
.startTime
= millis();
473 blackboxDeviceFlush();
478 blackboxState
= newState
;
481 static void writeIntraframe(void)
483 blackboxMainState_t
*blackboxCurrent
= blackboxHistory
[0];
488 blackboxWriteUnsignedVB(blackboxIteration
);
489 blackboxWriteUnsignedVB(blackboxCurrent
->time
);
491 blackboxWriteSignedVBArray(blackboxCurrent
->axisPID_P
, XYZ_AXIS_COUNT
);
492 blackboxWriteSignedVBArray(blackboxCurrent
->axisPID_I
, XYZ_AXIS_COUNT
);
494 // Don't bother writing the current D term if the corresponding PID setting is zero
495 for (x
= 0; x
< XYZ_AXIS_COUNT
; x
++) {
496 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0
+ x
)) {
497 blackboxWriteSignedVB(blackboxCurrent
->axisPID_D
[x
]);
501 // Write roll, pitch and yaw first:
502 blackboxWriteSigned16VBArray(blackboxCurrent
->rcCommand
, 3);
505 * Write the throttle separately from the rest of the RC data so we can apply a predictor to it.
506 * Throttle lies in range [minthrottle..maxthrottle]:
508 blackboxWriteUnsignedVB(blackboxCurrent
->rcCommand
[THROTTLE
] - masterConfig
.escAndServoConfig
.minthrottle
);
510 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT
)) {
512 * Our voltage is expected to decrease over the course of the flight, so store our difference from
515 * Write 14 bits even if the number is negative (which would otherwise result in 32 bits)
517 blackboxWriteUnsignedVB((vbatReference
- blackboxCurrent
->vbatLatest
) & 0x3FFF);
520 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC
)) {
521 // 12bit value directly from ADC
522 blackboxWriteUnsignedVB(blackboxCurrent
->amperageLatest
);
526 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_MAG
)) {
527 blackboxWriteSigned16VBArray(blackboxCurrent
->magADC
, XYZ_AXIS_COUNT
);
532 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_BARO
)) {
533 blackboxWriteSignedVB(blackboxCurrent
->BaroAlt
);
538 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_SONAR
)) {
539 blackboxWriteSignedVB(blackboxCurrent
->sonarRaw
);
543 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_RSSI
)) {
544 blackboxWriteUnsignedVB(blackboxCurrent
->rssi
);
547 blackboxWriteSigned16VBArray(blackboxCurrent
->gyroADC
, XYZ_AXIS_COUNT
);
548 blackboxWriteSigned16VBArray(blackboxCurrent
->accSmooth
, XYZ_AXIS_COUNT
);
550 //Motors can be below minthrottle when disarmed, but that doesn't happen much
551 blackboxWriteUnsignedVB(blackboxCurrent
->motor
[0] - masterConfig
.escAndServoConfig
.minthrottle
);
553 //Motors tend to be similar to each other so use the first motor's value as a predictor of the others
554 for (x
= 1; x
< motorCount
; x
++) {
555 blackboxWriteSignedVB(blackboxCurrent
->motor
[x
] - blackboxCurrent
->motor
[0]);
558 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_TRICOPTER
)) {
559 //Assume the tail spends most of its time around the center
560 blackboxWriteSignedVB(blackboxCurrent
->servo
[5] - 1500);
563 //Rotate our history buffers:
565 //The current state becomes the new "before" state
566 blackboxHistory
[1] = blackboxHistory
[0];
567 //And since we have no other history, we also use it for the "before, before" state
568 blackboxHistory
[2] = blackboxHistory
[0];
569 //And advance the current state over to a blank space ready to be filled
570 blackboxHistory
[0] = ((blackboxHistory
[0] - blackboxHistoryRing
+ 1) % 3) + blackboxHistoryRing
;
573 static void blackboxWriteMainStateArrayUsingAveragePredictor(int arrOffsetInHistory
, int count
)
575 int16_t *curr
= (int16_t*) ((char*) (blackboxHistory
[0]) + arrOffsetInHistory
);
576 int16_t *prev1
= (int16_t*) ((char*) (blackboxHistory
[1]) + arrOffsetInHistory
);
577 int16_t *prev2
= (int16_t*) ((char*) (blackboxHistory
[2]) + arrOffsetInHistory
);
579 for (int i
= 0; i
< count
; i
++) {
580 // Predictor is the average of the previous two history states
581 int32_t predictor
= (prev1
[i
] + prev2
[i
]) / 2;
583 blackboxWriteSignedVB(curr
[i
] - predictor
);
587 static void writeInterframe(void)
592 blackboxMainState_t
*blackboxCurrent
= blackboxHistory
[0];
593 blackboxMainState_t
*blackboxLast
= blackboxHistory
[1];
597 //No need to store iteration count since its delta is always 1
600 * Since the difference between the difference between successive times will be nearly zero (due to consistent
601 * looptime spacing), use second-order differences.
603 blackboxWriteSignedVB((int32_t) (blackboxHistory
[0]->time
- 2 * blackboxHistory
[1]->time
+ blackboxHistory
[2]->time
));
605 arraySubInt32(deltas
, blackboxCurrent
->axisPID_P
, blackboxLast
->axisPID_P
, XYZ_AXIS_COUNT
);
606 blackboxWriteSignedVBArray(deltas
, XYZ_AXIS_COUNT
);
609 * The PID I field changes very slowly, most of the time +-2, so use an encoding
610 * that can pack all three fields into one byte in that situation.
612 arraySubInt32(deltas
, blackboxCurrent
->axisPID_I
, blackboxLast
->axisPID_I
, XYZ_AXIS_COUNT
);
613 blackboxWriteTag2_3S32(deltas
);
616 * The PID D term is frequently set to zero for yaw, which makes the result from the calculation
617 * always zero. So don't bother recording D results when PID D terms are zero.
619 for (x
= 0; x
< XYZ_AXIS_COUNT
; x
++) {
620 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0
+ x
)) {
621 blackboxWriteSignedVB(blackboxCurrent
->axisPID_D
[x
] - blackboxLast
->axisPID_D
[x
]);
626 * RC tends to stay the same or fairly small for many frames at a time, so use an encoding that
627 * can pack multiple values per byte:
629 for (x
= 0; x
< 4; x
++) {
630 deltas
[x
] = blackboxCurrent
->rcCommand
[x
] - blackboxLast
->rcCommand
[x
];
633 blackboxWriteTag8_4S16(deltas
);
635 //Check for sensors that are updated periodically (so deltas are normally zero)
636 int optionalFieldCount
= 0;
638 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT
)) {
639 deltas
[optionalFieldCount
++] = (int32_t) blackboxCurrent
->vbatLatest
- blackboxLast
->vbatLatest
;
642 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_AMPERAGE_ADC
)) {
643 deltas
[optionalFieldCount
++] = (int32_t) blackboxCurrent
->amperageLatest
- blackboxLast
->amperageLatest
;
647 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_MAG
)) {
648 for (x
= 0; x
< XYZ_AXIS_COUNT
; x
++) {
649 deltas
[optionalFieldCount
++] = blackboxCurrent
->magADC
[x
] - blackboxLast
->magADC
[x
];
655 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_BARO
)) {
656 deltas
[optionalFieldCount
++] = blackboxCurrent
->BaroAlt
- blackboxLast
->BaroAlt
;
661 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_SONAR
)) {
662 deltas
[optionalFieldCount
++] = blackboxCurrent
->sonarRaw
- blackboxLast
->sonarRaw
;
666 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_RSSI
)) {
667 deltas
[optionalFieldCount
++] = (int32_t) blackboxCurrent
->rssi
- blackboxLast
->rssi
;
670 blackboxWriteTag8_8SVB(deltas
, optionalFieldCount
);
672 //Since gyros, accs and motors are noisy, base their predictions on the average of the history:
673 blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t
, gyroADC
), XYZ_AXIS_COUNT
);
674 blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t
, accSmooth
), XYZ_AXIS_COUNT
);
675 blackboxWriteMainStateArrayUsingAveragePredictor(offsetof(blackboxMainState_t
, motor
), motorCount
);
677 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_TRICOPTER
)) {
678 blackboxWriteSignedVB(blackboxCurrent
->servo
[5] - blackboxLast
->servo
[5]);
681 //Rotate our history buffers
682 blackboxHistory
[2] = blackboxHistory
[1];
683 blackboxHistory
[1] = blackboxHistory
[0];
684 blackboxHistory
[0] = ((blackboxHistory
[0] - blackboxHistoryRing
+ 1) % 3) + blackboxHistoryRing
;
687 /* Write the contents of the global "slowHistory" to the log as an "S" frame. Because this data is logged so
688 * infrequently, delta updates are not reasonable, so we log independent frames. */
689 static void writeSlowFrame(void)
695 blackboxWriteUnsignedVB(slowHistory
.flightModeFlags
);
696 blackboxWriteUnsignedVB(slowHistory
.stateFlags
);
699 * Most of the time these three values will be able to pack into one byte for us:
701 values
[0] = slowHistory
.failsafePhase
;
702 values
[1] = slowHistory
.rxSignalReceived
? 1 : 0;
703 values
[2] = slowHistory
.rxFlightChannelsValid
? 1 : 0;
704 blackboxWriteTag2_3S32(values
);
706 blackboxSlowFrameIterationTimer
= 0;
710 * Load rarely-changing values from the FC into the given structure
712 static void loadSlowState(blackboxSlowState_t
*slow
)
714 slow
->flightModeFlags
= flightModeFlags
;
715 slow
->stateFlags
= stateFlags
;
716 slow
->failsafePhase
= failsafePhase();
717 slow
->rxSignalReceived
= rxIsReceivingSignal();
718 slow
->rxFlightChannelsValid
= rxAreFlightChannelsValid();
722 * If the data in the slow frame has changed, log a slow frame.
724 * If allowPeriodicWrite is true, the frame is also logged if it has been more than SLOW_FRAME_INTERVAL logging iterations
725 * since the field was last logged.
727 static void writeSlowFrameIfNeeded(bool allowPeriodicWrite
)
729 // Write the slow frame peridocially so it can be recovered if we ever lose sync
730 bool shouldWrite
= allowPeriodicWrite
&& blackboxSlowFrameIterationTimer
>= SLOW_FRAME_INTERVAL
;
733 loadSlowState(&slowHistory
);
735 blackboxSlowState_t newSlowState
;
737 loadSlowState(&newSlowState
);
739 // Only write a slow frame if it was different from the previous state
740 if (memcmp(&newSlowState
, &slowHistory
, sizeof(slowHistory
)) != 0) {
741 // Use the new state as our new history
742 memcpy(&slowHistory
, &newSlowState
, sizeof(slowHistory
));
752 static int gcd(int num
, int denom
)
758 return gcd(denom
, num
% denom
);
761 static void validateBlackboxConfig()
765 if (masterConfig
.blackbox_rate_num
== 0 || masterConfig
.blackbox_rate_denom
== 0
766 || masterConfig
.blackbox_rate_num
>= masterConfig
.blackbox_rate_denom
) {
767 masterConfig
.blackbox_rate_num
= 1;
768 masterConfig
.blackbox_rate_denom
= 1;
770 /* Reduce the fraction the user entered as much as possible (makes the recorded/skipped frame pattern repeat
771 * itself more frequently)
773 div
= gcd(masterConfig
.blackbox_rate_num
, masterConfig
.blackbox_rate_denom
);
775 masterConfig
.blackbox_rate_num
/= div
;
776 masterConfig
.blackbox_rate_denom
/= div
;
779 if (masterConfig
.blackbox_device
>= BLACKBOX_DEVICE_END
) {
780 masterConfig
.blackbox_device
= BLACKBOX_DEVICE_SERIAL
;
785 * Start Blackbox logging if it is not already running. Intended to be called upon arming.
787 void startBlackbox(void)
789 if (blackboxState
== BLACKBOX_STATE_STOPPED
) {
790 validateBlackboxConfig();
792 if (!blackboxDeviceOpen()) {
793 blackboxSetState(BLACKBOX_STATE_DISABLED
);
797 memset(&gpsHistory
, 0, sizeof(gpsHistory
));
799 blackboxHistory
[0] = &blackboxHistoryRing
[0];
800 blackboxHistory
[1] = &blackboxHistoryRing
[1];
801 blackboxHistory
[2] = &blackboxHistoryRing
[2];
803 vbatReference
= vbatLatestADC
;
805 //No need to clear the content of blackboxHistoryRing since our first frame will be an intra which overwrites it
808 * We use conditional tests to decide whether or not certain fields should be logged. Since our headers
809 * must always agree with the logged data, the results of these tests must not change during logging. So
812 blackboxBuildConditionCache();
814 blackboxModeActivationConditionPresent
= isModeActivationConditionPresent(currentProfile
->modeActivationConditions
, BOXBLACKBOX
);
816 blackboxIteration
= 0;
817 blackboxPFrameIndex
= 0;
818 blackboxIFrameIndex
= 0;
821 * Record the beeper's current idea of the last arming beep time, so that we can detect it changing when
822 * it finally plays the beep for this arming event.
824 blackboxLastArmingBeep
= getArmingBeepTimeMicros();
826 blackboxSetState(BLACKBOX_STATE_SEND_HEADER
);
831 * Begin Blackbox shutdown.
833 void finishBlackbox(void)
835 if (blackboxState
== BLACKBOX_STATE_RUNNING
|| blackboxState
== BLACKBOX_STATE_PAUSED
) {
836 blackboxLogEvent(FLIGHT_LOG_EVENT_LOG_END
, NULL
);
838 blackboxSetState(BLACKBOX_STATE_SHUTTING_DOWN
);
839 } else if (blackboxState
!= BLACKBOX_STATE_DISABLED
&& blackboxState
!= BLACKBOX_STATE_STOPPED
840 && blackboxState
!= BLACKBOX_STATE_SHUTTING_DOWN
) {
842 * We're shutting down in the middle of transmitting headers, so we can't log a "log completed" event.
843 * Just give the port back and stop immediately.
845 blackboxDeviceClose();
846 blackboxSetState(BLACKBOX_STATE_STOPPED
);
851 static void writeGPSHomeFrame()
855 blackboxWriteSignedVB(GPS_home
[0]);
856 blackboxWriteSignedVB(GPS_home
[1]);
857 //TODO it'd be great if we could grab the GPS current time and write that too
859 gpsHistory
.GPS_home
[0] = GPS_home
[0];
860 gpsHistory
.GPS_home
[1] = GPS_home
[1];
863 static void writeGPSFrame()
868 * If we're logging every frame, then a GPS frame always appears just after a frame with the
869 * currentTime timestamp in the log, so the reader can just use that timestamp for the GPS frame.
871 * If we're not logging every frame, we need to store the time of this GPS frame.
873 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_NOT_LOGGING_EVERY_FRAME
)) {
874 // Predict the time of the last frame in the main log
875 blackboxWriteUnsignedVB(currentTime
- blackboxHistory
[1]->time
);
878 blackboxWriteUnsignedVB(GPS_numSat
);
879 blackboxWriteSignedVB(GPS_coord
[0] - gpsHistory
.GPS_home
[0]);
880 blackboxWriteSignedVB(GPS_coord
[1] - gpsHistory
.GPS_home
[1]);
881 blackboxWriteUnsignedVB(GPS_altitude
);
882 blackboxWriteUnsignedVB(GPS_speed
);
883 blackboxWriteUnsignedVB(GPS_ground_course
);
885 gpsHistory
.GPS_numSat
= GPS_numSat
;
886 gpsHistory
.GPS_coord
[0] = GPS_coord
[0];
887 gpsHistory
.GPS_coord
[1] = GPS_coord
[1];
892 * Fill the current state of the blackbox using values read from the flight controller
894 static void loadMainState(void)
896 blackboxMainState_t
*blackboxCurrent
= blackboxHistory
[0];
899 blackboxCurrent
->time
= currentTime
;
901 for (i
= 0; i
< XYZ_AXIS_COUNT
; i
++) {
902 blackboxCurrent
->axisPID_P
[i
] = axisPID_P
[i
];
904 for (i
= 0; i
< XYZ_AXIS_COUNT
; i
++) {
905 blackboxCurrent
->axisPID_I
[i
] = axisPID_I
[i
];
907 for (i
= 0; i
< XYZ_AXIS_COUNT
; i
++) {
908 blackboxCurrent
->axisPID_D
[i
] = axisPID_D
[i
];
911 for (i
= 0; i
< 4; i
++) {
912 blackboxCurrent
->rcCommand
[i
] = rcCommand
[i
];
915 for (i
= 0; i
< XYZ_AXIS_COUNT
; i
++) {
916 blackboxCurrent
->gyroADC
[i
] = gyroADC
[i
];
919 for (i
= 0; i
< XYZ_AXIS_COUNT
; i
++) {
920 blackboxCurrent
->accSmooth
[i
] = accSmooth
[i
];
923 for (i
= 0; i
< motorCount
; i
++) {
924 blackboxCurrent
->motor
[i
] = motor
[i
];
927 blackboxCurrent
->vbatLatest
= vbatLatestADC
;
928 blackboxCurrent
->amperageLatest
= amperageLatestADC
;
931 for (i
= 0; i
< XYZ_AXIS_COUNT
; i
++) {
932 blackboxCurrent
->magADC
[i
] = magADC
[i
];
937 blackboxCurrent
->BaroAlt
= BaroAlt
;
941 // Store the raw sonar value without applying tilt correction
942 blackboxCurrent
->sonarRaw
= sonarRead();
945 blackboxCurrent
->rssi
= rssi
;
948 //Tail servo for tricopters
949 blackboxCurrent
->servo
[5] = servo
[5];
954 * Transmit the header information for the given field definitions. Transmitted header lines look like:
956 * H Field I name:a,b,c
957 * H Field I predictor:0,1,2
959 * For all header types, provide a "mainFrameChar" which is the name for the field and will be used to refer to it in the
960 * header (e.g. P, I etc). For blackboxDeltaField_t fields, also provide deltaFrameChar, otherwise set this to zero.
962 * Provide an array 'conditions' of FlightLogFieldCondition enums if you want these conditions to decide whether a field
963 * should be included or not. Otherwise provide NULL for this parameter and NULL for secondCondition.
965 * Set xmitState.headerIndex to 0 and xmitState.u.fieldIndex to -1 before calling for the first time.
967 * secondFieldDefinition and secondCondition element pointers need to be provided in order to compute the stride of the
968 * fieldDefinition and secondCondition arrays.
970 * Returns true if there is still header left to transmit (so call again to continue transmission).
972 static bool sendFieldDefinition(char mainFrameChar
, char deltaFrameChar
, const void *fieldDefinitions
,
973 const void *secondFieldDefinition
, int fieldCount
, const uint8_t *conditions
, const uint8_t *secondCondition
)
975 const blackboxFieldDefinition_t
*def
;
977 unsigned int headerCount
;
978 static bool needComma
= false;
979 size_t definitionStride
= (char*) secondFieldDefinition
- (char*) fieldDefinitions
;
980 size_t conditionsStride
= (char*) secondCondition
- (char*) conditions
;
982 if (deltaFrameChar
) {
983 headerCount
= BLACKBOX_DELTA_FIELD_HEADER_COUNT
;
985 headerCount
= BLACKBOX_SIMPLE_FIELD_HEADER_COUNT
;
989 * We're chunking up the header data so we don't exceed our datarate. So we'll be called multiple times to transmit
992 if (xmitState
.u
.fieldIndex
== -1) {
993 if (xmitState
.headerIndex
>= headerCount
) {
994 return false; //Someone probably called us again after we had already completed transmission
997 charsWritten
= blackboxPrintf("H Field %c %s:", xmitState
.headerIndex
>= BLACKBOX_SIMPLE_FIELD_HEADER_COUNT
? deltaFrameChar
: mainFrameChar
, blackboxFieldHeaderNames
[xmitState
.headerIndex
]);
999 xmitState
.u
.fieldIndex
++;
1004 for (; xmitState
.u
.fieldIndex
< fieldCount
&& charsWritten
< blackboxWriteChunkSize
; xmitState
.u
.fieldIndex
++) {
1005 def
= (const blackboxFieldDefinition_t
*) ((const char*)fieldDefinitions
+ definitionStride
* xmitState
.u
.fieldIndex
);
1007 if (!conditions
|| testBlackboxCondition(conditions
[conditionsStride
* xmitState
.u
.fieldIndex
])) {
1015 // The first header is a field name
1016 if (xmitState
.headerIndex
== 0) {
1017 charsWritten
+= blackboxPrint(def
->name
);
1019 // Do we need to print an index in brackets after the name?
1020 if (def
->fieldNameIndex
!= -1) {
1021 charsWritten
+= blackboxPrintf("[%d]", def
->fieldNameIndex
);
1024 //The other headers are integers
1025 charsWritten
+= blackboxPrintf("%d", def
->arr
[xmitState
.headerIndex
- 1]);
1030 // Did we complete this line?
1031 if (xmitState
.u
.fieldIndex
== fieldCount
) {
1032 blackboxWrite('\n');
1033 xmitState
.headerIndex
++;
1034 xmitState
.u
.fieldIndex
= -1;
1037 return xmitState
.headerIndex
< headerCount
;
1041 * Transmit a portion of the system information headers. Call the first time with xmitState.headerIndex == 0. Returns
1042 * true iff transmission is complete, otherwise call again later to continue transmission.
1044 static bool blackboxWriteSysinfo()
1046 if (xmitState
.headerIndex
== 0) {
1047 xmitState
.u
.serialBudget
= 0;
1048 xmitState
.headerIndex
= 1;
1051 // How many bytes can we afford to transmit this loop?
1052 xmitState
.u
.serialBudget
= MIN(xmitState
.u
.serialBudget
+ blackboxWriteChunkSize
, 64);
1054 // Most headers will consume at least 20 bytes so wait until we've built up that much link budget
1055 if (xmitState
.u
.serialBudget
< 20) {
1059 switch (xmitState
.headerIndex
) {
1061 //Shouldn't ever get here
1064 xmitState
.u
.serialBudget
-= blackboxPrint("H Firmware type:Cleanflight\n");
1067 xmitState
.u
.serialBudget
-= blackboxPrintf("H Firmware revision:%s\n", shortGitRevision
);
1070 xmitState
.u
.serialBudget
-= blackboxPrintf("H Firmware date:%s %s\n", buildDate
, buildTime
);
1073 xmitState
.u
.serialBudget
-= blackboxPrintf("H P interval:%d/%d\n", masterConfig
.blackbox_rate_num
, masterConfig
.blackbox_rate_denom
);
1076 xmitState
.u
.serialBudget
-= blackboxPrintf("H rcRate:%d\n", masterConfig
.controlRateProfiles
[masterConfig
.current_profile_index
].rcRate8
);
1079 xmitState
.u
.serialBudget
-= blackboxPrintf("H minthrottle:%d\n", masterConfig
.escAndServoConfig
.minthrottle
);
1082 xmitState
.u
.serialBudget
-= blackboxPrintf("H maxthrottle:%d\n", masterConfig
.escAndServoConfig
.maxthrottle
);
1085 xmitState
.u
.serialBudget
-= blackboxPrintf("H gyro.scale:0x%x\n", castFloatBytesToInt(gyro
.scale
));
1088 xmitState
.u
.serialBudget
-= blackboxPrintf("H acc_1G:%u\n", acc_1G
);
1091 if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT
)) {
1092 xmitState
.u
.serialBudget
-= blackboxPrintf("H vbatscale:%u\n", masterConfig
.batteryConfig
.vbatscale
);
1094 xmitState
.headerIndex
+= 2; // Skip the next two vbat fields too
1098 xmitState
.u
.serialBudget
-= blackboxPrintf("H vbatcellvoltage:%u,%u,%u\n", masterConfig
.batteryConfig
.vbatmincellvoltage
,
1099 masterConfig
.batteryConfig
.vbatwarningcellvoltage
, masterConfig
.batteryConfig
.vbatmaxcellvoltage
);
1102 xmitState
.u
.serialBudget
-= blackboxPrintf("H vbatref:%u\n", vbatReference
);
1105 //Note: Log even if this is a virtual current meter, since the virtual meter uses these parameters too:
1106 if (feature(FEATURE_CURRENT_METER
)) {
1107 xmitState
.u
.serialBudget
-= blackboxPrintf("H currentMeter:%d,%d\n", masterConfig
.batteryConfig
.currentMeterOffset
, masterConfig
.batteryConfig
.currentMeterScale
);
1114 xmitState
.headerIndex
++;
1119 * Write the given event to the log immediately
1121 void blackboxLogEvent(FlightLogEvent event
, flightLogEventData_t
*data
)
1123 // Only allow events to be logged after headers have been written
1124 if (!(blackboxState
== BLACKBOX_STATE_RUNNING
|| blackboxState
== BLACKBOX_STATE_PAUSED
)) {
1128 //Shared header for event frames
1130 blackboxWrite(event
);
1132 //Now serialize the data for this specific frame type
1134 case FLIGHT_LOG_EVENT_SYNC_BEEP
:
1135 blackboxWriteUnsignedVB(data
->syncBeep
.time
);
1137 case FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT
:
1138 if (data
->inflightAdjustment
.floatFlag
) {
1139 blackboxWrite(data
->inflightAdjustment
.adjustmentFunction
+ FLIGHT_LOG_EVENT_INFLIGHT_ADJUSTMENT_FUNCTION_FLOAT_VALUE_FLAG
);
1140 blackboxWriteFloat(data
->inflightAdjustment
.newFloatValue
);
1142 blackboxWrite(data
->inflightAdjustment
.adjustmentFunction
);
1143 blackboxWriteSignedVB(data
->inflightAdjustment
.newValue
);
1145 case FLIGHT_LOG_EVENT_GTUNE_RESULT
:
1146 blackboxWrite(data
->gtuneCycleResult
.gtuneAxis
);
1147 blackboxWriteSignedVB(data
->gtuneCycleResult
.gtuneGyroAVG
);
1148 blackboxWriteS16(data
->gtuneCycleResult
.gtuneNewP
);
1150 case FLIGHT_LOG_EVENT_LOGGING_RESUME
:
1151 blackboxWriteUnsignedVB(data
->loggingResume
.logIteration
);
1152 blackboxWriteUnsignedVB(data
->loggingResume
.currentTime
);
1154 case FLIGHT_LOG_EVENT_LOG_END
:
1155 blackboxPrint("End of log");
1161 /* 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 */
1162 static void blackboxCheckAndLogArmingBeep()
1164 flightLogEvent_syncBeep_t eventData
;
1166 // Use != so that we can still detect a change if the counter wraps
1167 if (getArmingBeepTimeMicros() != blackboxLastArmingBeep
) {
1168 blackboxLastArmingBeep
= getArmingBeepTimeMicros();
1170 eventData
.time
= blackboxLastArmingBeep
;
1172 blackboxLogEvent(FLIGHT_LOG_EVENT_SYNC_BEEP
, (flightLogEventData_t
*) &eventData
);
1177 * Use the user's num/denom settings to decide if the P-frame of the given index should be logged, allowing the user to control
1178 * the portion of logged loop iterations.
1180 static bool blackboxShouldLogPFrame(uint32_t pFrameIndex
)
1182 /* Adding a magic shift of "masterConfig.blackbox_rate_num - 1" in here creates a better spread of
1183 * recorded / skipped frames when the I frame's position is considered:
1185 return (pFrameIndex
+ masterConfig
.blackbox_rate_num
- 1) % masterConfig
.blackbox_rate_denom
< masterConfig
.blackbox_rate_num
;
1188 static bool blackboxShouldLogIFrame() {
1189 return blackboxPFrameIndex
== 0;
1192 // Called once every FC loop in order to keep track of how many FC loop iterations have passed
1193 static void blackboxAdvanceIterationTimers()
1195 blackboxSlowFrameIterationTimer
++;
1196 blackboxIteration
++;
1197 blackboxPFrameIndex
++;
1199 if (blackboxPFrameIndex
== BLACKBOX_I_INTERVAL
) {
1200 blackboxPFrameIndex
= 0;
1201 blackboxIFrameIndex
++;
1205 // Called once every FC loop in order to log the current state
1206 static void blackboxLogIteration()
1208 // Write a keyframe every BLACKBOX_I_INTERVAL frames so we can resynchronise upon missing frames
1209 if (blackboxShouldLogIFrame()) {
1211 * Don't log a slow frame if the slow data didn't change ("I" frames are already large enough without adding
1212 * an additional item to write at the same time). Unless we're *only* logging "I" frames, then we have no choice.
1214 writeSlowFrameIfNeeded(blackboxIsOnlyLoggingIntraframes());
1219 blackboxCheckAndLogArmingBeep();
1221 if (blackboxShouldLogPFrame(blackboxPFrameIndex
)) {
1223 * We assume that slow frames are only interesting in that they aid the interpretation of the main data stream.
1224 * So only log slow frames during loop iterations where we log a main frame.
1226 writeSlowFrameIfNeeded(true);
1232 if (feature(FEATURE_GPS
)) {
1234 * If the GPS home point has been updated, or every 128 intraframes (~10 seconds), write the
1235 * GPS home position.
1237 * We write it periodically so that if one Home Frame goes missing, the GPS coordinates can
1238 * still be interpreted correctly.
1240 if (GPS_home
[0] != gpsHistory
.GPS_home
[0] || GPS_home
[1] != gpsHistory
.GPS_home
[1]
1241 || (blackboxPFrameIndex
== BLACKBOX_I_INTERVAL
/ 2 && blackboxIFrameIndex
% 128 == 0)) {
1243 writeGPSHomeFrame();
1245 } else if (GPS_numSat
!= gpsHistory
.GPS_numSat
|| GPS_coord
[0] != gpsHistory
.GPS_coord
[0]
1246 || GPS_coord
[1] != gpsHistory
.GPS_coord
[1]) {
1247 //We could check for velocity changes as well but I doubt it changes independent of position
1254 //Flush every iteration so that our runtime variance is minimized
1255 blackboxDeviceFlush();
1259 * Call each flight loop iteration to perform blackbox logging.
1261 void handleBlackbox(void)
1265 switch (blackboxState
) {
1266 case BLACKBOX_STATE_SEND_HEADER
:
1267 //On entry of this state, xmitState.headerIndex is 0 and startTime is intialised
1270 * Once the UART has had time to init, transmit the header in chunks so we don't overflow our transmit
1273 if (millis() > xmitState
.u
.startTime
+ 100) {
1274 for (i
= 0; i
< blackboxWriteChunkSize
&& blackboxHeader
[xmitState
.headerIndex
] != '\0'; i
++, xmitState
.headerIndex
++) {
1275 blackboxWrite(blackboxHeader
[xmitState
.headerIndex
]);
1278 if (blackboxHeader
[xmitState
.headerIndex
] == '\0') {
1279 blackboxSetState(BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER
);
1283 case BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER
:
1284 //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
1285 if (!sendFieldDefinition('I', 'P', blackboxMainFields
, blackboxMainFields
+ 1, ARRAY_LENGTH(blackboxMainFields
),
1286 &blackboxMainFields
[0].condition
, &blackboxMainFields
[1].condition
)) {
1288 if (feature(FEATURE_GPS
)) {
1289 blackboxSetState(BLACKBOX_STATE_SEND_GPS_H_HEADER
);
1292 blackboxSetState(BLACKBOX_STATE_SEND_SLOW_HEADER
);
1296 case BLACKBOX_STATE_SEND_GPS_H_HEADER
:
1297 //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
1298 if (!sendFieldDefinition('H', 0, blackboxGpsHFields
, blackboxGpsHFields
+ 1, ARRAY_LENGTH(blackboxGpsHFields
),
1300 blackboxSetState(BLACKBOX_STATE_SEND_GPS_G_HEADER
);
1303 case BLACKBOX_STATE_SEND_GPS_G_HEADER
:
1304 //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
1305 if (!sendFieldDefinition('G', 0, blackboxGpsGFields
, blackboxGpsGFields
+ 1, ARRAY_LENGTH(blackboxGpsGFields
),
1306 &blackboxGpsGFields
[0].condition
, &blackboxGpsGFields
[1].condition
)) {
1307 blackboxSetState(BLACKBOX_STATE_SEND_SLOW_HEADER
);
1311 case BLACKBOX_STATE_SEND_SLOW_HEADER
:
1312 //On entry of this state, xmitState.headerIndex is 0 and xmitState.u.fieldIndex is -1
1313 if (!sendFieldDefinition('S', 0, blackboxSlowFields
, blackboxSlowFields
+ 1, ARRAY_LENGTH(blackboxSlowFields
),
1315 blackboxSetState(BLACKBOX_STATE_SEND_SYSINFO
);
1318 case BLACKBOX_STATE_SEND_SYSINFO
:
1319 //On entry of this state, xmitState.headerIndex is 0
1321 //Keep writing chunks of the system info headers until it returns true to signal completion
1322 if (blackboxWriteSysinfo()) {
1325 * Wait for header buffers to drain completely before data logging begins to ensure reliable header delivery
1326 * (overflowing circular buffers causes all data to be discarded, so the first few logged iterations
1327 * could wipe out the end of the header if we weren't careful)
1329 if (blackboxDeviceFlush()) {
1330 blackboxSetState(BLACKBOX_STATE_RUNNING
);
1334 case BLACKBOX_STATE_PAUSED
:
1335 // Only allow resume to occur during an I-frame iteration, so that we have an "I" base to work from
1336 if (IS_RC_MODE_ACTIVE(BOXBLACKBOX
) && blackboxShouldLogIFrame()) {
1337 // Write a log entry so the decoder is aware that our large time/iteration skip is intended
1338 flightLogEvent_loggingResume_t resume
;
1340 resume
.logIteration
= blackboxIteration
;
1341 resume
.currentTime
= currentTime
;
1343 blackboxLogEvent(FLIGHT_LOG_EVENT_LOGGING_RESUME
, (flightLogEventData_t
*) &resume
);
1344 blackboxSetState(BLACKBOX_STATE_RUNNING
);
1346 blackboxLogIteration();
1349 // Keep the logging timers ticking so our log iteration continues to advance
1350 blackboxAdvanceIterationTimers();
1352 case BLACKBOX_STATE_RUNNING
:
1353 // On entry to this state, blackboxIteration, blackboxPFrameIndex and blackboxIFrameIndex are reset to 0
1354 if (blackboxModeActivationConditionPresent
&& !IS_RC_MODE_ACTIVE(BOXBLACKBOX
)) {
1355 blackboxSetState(BLACKBOX_STATE_PAUSED
);
1357 blackboxLogIteration();
1360 blackboxAdvanceIterationTimers();
1362 case BLACKBOX_STATE_SHUTTING_DOWN
:
1363 //On entry of this state, startTime is set and a flush is performed
1366 * Wait for the log we've transmitted to make its way to the logger before we release the serial port,
1367 * since releasing the port clears the Tx buffer.
1369 * Don't wait longer than it could possibly take if something funky happens.
1371 if (millis() > xmitState
.u
.startTime
+ BLACKBOX_SHUTDOWN_TIMEOUT_MILLIS
|| blackboxDeviceFlush()) {
1372 blackboxDeviceClose();
1373 blackboxSetState(BLACKBOX_STATE_STOPPED
);
1380 // Did we run out of room on the device? Stop!
1381 if (isBlackboxDeviceFull()) {
1382 blackboxSetState(BLACKBOX_STATE_STOPPED
);
1386 static bool canUseBlackboxWithCurrentConfiguration(void)
1388 return feature(FEATURE_BLACKBOX
);
1392 * Call during system startup to initialize the blackbox.
1394 void initBlackbox(void)
1396 if (canUseBlackboxWithCurrentConfiguration()) {
1397 blackboxSetState(BLACKBOX_STATE_STOPPED
);
1399 blackboxSetState(BLACKBOX_STATE_DISABLED
);