mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 04:45:24 +03:00
Merge branch 'master' of https://github.com/borisbstyle/betaflight
This commit is contained in:
commit
6f06561782
4 changed files with 79 additions and 6 deletions
|
@ -893,6 +893,61 @@ void finishBlackbox(void)
|
|||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Test Motors Blackbox Logging
|
||||
*/
|
||||
bool startedLoggingInTestMode = false;
|
||||
|
||||
void startInTestMode(void)
|
||||
{
|
||||
if(!startedLoggingInTestMode) {
|
||||
if (masterConfig.blackbox_device == BLACKBOX_DEVICE_SERIAL) {
|
||||
serialPort_t *sharedBlackboxAndMspPort = findSharedSerialPort(FUNCTION_BLACKBOX, FUNCTION_MSP);
|
||||
if (sharedBlackboxAndMspPort) {
|
||||
return; // When in test mode, we cannot share the MSP and serial logger port!
|
||||
}
|
||||
}
|
||||
startBlackbox();
|
||||
startedLoggingInTestMode = true;
|
||||
}
|
||||
}
|
||||
void stopInTestMode(void)
|
||||
{
|
||||
if(startedLoggingInTestMode) {
|
||||
finishBlackbox();
|
||||
startedLoggingInTestMode = false;
|
||||
}
|
||||
}
|
||||
/**
|
||||
* We are going to monitor the MSP_SET_MOTOR target variables motor_disarmed[] for values other than minthrottle
|
||||
* on reading a value (i.e. the user is testing the motors), then we enable test mode logging;
|
||||
* we monitor when the values return to minthrottle and start a delay timer (5 seconds); if
|
||||
* the test motors are left at minimum throttle for this delay timer, then we assume we are done testing and
|
||||
* shutdown the logger.
|
||||
*
|
||||
* Of course, after the 5 seconds and shutdown of the logger, the system will be re-enabled to allow the
|
||||
* test mode to trigger again; its just that the data will be in a second, third, fourth etc log file.
|
||||
*/
|
||||
bool inMotorTestMode(void) {
|
||||
static uint32_t resetTime = 0;
|
||||
uint16_t inactiveMotorCommand = (feature(FEATURE_3D) ? masterConfig.flight3DConfig.neutral3d : masterConfig.escAndServoConfig.mincommand);
|
||||
int i;
|
||||
bool atLeastOneMotorActivated = false;
|
||||
|
||||
// set disarmed motor values
|
||||
for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
|
||||
atLeastOneMotorActivated |= (motor_disarmed[i] != inactiveMotorCommand);
|
||||
|
||||
if(atLeastOneMotorActivated) {
|
||||
resetTime = millis() + 5000; // add 5 seconds
|
||||
return true;
|
||||
} else {
|
||||
// Monitor the duration at minimum
|
||||
return (millis() < resetTime);
|
||||
}
|
||||
return false;
|
||||
}
|
||||
|
||||
#ifdef GPS
|
||||
static void writeGPSHomeFrame()
|
||||
{
|
||||
|
@ -1533,7 +1588,8 @@ void handleBlackbox(void)
|
|||
break;
|
||||
case BLACKBOX_STATE_RUNNING:
|
||||
// On entry to this state, blackboxIteration, blackboxPFrameIndex and blackboxIFrameIndex are reset to 0
|
||||
if (blackboxModeActivationConditionPresent && !IS_RC_MODE_ACTIVE(BOXBLACKBOX)) {
|
||||
// Prevent the Pausing of the log on the mode switch if in Motor Test Mode
|
||||
if (blackboxModeActivationConditionPresent && !IS_RC_MODE_ACTIVE(BOXBLACKBOX) && !startedLoggingInTestMode) {
|
||||
blackboxSetState(BLACKBOX_STATE_PAUSED);
|
||||
} else {
|
||||
blackboxLogIteration();
|
||||
|
@ -1562,6 +1618,20 @@ void handleBlackbox(void)
|
|||
// Did we run out of room on the device? Stop!
|
||||
if (isBlackboxDeviceFull()) {
|
||||
blackboxSetState(BLACKBOX_STATE_STOPPED);
|
||||
// ensure we reset the test mode flag if we stop due to full memory card
|
||||
if (startedLoggingInTestMode) startedLoggingInTestMode = false;
|
||||
} else { // Only log in test mode if there is room!
|
||||
|
||||
if(masterConfig.blackbox_on_motor_test) {
|
||||
// Handle Motor Test Mode
|
||||
if(inMotorTestMode()) {
|
||||
if(blackboxState==BLACKBOX_STATE_STOPPED)
|
||||
startInTestMode();
|
||||
} else {
|
||||
if(blackboxState!=BLACKBOX_STATE_STOPPED)
|
||||
stopInTestMode();
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -172,7 +172,7 @@ static uint32_t activeFeaturesLatch = 0;
|
|||
static uint8_t currentControlRateProfileIndex = 0;
|
||||
controlRateConfig_t *currentControlRateProfile;
|
||||
|
||||
static const uint8_t EEPROM_CONF_VERSION = 143;
|
||||
static const uint8_t EEPROM_CONF_VERSION = 144;
|
||||
|
||||
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
|
||||
{
|
||||
|
@ -680,6 +680,7 @@ void createDefaultConfig(master_t *config)
|
|||
|
||||
config->blackbox_rate_num = 1;
|
||||
config->blackbox_rate_denom = 1;
|
||||
config->blackbox_on_motor_test = 0; // default off
|
||||
#endif // BLACKBOX
|
||||
|
||||
#ifdef SERIALRX_UART
|
||||
|
|
|
@ -159,6 +159,7 @@ typedef struct master_t {
|
|||
uint8_t blackbox_rate_num;
|
||||
uint8_t blackbox_rate_denom;
|
||||
uint8_t blackbox_device;
|
||||
uint8_t blackbox_on_motor_test;
|
||||
#endif
|
||||
|
||||
uint32_t beeper_off_flags;
|
||||
|
|
|
@ -849,11 +849,11 @@ const clivalue_t valueTable[] = {
|
|||
{ "iterm_throttle_gain", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.itermThrottleGain, .config.minmax = {0, 200 } },
|
||||
{ "pterm_setpoint_weight", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.ptermSetpointWeight, .config.minmax = {30, 100 } },
|
||||
{ "dterm_setpoint_weight", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dtermSetpointWeight, .config.minmax = {0, 200 } },
|
||||
{ "yaw_rate_acceleration_limit",VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawRateAccelLimit, .config.minmax = {0, 1000 } },
|
||||
{ "rate_acceleration_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rateAccelLimit, .config.minmax = {0, 1000 } },
|
||||
{ "yaw_rate_accel_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawRateAccelLimit, .config.minmax = {0, 1000 } },
|
||||
{ "rate_accel_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rateAccelLimit, .config.minmax = {0, 1000 } },
|
||||
|
||||
{ "iterm_ignore_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermIgnoreRate, .config.minmax = {15, 1000 } },
|
||||
{ "yaw_iterm_ignore_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermIgnoreRate, .config.minmax = {15, 1000 } },
|
||||
{ "accumulation_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermIgnoreRate, .config.minmax = {15, 1000 } },
|
||||
{ "yaw_accumulation_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermIgnoreRate, .config.minmax = {15, 1000 } },
|
||||
{ "yaw_lowpass", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_lpf_hz, .config.minmax = {0, 500 } },
|
||||
{ "pid_process_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.pid_process_denom, .config.minmax = { 1, 8 } },
|
||||
|
||||
|
@ -885,6 +885,7 @@ const clivalue_t valueTable[] = {
|
|||
{ "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, .config.minmax = { 1, 32 } },
|
||||
{ "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, .config.minmax = { 1, 32 } },
|
||||
{ "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.blackbox_device, .config.lookup = { TABLE_BLACKBOX_DEVICE } },
|
||||
{ "blackbox_on_motor_test", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.blackbox_on_motor_test, .config.lookup = { TABLE_OFF_ON } },
|
||||
#endif
|
||||
|
||||
#ifdef VTX
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue