Skip to content

Commit c1dc04b

Browse files
committed
cr148
1 parent cc4b9f4 commit c1dc04b

File tree

6 files changed

+120
-45
lines changed

6 files changed

+120
-45
lines changed

src/main/blackbox/blackbox.c

Lines changed: 21 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -106,6 +106,7 @@ PG_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig,
106106
.rate_num = SETTING_BLACKBOX_RATE_NUM_DEFAULT,
107107
.rate_denom = SETTING_BLACKBOX_RATE_DENOM_DEFAULT,
108108
.invertedCardDetection = BLACKBOX_INVERTED_CARD_DETECTION,
109+
.arm_control = SETTING_BLACKBOX_ARM_CONTROL_DEFAULT, // CR148
109110
.includeFlags = BLACKBOX_FEATURE_NAV_PID | BLACKBOX_FEATURE_NAV_POS |
110111
BLACKBOX_FEATURE_MAG | BLACKBOX_FEATURE_ACC | BLACKBOX_FEATURE_ATTITUDE |
111112
BLACKBOX_FEATURE_RC_DATA | BLACKBOX_FEATURE_RC_COMMAND |
@@ -469,20 +470,20 @@ static const blackboxSimpleFieldDefinition_t blackboxSlowFields[] = {
469470
#endif
470471
};
471472

472-
typedef enum BlackboxState {
473-
BLACKBOX_STATE_DISABLED = 0,
474-
BLACKBOX_STATE_STOPPED,
475-
BLACKBOX_STATE_PREPARE_LOG_FILE,
476-
BLACKBOX_STATE_SEND_HEADER,
477-
BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER,
478-
BLACKBOX_STATE_SEND_GPS_H_HEADER,
479-
BLACKBOX_STATE_SEND_GPS_G_HEADER,
480-
BLACKBOX_STATE_SEND_SLOW_HEADER,
481-
BLACKBOX_STATE_SEND_SYSINFO,
482-
BLACKBOX_STATE_PAUSED,
483-
BLACKBOX_STATE_RUNNING,
484-
BLACKBOX_STATE_SHUTTING_DOWN
485-
} BlackboxState;
473+
// typedef enum BlackboxState {
474+
// BLACKBOX_STATE_DISABLED = 0,
475+
// BLACKBOX_STATE_STOPPED,
476+
// BLACKBOX_STATE_PREPARE_LOG_FILE,
477+
// BLACKBOX_STATE_SEND_HEADER,
478+
// BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER,
479+
// BLACKBOX_STATE_SEND_GPS_H_HEADER,
480+
// BLACKBOX_STATE_SEND_GPS_G_HEADER,
481+
// BLACKBOX_STATE_SEND_SLOW_HEADER,
482+
// BLACKBOX_STATE_SEND_SYSINFO,
483+
// BLACKBOX_STATE_PAUSED,
484+
// BLACKBOX_STATE_RUNNING,
485+
// BLACKBOX_STATE_SHUTTING_DOWN
486+
// } BlackboxState;
486487

487488
#define BLACKBOX_FIRST_HEADER_SENDING_STATE BLACKBOX_STATE_SEND_HEADER
488489
#define BLACKBOX_LAST_HEADER_SENDING_STATE BLACKBOX_STATE_SEND_SYSINFO
@@ -2322,7 +2323,12 @@ static bool canUseBlackboxWithCurrentConfiguration(void)
23222323
{
23232324
return feature(FEATURE_BLACKBOX);
23242325
}
2325-
2326+
// CR148
2327+
BlackboxState getBlackboxState(void)
2328+
{
2329+
return blackboxState;
2330+
}
2331+
// CR148
23262332
/**
23272333
* Call during system startup to initialize the blackbox.
23282334
*/

src/main/blackbox/blackbox.h

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -37,12 +37,29 @@ typedef enum {
3737
BLACKBOX_FEATURE_GYRO_PEAKS_YAW = 1 << 12,
3838
BLACKBOX_FEATURE_SERVOS = 1 << 13,
3939
} blackboxFeatureMask_e;
40+
// CR148
41+
typedef enum BlackboxState {
42+
BLACKBOX_STATE_DISABLED = 0,
43+
BLACKBOX_STATE_STOPPED,
44+
BLACKBOX_STATE_PREPARE_LOG_FILE,
45+
BLACKBOX_STATE_SEND_HEADER,
46+
BLACKBOX_STATE_SEND_MAIN_FIELD_HEADER,
47+
BLACKBOX_STATE_SEND_GPS_H_HEADER,
48+
BLACKBOX_STATE_SEND_GPS_G_HEADER,
49+
BLACKBOX_STATE_SEND_SLOW_HEADER,
50+
BLACKBOX_STATE_SEND_SYSINFO,
51+
BLACKBOX_STATE_PAUSED,
52+
BLACKBOX_STATE_RUNNING,
53+
BLACKBOX_STATE_SHUTTING_DOWN
54+
} BlackboxState;
55+
// CR148
4056
typedef struct blackboxConfig_s {
4157
uint16_t rate_num;
4258
uint16_t rate_denom;
4359
uint8_t device;
4460
uint8_t invertedCardDetection;
4561
uint32_t includeFlags;
62+
int8_t arm_control; // CR148
4663
} blackboxConfig_t;
4764

4865
PG_DECLARE(blackboxConfig_t, blackboxConfig);
@@ -57,3 +74,4 @@ bool blackboxMayEditConfig(void);
5774
void blackboxIncludeFlagSet(uint32_t mask);
5875
void blackboxIncludeFlagClear(uint32_t mask);
5976
bool blackboxIncludeFlag(uint32_t mask);
77+
BlackboxState getBlackboxState(void); // CR148

src/main/fc/fc_core.c

Lines changed: 60 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222
#include "platform.h"
2323

2424
#include "blackbox/blackbox.h"
25+
#include "blackbox/blackbox_io.h" // CR148
2526

2627
#include "build/debug.h"
2728

@@ -279,20 +280,16 @@ static void updateArmingStatus(void)
279280
#endif
280281

281282
#ifdef USE_GEOZONE
282-
if (feature(FEATURE_GEOZONE) && geozoneIsBlockingArming()) {
283-
ENABLE_ARMING_FLAG(ARMING_DISABLED_GEOZONE);
284-
} else {
285-
DISABLE_ARMING_FLAG(ARMING_DISABLED_GEOZONE);
286-
}
283+
if (feature(FEATURE_GEOZONE) && geozoneIsBlockingArming()) {
284+
ENABLE_ARMING_FLAG(ARMING_DISABLED_GEOZONE);
285+
} else {
286+
DISABLE_ARMING_FLAG(ARMING_DISABLED_GEOZONE);
287+
}
287288
#endif
288289

289290
/* CHECK: */
290-
if (
291-
sensors(SENSOR_ACC) &&
292-
!STATE(ACCELEROMETER_CALIBRATED) &&
293-
// Require ACC calibration only if any of the setting might require it
294-
isAccRequired()
295-
) {
291+
// Require ACC calibration only if any of the setting might require it
292+
if (sensors(SENSOR_ACC) && !STATE(ACCELEROMETER_CALIBRATED) && isAccRequired()) {
296293
ENABLE_ARMING_FLAG(ARMING_DISABLED_ACCELEROMETER_NOT_CALIBRATED);
297294
}
298295
else {
@@ -443,11 +440,11 @@ void disarm(disarmReason_t disarmReason)
443440
DISABLE_ARMING_FLAG(ARMED);
444441
DISABLE_STATE(IN_FLIGHT_EMERG_REARM);
445442

446-
#ifdef USE_BLACKBOX
447-
if (feature(FEATURE_BLACKBOX)) {
448-
blackboxFinish();
449-
}
450-
#endif
443+
// #ifdef USE_BLACKBOX // CR148
444+
// if (feature(FEATURE_BLACKBOX)) {
445+
// blackboxFinish();
446+
// }
447+
// #endif
451448
#ifdef USE_DSHOT
452449
if (FLIGHT_MODE(TURTLE_MODE)) {
453450
sendDShotCommand(DSHOT_CMD_SPIN_DIRECTION_NORMAL);
@@ -589,15 +586,15 @@ void tryArm(void)
589586

590587
resetHeadingHoldTarget(DECIDEGREES_TO_DEGREES(attitude.values.yaw));
591588

592-
#ifdef USE_BLACKBOX
593-
if (feature(FEATURE_BLACKBOX)) {
594-
serialPort_t *sharedBlackboxAndMspPort = findSharedSerialPort(FUNCTION_BLACKBOX, FUNCTION_MSP);
595-
if (sharedBlackboxAndMspPort) {
596-
mspSerialReleasePortIfAllocated(sharedBlackboxAndMspPort);
597-
}
598-
blackboxStart();
599-
}
600-
#endif
589+
// #ifdef USE_BLACKBOX // CR148
590+
// if (feature(FEATURE_BLACKBOX)) {
591+
// serialPort_t *sharedBlackboxAndMspPort = findSharedSerialPort(FUNCTION_BLACKBOX, FUNCTION_MSP);
592+
// if (sharedBlackboxAndMspPort) {
593+
// mspSerialReleasePortIfAllocated(sharedBlackboxAndMspPort);
594+
// }
595+
// blackboxStart();
596+
// }
597+
// #endif
601598

602599
//beep to indicate arming
603600
if (navigationPositionEstimateIsHealthy()) {
@@ -879,10 +876,45 @@ static void applyThrottleTiltCompensation(void)
879876
}
880877
}
881878
}
879+
// CR148
880+
bool isMspConfigActive(bool isActive)
881+
{
882+
static timeMs_t lastActive = 0;
882883

883-
void taskMainPidLoop(timeUs_t currentTimeUs)
884+
if (isActive) {
885+
lastActive = millis();
886+
}
887+
888+
return millis() - lastActive < 1000;
889+
}
890+
#ifdef USE_BLACKBOX
891+
static void processBlackbox(void)
884892
{
893+
if (getBlackboxState() == BLACKBOX_STATE_DISABLED || isBlackboxDeviceFull()) {
894+
return;
895+
}
885896

897+
if (getBlackboxState() == BLACKBOX_STATE_STOPPED) {
898+
if ((blackboxConfig()->arm_control == -1 && !areSensorsCalibrating() && !isMspConfigActive(NULL)) || ARMING_FLAG(ARMED)) {
899+
serialPort_t *sharedBlackboxAndMspPort = findSharedSerialPort(FUNCTION_BLACKBOX, FUNCTION_MSP);
900+
if (sharedBlackboxAndMspPort) {
901+
mspSerialReleasePortIfAllocated(sharedBlackboxAndMspPort);
902+
}
903+
blackboxStart();
904+
}
905+
} else if (!ARMING_FLAG(ARMED)) {
906+
if ((blackboxConfig()->arm_control == -1 && isMspConfigActive(NULL)) ||
907+
(blackboxConfig()->arm_control >= 0 && micros() - lastDisarmTimeUs > (timeUs_t)(USECS_PER_SEC * blackboxConfig()->arm_control))) {
908+
blackboxFinish();
909+
}
910+
}
911+
912+
blackboxUpdate(micros());
913+
}
914+
#endif
915+
// CR148
916+
void taskMainPidLoop(timeUs_t currentTimeUs)
917+
{
886918
cycleTime = getTaskDeltaTime(TASK_SELF);
887919
dT = (float)cycleTime * 0.000001f;
888920

@@ -981,7 +1013,8 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
9811013

9821014
#ifdef USE_BLACKBOX
9831015
if (!cliMode && feature(FEATURE_BLACKBOX)) {
984-
blackboxUpdate(micros());
1016+
processBlackbox();
1017+
// blackboxUpdate(micros()); // CR148
9851018
}
9861019
#endif
9871020

src/main/fc/fc_core.h

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -47,4 +47,6 @@ float getFlightTime(void);
4747
void resetFlightTime(void);
4848
float getArmTime(void);
4949

50-
void fcReboot(bool bootLoader);
50+
void fcReboot(bool bootLoader);
51+
52+
bool isMspConfigActive(bool isActive); // CR148

src/main/fc/fc_msp.c

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -422,6 +422,8 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
422422
sbufWriteU8(dst, getHwRangefinderStatus());
423423
sbufWriteU8(dst, getHwPitotmeterStatus());
424424
sbufWriteU8(dst, getHwOpticalFlowStatus());
425+
426+
isMspConfigActive(true); // CR148
425427
break;
426428

427429
case MSP_ACTIVEBOXES:
@@ -2814,7 +2816,13 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
28142816

28152817
#ifdef USE_FLASHFS
28162818
case MSP_DATAFLASH_ERASE:
2817-
flashfsEraseCompletely();
2819+
// CR148
2820+
if (blackboxMayEditConfig()) {
2821+
flashfsEraseCompletely();
2822+
} else {
2823+
return MSP_RESULT_ERROR;
2824+
}
2825+
// CR148
28182826
break;
28192827
#endif
28202828

src/main/fc/settings.yaml

Lines changed: 9 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -819,6 +819,14 @@ groups:
819819
field: invertedCardDetection
820820
condition: USE_SDCARD
821821
type: bool
822+
# CR148
823+
- name: blackbox_arm_control
824+
description: "Determines behaviour of logging in relation to Arm state. For settings from 0 to 60 logging will start on Arm with the setting determining how long logging will continue after disarm in seconds, i.e. set to 0 to stop logging at disarm or 10 to stop logging 10s after disarm. Set to -1 to start logging from boot up until power off (Use with caution - mainly for debugging and best used with BLACKBOX mode)."
825+
default_value: 0
826+
field: arm_control
827+
min: -1
828+
max: 60
829+
# CR148
822830

823831
- name: PG_MOTOR_CONFIG
824832
type: motorConfig_t
@@ -2177,7 +2185,7 @@ groups:
21772185
max: 255
21782186
- name: nav_fw_pos_z_ff
21792187
description: "FF gain of altitude PID controller (Fixedwing)"
2180-
default_value: 10
2188+
default_value: 35
21812189
field: bank_fw.pid[PID_POS_Z].FF
21822190
min: 0
21832191
max: 255

0 commit comments

Comments
 (0)