Added beeps to indicate the reason for arming being disabled.

This commit is contained in:
mikeller 2017-07-02 17:13:12 +12:00
parent 31c639b13f
commit 67acc6c7ec
12 changed files with 109 additions and 61 deletions

View File

@ -162,49 +162,45 @@ void delay(uint32_t ms)
} }
#define SHORT_FLASH_DURATION 50 #define SHORT_FLASH_DURATION 50
#define SHORT_FLASH_COUNT 5
#define CODE_FLASH_DURATION 250 #define CODE_FLASH_DURATION 250
void failureLedCode(failureMode_e mode, int codeRepeatsRemaining) static void indicate(uint8_t count, uint16_t duration)
{ {
int codeFlashesRemaining; if (count) {
int shortFlashesRemaining;
while (codeRepeatsRemaining--) {
LED1_ON; LED1_ON;
LED0_OFF; LED0_OFF;
shortFlashesRemaining = 5;
codeFlashesRemaining = mode + 1;
uint8_t flashDuration = SHORT_FLASH_DURATION;
while (shortFlashesRemaining || codeFlashesRemaining) { while (count--) {
LED1_TOGGLE; LED1_TOGGLE;
LED0_TOGGLE; LED0_TOGGLE;
BEEP_ON; BEEP_ON;
delay(flashDuration); delay(duration);
LED1_TOGGLE; LED1_TOGGLE;
LED0_TOGGLE; LED0_TOGGLE;
BEEP_OFF; BEEP_OFF;
delay(flashDuration); delay(duration);
if (shortFlashesRemaining) {
shortFlashesRemaining--;
if (shortFlashesRemaining == 0) {
delay(500);
flashDuration = CODE_FLASH_DURATION;
}
} else {
codeFlashesRemaining--;
}
} }
}
}
void indicateFailure(failureMode_e mode, int codeRepeatsRemaining)
{
while (codeRepeatsRemaining--) {
indicate(SHORT_FLASH_COUNT, SHORT_FLASH_DURATION);
delay(500);
indicate(mode + 1, CODE_FLASH_DURATION);
delay(1000); delay(1000);
} }
} }
void failureMode(failureMode_e mode) void failureMode(failureMode_e mode)
{ {
failureLedCode(mode, 10); indicateFailure(mode, 10);
#ifdef DEBUG #ifdef DEBUG
systemReset(); systemReset();

View File

@ -33,7 +33,7 @@ typedef enum {
} failureMode_e; } failureMode_e;
// failure // failure
void failureLedCode(failureMode_e mode, int repeatCount); void indicateFailure(failureMode_e mode, int repeatCount);
void failureMode(failureMode_e mode); void failureMode(failureMode_e mode);
// bootloader/IAP // bootloader/IAP

View File

@ -17,6 +17,7 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <string.h>
#include "platform.h" #include "platform.h"
@ -35,6 +36,7 @@
#include "drivers/gyro_sync.h" #include "drivers/gyro_sync.h"
#include "drivers/light_led.h" #include "drivers/light_led.h"
#include "drivers/system.h"
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/transponder_ir.h" #include "drivers/transponder_ir.h"
@ -111,7 +113,7 @@ static bool reverseMotors = false;
static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero static uint32_t disarmAt; // Time of automatic disarm when "Don't spin the motors when armed" is enabled and auto_disarm_delay is nonzero
bool isRXDataNew; bool isRXDataNew;
static bool armingCalibrationWasInitialised; static int lastArmingDisabledReason = 0;
PG_REGISTER_WITH_RESET_TEMPLATE(throttleCorrectionConfig_t, throttleCorrectionConfig, PG_THROTTLE_CORRECTION_CONFIG, 0); PG_REGISTER_WITH_RESET_TEMPLATE(throttleCorrectionConfig_t, throttleCorrectionConfig, PG_THROTTLE_CORRECTION_CONFIG, 0);
@ -141,6 +143,11 @@ static bool isCalibrating()
return (!isAccelerationCalibrationComplete() && sensors(SENSOR_ACC)) || (!isGyroCalibrationComplete()); return (!isAccelerationCalibrationComplete() && sensors(SENSOR_ACC)) || (!isGyroCalibrationComplete());
} }
void resetArmingDisabled(void)
{
lastArmingDisabledReason = 0;
}
void updateArmingStatus(void) void updateArmingStatus(void)
{ {
if (ARMING_FLAG(ARMED)) { if (ARMING_FLAG(ARMED)) {
@ -188,8 +195,6 @@ void updateArmingStatus(void)
void disarm(void) void disarm(void)
{ {
armingCalibrationWasInitialised = false;
if (ARMING_FLAG(ARMED)) { if (ARMING_FLAG(ARMED)) {
DISABLE_ARMING_FLAG(ARMED); DISABLE_ARMING_FLAG(ARMED);
@ -205,12 +210,8 @@ void disarm(void)
void tryArm(void) void tryArm(void)
{ {
static bool firstArmingCalibrationWasCompleted; if (armingConfig()->gyro_cal_on_first_arm) {
gyroStartCalibration(true);
if (armingConfig()->gyro_cal_on_first_arm && !firstArmingCalibrationWasCompleted) {
gyroStartCalibration();
armingCalibrationWasInitialised = true;
firstArmingCalibrationWasCompleted = true;
} }
updateArmingStatus(); updateArmingStatus();
@ -233,7 +234,7 @@ void tryArm(void)
pwmWriteDshotCommand(index, DSHOT_CMD_SPIN_DIRECTION_REVERSED); pwmWriteDshotCommand(index, DSHOT_CMD_SPIN_DIRECTION_REVERSED);
} }
} }
} }
#endif #endif
ENABLE_ARMING_FLAG(ARMED); ENABLE_ARMING_FLAG(ARMED);
@ -242,6 +243,8 @@ void tryArm(void)
disarmAt = millis() + armingConfig()->auto_disarm_delay * 1000; // start disarm timeout, will be extended when throttle is nonzero disarmAt = millis() + armingConfig()->auto_disarm_delay * 1000; // start disarm timeout, will be extended when throttle is nonzero
lastArmingDisabledReason = 0;
//beep to indicate arming //beep to indicate arming
#ifdef GPS #ifdef GPS
if (feature(FEATURE_GPS) && STATE(GPS_FIX) && gpsSol.numSat >= 5) { if (feature(FEATURE_GPS) && STATE(GPS_FIX) && gpsSol.numSat >= 5) {
@ -252,12 +255,15 @@ void tryArm(void)
#else #else
beeper(BEEPER_ARMING); beeper(BEEPER_ARMING);
#endif #endif
} else {
if (!isFirstArmingGyroCalibrationRunning()) {
int armingDisabledReason = ffs(getArmingDisableFlags());
if (lastArmingDisabledReason != armingDisabledReason) {
lastArmingDisabledReason = armingDisabledReason;
return; beeperWarningBeeps(armingDisabledReason);
} }
}
if (!ARMING_FLAG(ARMED)) {
beeperConfirmationBeeps(1);
} }
} }

View File

@ -40,6 +40,8 @@ union rollAndPitchTrims_u;
void applyAndSaveAccelerometerTrimsDelta(union rollAndPitchTrims_u *rollAndPitchTrimsDelta); void applyAndSaveAccelerometerTrimsDelta(union rollAndPitchTrims_u *rollAndPitchTrimsDelta);
void handleInflightCalibrationStickPosition(); void handleInflightCalibrationStickPosition();
void resetArmingDisabled(void);
void disarm(void); void disarm(void);
void tryArm(void); void tryArm(void);

View File

@ -481,7 +481,7 @@ void init(void)
if (!sensorsAutodetect()) { if (!sensorsAutodetect()) {
// if gyro was not detected due to whatever reason, notify and don't arm. // if gyro was not detected due to whatever reason, notify and don't arm.
failureLedCode(FAILURE_MISSING_ACC, 2); indicateFailure(FAILURE_MISSING_ACC, 2);
setArmingDisabled(ARMING_DISABLED_NO_GYRO); setArmingDisabled(ARMING_DISABLED_NO_GYRO);
} }
@ -632,7 +632,7 @@ void init(void)
if (mixerConfig()->mixerMode == MIXER_GIMBAL) { if (mixerConfig()->mixerMode == MIXER_GIMBAL) {
accSetCalibrationCycles(CALIBRATING_ACC_CYCLES); accSetCalibrationCycles(CALIBRATING_ACC_CYCLES);
} }
gyroStartCalibration(); gyroStartCalibration(false);
#ifdef BARO #ifdef BARO
baroSetCalibrationCycles(CALIBRATING_BARO_CYCLES); baroSetCalibrationCycles(CALIBRATING_BARO_CYCLES);
#endif #endif

View File

@ -147,6 +147,7 @@ void processRcStickPositions(throttleStatus_e throttleStatus)
tryArm(); tryArm();
} else { } else {
// Disarming via ARM BOX // Disarming via ARM BOX
resetArmingDisabled();
if (ARMING_FLAG(ARMED) && rxIsReceivingSignal() && !failsafeIsActive() ) { if (ARMING_FLAG(ARMED) && rxIsReceivingSignal() && !failsafeIsActive() ) {
rcDisarmTicks++; rcDisarmTicks++;
@ -187,7 +188,7 @@ void processRcStickPositions(throttleStatus_e throttleStatus)
if (rcSticks == THR_LO + YAW_LO + PIT_LO + ROL_CE) { if (rcSticks == THR_LO + YAW_LO + PIT_LO + ROL_CE) {
// GYRO calibration // GYRO calibration
gyroStartCalibration(); gyroStartCalibration(false);
#ifdef GPS #ifdef GPS
if (feature(FEATURE_GPS)) { if (feature(FEATURE_GPS)) {
@ -232,6 +233,8 @@ void processRcStickPositions(throttleStatus_e throttleStatus)
tryArm(); tryArm();
return; return;
} else {
resetArmingDisabled();
} }
} }

View File

@ -78,7 +78,7 @@ PG_RESET_TEMPLATE(beeperDevConfig_t, beeperDevConfig,
#define BEEPER_NAMES #define BEEPER_NAMES
#endif #endif
#define MAX_MULTI_BEEPS 20 //size limit for 'beep_multiBeeps[]' #define MAX_MULTI_BEEPS 64 //size limit for 'beep_multiBeeps[]'
#define BEEPER_COMMAND_REPEAT 0xFE #define BEEPER_COMMAND_REPEAT 0xFE
#define BEEPER_COMMAND_STOP 0xFF #define BEEPER_COMMAND_STOP 0xFF
@ -151,11 +151,15 @@ static const uint8_t beep_gyroCalibrated[] = {
}; };
// array used for variable # of beeps (reporting GPS sat count, etc) // array used for variable # of beeps (reporting GPS sat count, etc)
static uint8_t beep_multiBeeps[MAX_MULTI_BEEPS + 2]; static uint8_t beep_multiBeeps[MAX_MULTI_BEEPS + 1];
#define BEEPER_CONFIRMATION_BEEP_DURATION 2 #define BEEPER_CONFIRMATION_BEEP_DURATION 2
#define BEEPER_CONFIRMATION_BEEP_GAP_DURATION 20 #define BEEPER_CONFIRMATION_BEEP_GAP_DURATION 20
#define BEEPER_WARNING_BEEP_1_DURATION 20
#define BEEPER_WARNING_BEEP_2_DURATION 5
#define BEEPER_WARNING_BEEP_GAP_DURATION 10
// Beeper off = 0 Beeper on = 1 // Beeper off = 0 Beeper on = 1
static uint8_t beeperIsOn = 0; static uint8_t beeperIsOn = 0;
@ -270,25 +274,43 @@ void beeperSilence(void)
currentBeeperEntry = NULL; currentBeeperEntry = NULL;
} }
/* /*
* Emits the given number of 20ms beeps (with 200ms spacing). * Emits the given number of 20ms beeps (with 200ms spacing).
* This function returns immediately (does not block). * This function returns immediately (does not block).
*/ */
void beeperConfirmationBeeps(uint8_t beepCount) void beeperConfirmationBeeps(uint8_t beepCount)
{ {
int i; uint32_t i = 0;
int cLimit; uint32_t cLimit = beepCount * 2;
if (cLimit > MAX_MULTI_BEEPS) {
i = 0; cLimit = MAX_MULTI_BEEPS;
cLimit = beepCount * 2; }
if(cLimit > MAX_MULTI_BEEPS)
cLimit = MAX_MULTI_BEEPS; //stay within array size
do { do {
beep_multiBeeps[i++] = BEEPER_CONFIRMATION_BEEP_DURATION; // 20ms beep beep_multiBeeps[i++] = BEEPER_CONFIRMATION_BEEP_DURATION;
beep_multiBeeps[i++] = BEEPER_CONFIRMATION_BEEP_GAP_DURATION; // 200ms pause beep_multiBeeps[i++] = BEEPER_CONFIRMATION_BEEP_GAP_DURATION;
} while (i < cLimit); } while (i < cLimit);
beep_multiBeeps[i] = BEEPER_COMMAND_STOP; //sequence end beep_multiBeeps[i] = BEEPER_COMMAND_STOP;
beeper(BEEPER_MULTI_BEEPS); //initiate sequence
beeper(BEEPER_MULTI_BEEPS);
}
void beeperWarningBeeps(uint8_t beepCount)
{
uint32_t i = 0;
uint32_t cLimit = beepCount * 4;
if (cLimit >= MAX_MULTI_BEEPS) {
cLimit = MAX_MULTI_BEEPS;
}
do {
beep_multiBeeps[i++] = BEEPER_WARNING_BEEP_1_DURATION;
beep_multiBeeps[i++] = BEEPER_WARNING_BEEP_GAP_DURATION;
beep_multiBeeps[i++] = BEEPER_WARNING_BEEP_2_DURATION;
beep_multiBeeps[i++] = BEEPER_WARNING_BEEP_GAP_DURATION;
} while (i < cLimit);
beep_multiBeeps[i] = BEEPER_COMMAND_STOP;
beeper(BEEPER_MULTI_BEEPS);
} }
#ifdef GPS #ifdef GPS
@ -302,7 +324,7 @@ void beeperGpsStatus(void)
beep_multiBeeps[i++] = 10; beep_multiBeeps[i++] = 10;
} while (i < MAX_MULTI_BEEPS && gpsSol.numSat > i / 2); } while (i < MAX_MULTI_BEEPS && gpsSol.numSat > i / 2);
beep_multiBeeps[i-1] = 50; // extend last pause beep_multiBeeps[i - 1] = 50; // extend last pause
beep_multiBeeps[i] = BEEPER_COMMAND_STOP; beep_multiBeeps[i] = BEEPER_COMMAND_STOP;
beeper(BEEPER_MULTI_BEEPS); //initiate sequence beeper(BEEPER_MULTI_BEEPS); //initiate sequence
@ -444,6 +466,7 @@ bool isBeeperOn(void)
void beeper(beeperMode_e mode) {UNUSED(mode);} void beeper(beeperMode_e mode) {UNUSED(mode);}
void beeperSilence(void) {} void beeperSilence(void) {}
void beeperConfirmationBeeps(uint8_t beepCount) {UNUSED(beepCount);} void beeperConfirmationBeeps(uint8_t beepCount) {UNUSED(beepCount);}
void beeperWarningBeeps(uint8_t beepCount) {UNUSED(beepCount);}
void beeperUpdate(timeUs_t currentTimeUs) {UNUSED(currentTimeUs);} void beeperUpdate(timeUs_t currentTimeUs) {UNUSED(currentTimeUs);}
uint32_t getArmingBeepTimeMicros(void) {return 0;} uint32_t getArmingBeepTimeMicros(void) {return 0;}
beeperMode_e beeperModeForTableIndex(int idx) {UNUSED(idx); return BEEPER_SILENCE;} beeperMode_e beeperModeForTableIndex(int idx) {UNUSED(idx); return BEEPER_SILENCE;}

View File

@ -61,6 +61,7 @@ void beeper(beeperMode_e mode);
void beeperSilence(void); void beeperSilence(void);
void beeperUpdate(timeUs_t currentTimeUs); void beeperUpdate(timeUs_t currentTimeUs);
void beeperConfirmationBeeps(uint8_t beepCount); void beeperConfirmationBeeps(uint8_t beepCount);
void beeperWarningBeeps(uint8_t beepCount);
uint32_t getArmingBeepTimeMicros(void); uint32_t getArmingBeepTimeMicros(void);
beeperMode_e beeperModeForTableIndex(int idx); beeperMode_e beeperModeForTableIndex(int idx);
const char *beeperNameForTableIndex(int idx); const char *beeperNameForTableIndex(int idx);

View File

@ -77,6 +77,8 @@ typedef struct gyroCalibration_s {
uint16_t calibratingG; uint16_t calibratingG;
} gyroCalibration_t; } gyroCalibration_t;
bool firstArmingCalibrationWasStarted = false;
typedef union gyroSoftFilter_u { typedef union gyroSoftFilter_u {
biquadFilter_t gyroFilterLpfState[XYZ_AXIS_COUNT]; biquadFilter_t gyroFilterLpfState[XYZ_AXIS_COUNT];
pt1Filter_t gyroFilterPt1State[XYZ_AXIS_COUNT]; pt1Filter_t gyroFilterPt1State[XYZ_AXIS_COUNT];
@ -489,9 +491,20 @@ static void gyroSetCalibrationCycles(gyroSensor_t *gyroSensor)
gyroSensor->calibration.calibratingG = gyroCalculateCalibratingCycles(); gyroSensor->calibration.calibratingG = gyroCalculateCalibratingCycles();
} }
void gyroStartCalibration(void) void gyroStartCalibration(bool isFirstArmingCalibration)
{ {
gyroSetCalibrationCycles(&gyroSensor0); if (!(isFirstArmingCalibration && firstArmingCalibrationWasStarted)) {
gyroSetCalibrationCycles(&gyroSensor0);
if (isFirstArmingCalibration) {
firstArmingCalibrationWasStarted = true;
}
}
}
bool isFirstArmingGyroCalibrationRunning(void)
{
return firstArmingCalibrationWasStarted && !isGyroCalibrationComplete();
} }
STATIC_UNIT_TESTED void performGyroCalibration(gyroSensor_t *gyroSensor, uint8_t gyroMovementCalibrationThreshold) STATIC_UNIT_TESTED void performGyroCalibration(gyroSensor_t *gyroSensor, uint8_t gyroMovementCalibrationThreshold)
@ -525,7 +538,9 @@ STATIC_UNIT_TESTED void performGyroCalibration(gyroSensor_t *gyroSensor, uint8_t
if (isOnFinalGyroCalibrationCycle(&gyroSensor->calibration)) { if (isOnFinalGyroCalibrationCycle(&gyroSensor->calibration)) {
schedulerResetTaskStatistics(TASK_SELF); // so calibration cycles do not pollute tasks statistics schedulerResetTaskStatistics(TASK_SELF); // so calibration cycles do not pollute tasks statistics
beeper(BEEPER_GYRO_CALIBRATED); if (!firstArmingCalibrationWasStarted || !isArmingDisabled()) {
beeper(BEEPER_GYRO_CALIBRATED);
}
} }
--gyroSensor->calibration.calibratingG; --gyroSensor->calibration.calibratingG;

View File

@ -74,7 +74,8 @@ struct mpuConfiguration_s;
const struct mpuConfiguration_s *gyroMpuConfiguration(void); const struct mpuConfiguration_s *gyroMpuConfiguration(void);
struct mpuDetectionResult_s; struct mpuDetectionResult_s;
const struct mpuDetectionResult_s *gyroMpuDetectionResult(void); const struct mpuDetectionResult_s *gyroMpuDetectionResult(void);
void gyroStartCalibration(void); void gyroStartCalibration(bool isFirstArmingCalibration);
bool isFirstArmingGyroCalibrationRunning(void);
bool isGyroCalibrationComplete(void); bool isGyroCalibrationComplete(void);
void gyroReadTemperature(void); void gyroReadTemperature(void);
int16_t gyroGetTemperature(void); int16_t gyroGetTemperature(void);

View File

@ -269,7 +269,7 @@ void failureMode(failureMode_e mode) {
while(1); while(1);
} }
void failureLedCode(failureMode_e mode, int repeatCount) void indicateFailure(failureMode_e mode, int repeatCount)
{ {
UNUSED(repeatCount); UNUSED(repeatCount);
printf("Failure LED flash for: [failureMode]!!! %d\n", mode); printf("Failure LED flash for: [failureMode]!!! %d\n", mode);

View File

@ -701,4 +701,5 @@ uint8_t stateFlags = 0;
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
rxRuntimeConfig_t rxRuntimeConfig; rxRuntimeConfig_t rxRuntimeConfig;
PG_REGISTER(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 0); PG_REGISTER(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 0);
void resetArmingDisabled(void) {}
} }