1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-16 12:55:19 +03:00

Merge branch 'master' into betaflight

Conflicts:
	src/main/drivers/system.c
	src/main/rx/rx.h
This commit is contained in:
borisbstyle 2015-09-07 10:08:34 +02:00
commit febee3fb90
26 changed files with 812 additions and 320 deletions

View file

@ -348,6 +348,11 @@ static void setControlRateProfile(uint8_t profileIndex)
currentControlRateProfile = &masterConfig.controlRateProfiles[profileIndex];
}
uint16_t getCurrentMinthrottle(void)
{
return masterConfig.escAndServoConfig.minthrottle;
}
// Default settings
static void resetConf(void)
{
@ -408,8 +413,8 @@ static void resetConf(void)
for (i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[i];
channelFailsafeConfiguration->mode = RX_FAILSAFE_MODE_AUTO;
channelFailsafeConfiguration->step = CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.midrc);
channelFailsafeConfiguration->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD;
channelFailsafeConfiguration->step = (i == THROTTLE) ? masterConfig.rxConfig.rx_min_usec : CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.midrc);
}
masterConfig.rxConfig.rssi_channel = 0;
@ -486,6 +491,8 @@ static void resetConf(void)
masterConfig.failsafeConfig.failsafe_delay = 10; // 1sec
masterConfig.failsafeConfig.failsafe_off_delay = 200; // 20sec
masterConfig.failsafeConfig.failsafe_throttle = 1000; // default throttle off.
masterConfig.failsafeConfig.failsafe_kill_switch = 0; // default failsafe switch action is identical to rc link loss
masterConfig.failsafeConfig.failsafe_throttle_low_delay = 100; // default throttle low delay for "just disarm" on failsafe condition
#ifdef USE_SERVOS
// servos
@ -833,6 +840,8 @@ void readEEPROM(void)
if (!isEEPROMContentValid())
failureMode(10);
suspendRxSignal();
// Read flash
memcpy(&masterConfig, (char *) CONFIG_START_FLASH_ADDRESS, sizeof(master_t));
@ -848,6 +857,8 @@ void readEEPROM(void)
validateAndFixConfig();
activateConfig();
resumeRxSignal();
}
void readEEPROMAndNotify(void)
@ -866,6 +877,8 @@ void writeEEPROM(void)
uint32_t wordOffset;
int8_t attemptsRemaining = 3;
suspendRxSignal();
// prepare checksum/version constants
masterConfig.version = EEPROM_CONF_VERSION;
masterConfig.size = sizeof(master_t);
@ -907,6 +920,8 @@ void writeEEPROM(void)
if (status != FLASH_COMPLETE || !isEEPROMContentValid()) {
failureMode(10);
}
resumeRxSignal();
}
void ensureEEPROMContainsValidData(void)

View file

@ -72,3 +72,4 @@ void changeControlRateProfile(uint8_t profileIndex);
bool canSoftwareSerialBeUsed(void);
uint16_t getCurrentMinthrottle(void);

View file

@ -41,6 +41,7 @@ typedef enum {
AUTOTUNE_MODE = (1 << 7),
PASSTHRU_MODE = (1 << 8),
SONAR_MODE = (1 << 9),
FAILSAFE_MODE = (1 << 10),
} flightModeFlags_e;
extern uint16_t flightModeFlags;

View file

@ -99,6 +99,10 @@ uint32_t micros(void)
do {
ms = sysTickUptime;
cycle_cnt = SysTick->VAL;
/*
* If the SysTick timer expired during the previous instruction, we need to give it a little time for that
* interrupt to be delivered before we can recheck sysTickUptime:
*/
asm volatile("\tnop\n");
} while (ms != sysTickUptime);
return (ms * 1000) + (usTicks * 1000 - cycle_cnt) / usTicks;

View file

@ -23,10 +23,12 @@
#include "common/axis.h"
#include "rx/rx.h"
#include "drivers/system.h"
#include "io/beeper.h"
#include "io/escservo.h"
#include "io/rc_controls.h"
#include "config/runtime_config.h"
#include "config/config.h"
#include "flight/failsafe.h"
@ -47,10 +49,19 @@ static failsafeConfig_t *failsafeConfig;
static rxConfig_t *rxConfig;
static uint16_t deadband3dThrottle; // default throttle deadband from MIDRC
static void failsafeReset(void)
{
failsafeState.counter = 0;
failsafeState.rxDataFailurePeriod = PERIOD_RXDATA_FAILURE + failsafeConfig->failsafe_delay * MILLIS_PER_TENTH_SECOND;
failsafeState.validRxDataReceivedAt = 0;
failsafeState.validRxDataFailedAt = 0;
failsafeState.throttleLowPeriod = 0;
failsafeState.landingShouldBeFinishedAt = 0;
failsafeState.receivingRxDataPeriod = 0;
failsafeState.receivingRxDataPeriodPreset = 0;
failsafeState.phase = FAILSAFE_IDLE;
failsafeState.rxLinkState = FAILSAFE_RXLINK_DOWN;
}
/*
@ -62,10 +73,11 @@ void useFailsafeConfig(failsafeConfig_t *failsafeConfigToUse)
failsafeReset();
}
void failsafeInit(rxConfig_t *intialRxConfig)
void failsafeInit(rxConfig_t *intialRxConfig, uint16_t deadband3d_throttle)
{
rxConfig = intialRxConfig;
deadband3dThrottle = deadband3d_throttle;
failsafeState.events = 0;
failsafeState.monitoring = false;
@ -77,13 +89,6 @@ failsafePhase_e failsafePhase()
return failsafeState.phase;
}
#define FAILSAFE_COUNTER_THRESHOLD 20
bool failsafeIsReceivingRxData(void)
{
return failsafeState.counter <= FAILSAFE_COUNTER_THRESHOLD;
}
bool failsafeIsMonitoring(void)
{
return failsafeState.monitoring;
@ -99,25 +104,17 @@ void failsafeStartMonitoring(void)
failsafeState.monitoring = true;
}
static bool failsafeHasTimerElapsed(void)
{
return failsafeState.counter > (5 * failsafeConfig->failsafe_delay);
}
static bool failsafeShouldForceLanding(bool armed)
{
return failsafeHasTimerElapsed() && armed;
}
static bool failsafeShouldHaveCausedLandingByNow(void)
{
return failsafeState.counter > 5 * (failsafeConfig->failsafe_delay + failsafeConfig->failsafe_off_delay);
return (millis() > failsafeState.landingShouldBeFinishedAt);
}
static void failsafeActivate(void)
{
failsafeState.active = true;
failsafeState.phase = FAILSAFE_LANDING;
ENABLE_FLIGHT_MODE(FAILSAFE_MODE);
failsafeState.landingShouldBeFinishedAt = millis() + failsafeConfig->failsafe_off_delay * MILLIS_PER_TENTH_SECOND;
failsafeState.events++;
}
@ -130,27 +127,41 @@ static void failsafeApplyControlInput(void)
rcData[THROTTLE] = failsafeConfig->failsafe_throttle;
}
bool failsafeIsReceivingRxData(void)
{
return (failsafeState.rxLinkState == FAILSAFE_RXLINK_UP);
}
void failsafeOnValidDataReceived(void)
{
if (failsafeState.counter > FAILSAFE_COUNTER_THRESHOLD)
failsafeState.counter -= FAILSAFE_COUNTER_THRESHOLD;
else
failsafeState.counter = 0;
failsafeState.validRxDataReceivedAt = millis();
if ((failsafeState.validRxDataReceivedAt - failsafeState.validRxDataFailedAt) > PERIOD_RXDATA_RECOVERY) {
failsafeState.rxLinkState = FAILSAFE_RXLINK_UP;
}
}
void failsafeOnValidDataFailed(void)
{
failsafeState.validRxDataFailedAt = millis();
if ((failsafeState.validRxDataFailedAt - failsafeState.validRxDataReceivedAt) > failsafeState.rxDataFailurePeriod) {
failsafeState.rxLinkState = FAILSAFE_RXLINK_DOWN;
}
}
void failsafeUpdateState(void)
{
bool receivingRxData = failsafeIsReceivingRxData();
bool armed = ARMING_FLAG(ARMED);
beeperMode_e beeperMode = BEEPER_SILENCE;
if (receivingRxData) {
failsafeState.phase = FAILSAFE_IDLE;
failsafeState.active = false;
} else {
beeperMode = BEEPER_RX_LOST;
if (!failsafeIsMonitoring()) {
return;
}
bool receivingRxData = failsafeIsReceivingRxData();
bool armed = ARMING_FLAG(ARMED);
bool failsafeSwitchIsOn = IS_RC_MODE_ACTIVE(BOXFAILSAFE);
beeperMode_e beeperMode = BEEPER_SILENCE;
if (!receivingRxData) {
beeperMode = BEEPER_RX_LOST;
}
bool reprocessState;
@ -159,50 +170,100 @@ void failsafeUpdateState(void)
switch (failsafeState.phase) {
case FAILSAFE_IDLE:
if (!receivingRxData && armed) {
failsafeState.phase = FAILSAFE_RX_LOSS_DETECTED;
reprocessState = true;
if (armed) {
// Track throttle command below minimum time
if (THROTTLE_HIGH == calculateThrottleStatus(rxConfig, deadband3dThrottle)) {
failsafeState.throttleLowPeriod = millis() + failsafeConfig->failsafe_throttle_low_delay * MILLIS_PER_TENTH_SECOND;
}
// Kill switch logic (must be independent of receivingRxData to skip PERIOD_RXDATA_FAILURE delay before disarming)
if (failsafeSwitchIsOn && failsafeConfig->failsafe_kill_switch) {
// KillswitchEvent: failsafe switch is configured as KILL switch and is switched ON
failsafeActivate();
failsafeState.phase = FAILSAFE_LANDED; // skip auto-landing procedure
failsafeState.receivingRxDataPeriodPreset = PERIOD_OF_1_SECONDS; // require 1 seconds of valid rxData
reprocessState = true;
} else if (!receivingRxData) {
if (millis() > failsafeState.throttleLowPeriod) {
// JustDisarm: throttle was LOW for at least 'failsafe_throttle_low_delay' seconds
failsafeActivate();
failsafeState.phase = FAILSAFE_LANDED; // skip auto-landing procedure
failsafeState.receivingRxDataPeriodPreset = PERIOD_OF_3_SECONDS; // require 3 seconds of valid rxData
} else {
failsafeState.phase = FAILSAFE_RX_LOSS_DETECTED;
}
reprocessState = true;
}
} else {
// When NOT armed, show rxLinkState of failsafe switch in GUI (failsafe mode)
if (failsafeSwitchIsOn) {
ENABLE_FLIGHT_MODE(FAILSAFE_MODE);
} else {
DISABLE_FLIGHT_MODE(FAILSAFE_MODE);
}
// Throttle low period expired (= low long enough for JustDisarm)
failsafeState.throttleLowPeriod = 0;
}
break;
case FAILSAFE_RX_LOSS_DETECTED:
if (failsafeShouldForceLanding(armed)) {
if (receivingRxData) {
failsafeState.phase = FAILSAFE_RX_LOSS_RECOVERED;
} else {
// Stabilize, and set Throttle to specified level
failsafeActivate();
reprocessState = true;
}
reprocessState = true;
break;
case FAILSAFE_LANDING:
if (receivingRxData) {
failsafeState.phase = FAILSAFE_RX_LOSS_RECOVERED;
reprocessState = true;
}
if (armed) {
failsafeApplyControlInput();
beeperMode = BEEPER_RX_LOST_LANDING;
}
if (failsafeShouldHaveCausedLandingByNow() || !armed) {
failsafeState.receivingRxDataPeriodPreset = PERIOD_OF_30_SECONDS; // require 30 seconds of valid rxData
failsafeState.phase = FAILSAFE_LANDED;
reprocessState = true;
}
break;
case FAILSAFE_LANDED:
if (!armed) {
break;
}
// This will prevent the automatic rearm if failsafe shuts it down and prevents
// to restart accidently by just reconnect to the tx - you will have to switch off first to rearm
ENABLE_ARMING_FLAG(PREVENT_ARMING);
failsafeState.active = false;
ENABLE_ARMING_FLAG(PREVENT_ARMING); // To prevent accidently rearming by an intermittent rx link
mwDisarm();
failsafeState.receivingRxDataPeriod = millis() + failsafeState.receivingRxDataPeriodPreset; // set required period of valid rxData
failsafeState.phase = FAILSAFE_RX_LOSS_MONITORING;
reprocessState = true;
break;
case FAILSAFE_RX_LOSS_MONITORING:
// Monitoring the rx link to allow rearming when it has become good for > `receivingRxDataPeriodPreset` time.
if (receivingRxData) {
if (millis() > failsafeState.receivingRxDataPeriod) {
// rx link is good now, when arming via ARM switch, it must be OFF first
if (!(!isUsingSticksForArming() && IS_RC_MODE_ACTIVE(BOXARM))) {
DISABLE_ARMING_FLAG(PREVENT_ARMING);
failsafeState.phase = FAILSAFE_RX_LOSS_RECOVERED;
reprocessState = true;
}
}
} else {
failsafeState.receivingRxDataPeriod = millis() + failsafeState.receivingRxDataPeriodPreset;
}
break;
case FAILSAFE_RX_LOSS_RECOVERED:
// Entering IDLE with the requirement that throttle first must be at min_check for failsafe_throttle_low_delay period.
// This is to prevent that JustDisarm is activated on the next iteration.
// Because that would have the effect of shutting down failsafe handling on intermittent connections.
failsafeState.throttleLowPeriod = millis() + failsafeConfig->failsafe_throttle_low_delay * MILLIS_PER_TENTH_SECOND;
failsafeState.phase = FAILSAFE_IDLE;
failsafeState.active = false;
DISABLE_FLIGHT_MODE(FAILSAFE_MODE);
reprocessState = true;
break;
default:
@ -214,11 +275,3 @@ void failsafeUpdateState(void)
beeper(beeperMode);
}
}
/**
* Should be called once when RX data is processed by the system.
*/
void failsafeOnRxCycleStarted(void)
{
failsafeState.counter++;
}

View file

@ -18,26 +18,50 @@
#pragma once
#define FAILSAFE_POWER_ON_DELAY_US (1000 * 1000 * 5)
#define MILLIS_PER_TENTH_SECOND 100
#define MILLIS_PER_SECOND 1000
#define PERIOD_OF_1_SECONDS 1 * MILLIS_PER_SECOND
#define PERIOD_OF_3_SECONDS 3 * MILLIS_PER_SECOND
#define PERIOD_OF_30_SECONDS 30 * MILLIS_PER_SECOND
#define PERIOD_RXDATA_FAILURE 200 // millis
#define PERIOD_RXDATA_RECOVERY 200 // millis
typedef struct failsafeConfig_s {
uint8_t failsafe_delay; // Guard time for failsafe activation after signal lost. 1 step = 0.1sec - 1sec in example (10)
uint8_t failsafe_off_delay; // Time for Landing before motors stop in 0.1sec. 1 step = 0.1sec - 20sec in example (200)
uint16_t failsafe_throttle; // Throttle level used for landing - specify value between 1000..2000 (pwm pulse width for slightly below hover). center throttle = 1500.
uint8_t failsafe_kill_switch; // failsafe switch action is 0: identical to rc link loss, 1: disarms instantly
uint16_t failsafe_throttle_low_delay; // Time throttle stick must have been below 'min_check' to "JustDisarm" instead of "full failsafe procedure".
} failsafeConfig_t;
typedef enum {
FAILSAFE_IDLE = 0,
FAILSAFE_RX_LOSS_DETECTED,
FAILSAFE_LANDING,
FAILSAFE_LANDED
FAILSAFE_LANDED,
FAILSAFE_RX_LOSS_MONITORING,
FAILSAFE_RX_LOSS_RECOVERED
} failsafePhase_e;
typedef enum {
FAILSAFE_RXLINK_DOWN = 0,
FAILSAFE_RXLINK_UP
} failsafeRxLinkState_e;
typedef struct failsafeState_s {
int16_t counter;
int16_t events;
bool monitoring;
bool active;
uint32_t rxDataFailurePeriod;
uint32_t validRxDataReceivedAt;
uint32_t validRxDataFailedAt;
uint32_t throttleLowPeriod; // throttle stick must have been below 'min_check' for this period
uint32_t landingShouldBeFinishedAt;
uint32_t receivingRxDataPeriod; // period for the required period of valid rxData
uint32_t receivingRxDataPeriodPreset; // preset for the required period of valid rxData
failsafePhase_e phase;
failsafeRxLinkState_e rxLinkState;
} failsafeState_t;
void useFailsafeConfig(failsafeConfig_t *failsafeConfigToUse);
@ -51,7 +75,7 @@ bool failsafeIsActive(void);
bool failsafeIsReceivingRxData(void);
void failsafeOnValidDataReceived(void);
void failsafeOnRxCycleStarted(void);
void failsafeOnValidDataFailed(void);

View file

@ -174,10 +174,10 @@ static const motorMixer_t mixerOctoFlatX[] = {
};
static const motorMixer_t mixerVtail4[] = {
{ 1.0f, 0.0f, 1.0f, 1.0f }, // REAR_R
{ 1.0f, -1.0f, -1.0f, 0.0f }, // FRONT_R
{ 1.0f, 0.0f, 1.0f, -1.0f }, // REAR_L
{ 1.0f, 1.0f, -1.0f, -0.0f }, // FRONT_L
{ 1.0f, -0.58f, 0.58f, 1.0f }, // REAR_R
{ 1.0f, -0.46f, -0.39f, -0.5f }, // FRONT_R
{ 1.0f, 0.58f, 0.58f, -1.0f }, // REAR_L
{ 1.0f, 0.46f, -0.39f, 0.5f }, // FRONT_L
};
static const motorMixer_t mixerAtail4[] = {

View file

@ -231,6 +231,12 @@ void updateFailsafeStatus(void)
case FAILSAFE_LANDED:
failsafeIndicator = 'L';
break;
case FAILSAFE_RX_LOSS_MONITORING:
failsafeIndicator = 'M';
break;
case FAILSAFE_RX_LOSS_RECOVERED:
failsafeIndicator = 'r';
break;
}
i2c_OLED_set_xy(SCREEN_CHARACTER_COLUMN_COUNT - 3, 0);
i2c_OLED_send_char(failsafeIndicator);

View file

@ -47,6 +47,7 @@ typedef enum {
BOXSERVO2,
BOXSERVO3,
BOXBLACKBOX,
BOXFAILSAFE,
CHECKBOX_ITEM_COUNT
} boxId_e;

View file

@ -112,8 +112,12 @@ static void cliRateProfile(char *cmdline);
static void cliReboot(void);
static void cliSave(char *cmdline);
static void cliSerial(char *cmdline);
#ifdef USE_SERVOS
static void cliServo(char *cmdline);
static void cliServoMix(char *cmdline);
#endif
static void cliSet(char *cmdline);
static void cliGet(char *cmdline);
static void cliStatus(char *cmdline);
@ -175,7 +179,12 @@ static const char * const featureNames[] = {
};
// sync this with rxFailsafeChannelMode_e
static char rxFailsafeModes[RX_FAILSAFE_MODE_COUNT] = { 'a', 'h', 's'};
static const char rxFailsafeModeCharacters[] = "ahs";
static const rxFailsafeChannelMode_e rxFailsafeModesTable[RX_FAILSAFE_TYPE_COUNT][RX_FAILSAFE_MODE_COUNT] = {
{ RX_FAILSAFE_MODE_AUTO, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_INVALID },
{ RX_FAILSAFE_MODE_INVALID, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_SET }
};
#ifndef CJMCU
// sync this with sensors_e
@ -443,6 +452,8 @@ const clivalue_t valueTable[] = {
{ "failsafe_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_delay, 0, 200 },
{ "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_off_delay, 0, 200 },
{ "failsafe_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle, PWM_RANGE_MIN, PWM_RANGE_MAX },
{ "failsafe_kill_switch", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_kill_switch, 0, 1 },
{ "failsafe_throttle_low_delay",VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle_low_delay, 0, 300 },
{ "rx_min_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_min_usec, PWM_PULSE_MIN, PWM_PULSE_MAX },
{ "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_max_usec, PWM_PULSE_MIN, PWM_PULSE_MAX },
@ -598,27 +609,22 @@ static void cliRxFail(char *cmdline)
rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[channel];
uint16_t value;
rxFailsafeChannelType_e type = (channel < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_TYPE_FLIGHT : RX_FAILSAFE_TYPE_AUX;
rxFailsafeChannelMode_e mode = channelFailsafeConfiguration->mode;
bool requireValue = channelFailsafeConfiguration->mode == RX_FAILSAFE_MODE_SET;
// TODO optimize to use rxFailsafeModes - less logic.
ptr = strchr(ptr, ' ');
if (ptr) {
switch (*(++ptr)) {
case 'a':
mode = RX_FAILSAFE_MODE_AUTO;
break;
case 'h':
mode = RX_FAILSAFE_MODE_HOLD;
break;
case 's':
mode = RX_FAILSAFE_MODE_SET;
break;
default:
cliShowParseError();
return;
char *p = strchr(rxFailsafeModeCharacters, *(++ptr));
if (p) {
uint8_t requestedMode = p - rxFailsafeModeCharacters;
mode = rxFailsafeModesTable[type][requestedMode];
} else {
mode = RX_FAILSAFE_MODE_INVALID;
}
if (mode == RX_FAILSAFE_MODE_INVALID) {
cliShowParseError();
return;
}
requireValue = mode == RX_FAILSAFE_MODE_SET;
@ -637,12 +643,15 @@ static void cliRxFail(char *cmdline)
}
channelFailsafeConfiguration->step = value;
} else if (requireValue) {
cliShowParseError();
return;
}
channelFailsafeConfiguration->mode = mode;
}
char modeCharacter = rxFailsafeModes[channelFailsafeConfiguration->mode];
char modeCharacter = rxFailsafeModeCharacters[channelFailsafeConfiguration->mode];
// triple use of printf below
// 1. acknowledge interpretation on command,
@ -1067,11 +1076,9 @@ static void cliColor(char *cmdline)
}
#endif
#ifdef USE_SERVOS
static void cliServo(char *cmdline)
{
#ifndef USE_SERVOS
UNUSED(cmdline);
#else
enum { SERVO_ARGUMENT_COUNT = 8 };
int16_t arguments[SERVO_ARGUMENT_COUNT];
@ -1141,7 +1148,7 @@ static void cliServo(char *cmdline)
arguments[MAX] < PWM_PULSE_MIN || arguments[MAX] > PWM_PULSE_MAX ||
arguments[MIDDLE] < arguments[MIN] || arguments[MIDDLE] > arguments[MAX] ||
arguments[MIN] > arguments[MAX] || arguments[MAX] < arguments[MIN] ||
arguments[RATE] < 100 || arguments[RATE] > 100 ||
arguments[RATE] < -100 || arguments[RATE] > 100 ||
arguments[FORWARD] >= MAX_SUPPORTED_RC_CHANNEL_COUNT ||
arguments[ANGLE_AT_MIN] < 0 || arguments[ANGLE_AT_MIN] > 180 ||
arguments[ANGLE_AT_MAX] < 0 || arguments[ANGLE_AT_MAX] > 180
@ -1158,14 +1165,12 @@ static void cliServo(char *cmdline)
servo->rate = arguments[6];
servo->forwardFromChannel = arguments[7];
}
#endif
}
#endif
#ifdef USE_SERVOS
static void cliServoMix(char *cmdline)
{
#ifndef USE_SERVOS
UNUSED(cmdline);
#else
int i;
uint8_t len;
char *ptr;
@ -1293,8 +1298,8 @@ static void cliServoMix(char *cmdline)
cliShowParseError();
}
}
#endif
}
#endif
#ifdef USE_FLASHFS
@ -1414,7 +1419,7 @@ static const char* const sectionBreak = "\r\n";
static void cliDump(char *cmdline)
{
unsigned int i, channel;
unsigned int i;
char buf[16];
uint32_t mask;
@ -1488,15 +1493,6 @@ static void cliDump(char *cmdline)
);
}
// print servo directions
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
for (channel = 0; channel < INPUT_SOURCE_COUNT; channel++) {
if (servoDirection(i, channel) < 0) {
printf("smix reverse %d %d r\r\n", i , channel);
}
}
}
#endif
cliPrint("\r\n\r\n# feature\r\n");
@ -1556,10 +1552,23 @@ static void cliDump(char *cmdline)
cliRxRange("");
#ifdef USE_SERVOS
cliPrint("\r\n# servo\r\n");
cliServo("");
// print servo directions
unsigned int channel;
for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
for (channel = 0; channel < INPUT_SOURCE_COUNT; channel++) {
if (servoDirection(i, channel) < 0) {
printf("smix reverse %d %d r\r\n", i , channel);
}
}
}
#endif
printSectionBreak();
dumpValues(PROFILE_VALUE);
@ -1584,6 +1593,7 @@ void cliEnter(serialPort_t *serialPort)
setPrintfSerialPort(cliPort);
cliPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n");
cliPrompt();
ENABLE_ARMING_FLAG(PREVENT_ARMING);
}
static void cliExit(char *cmdline)

View file

@ -134,7 +134,7 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
#define MSP_PROTOCOL_VERSION 0
#define API_VERSION_MAJOR 1 // increment when major changes are made
#define API_VERSION_MINOR 12 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
#define API_VERSION_MINOR 13 // increment when any change is made, reset to zero when major changes are released after changing API_VERSION_MAJOR
#define API_VERSION_LENGTH 2
@ -352,6 +352,7 @@ static const box_t boxes[CHECKBOX_ITEM_COUNT + 1] = {
{ BOXSERVO2, "SERVO2;", 24 },
{ BOXSERVO3, "SERVO3;", 25 },
{ BOXBLACKBOX, "BLACKBOX;", 26 },
{ BOXFAILSAFE, "FAILSAFE;", 27 },
{ CHECKBOX_ITEM_COUNT, NULL, 0xFF }
};
@ -704,6 +705,10 @@ void mspInit(serialConfig_t *serialConfig)
}
#endif
if (feature(FEATURE_FAILSAFE)){
activeBoxIds[activeBoxIdCount++] = BOXFAILSAFE;
}
memset(mspPorts, 0x00, sizeof(mspPorts));
mspAllocateSerialPorts(serialConfig);
}
@ -825,7 +830,8 @@ static bool processOutCommand(uint8_t cmdMSP)
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXAUTOTUNE)) << BOXAUTOTUNE |
IS_ENABLED(FLIGHT_MODE(SONAR_MODE)) << BOXSONAR |
IS_ENABLED(ARMING_FLAG(ARMED)) << BOXARM |
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXBLACKBOX)) << BOXBLACKBOX;
IS_ENABLED(IS_RC_MODE_ACTIVE(BOXBLACKBOX)) << BOXBLACKBOX |
IS_ENABLED(FLIGHT_MODE(FAILSAFE_MODE)) << BOXFAILSAFE;
for (i = 0; i < activeBoxIdCount; i++) {
int flag = (tmp & (1 << activeBoxIds[i]));
if (flag)

View file

@ -104,7 +104,7 @@ void telemetryInit(void);
void serialInit(serialConfig_t *initialSerialConfig, bool softserialEnabled);
void mspInit(serialConfig_t *serialConfig);
void cliInit(serialConfig_t *serialConfig);
void failsafeInit(rxConfig_t *intialRxConfig);
void failsafeInit(rxConfig_t *intialRxConfig, uint16_t deadband3d_throttle);
pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init);
#ifdef USE_SERVOS
void mixerInit(mixerMode_e mixerMode, motorMixer_t *customMotorMixers, servoMixer_t *customServoMixers);
@ -404,7 +404,7 @@ void init(void)
cliInit(&masterConfig.serialConfig);
#endif
failsafeInit(&masterConfig.rxConfig);
failsafeInit(&masterConfig.rxConfig, masterConfig.flight3DConfig.deadband3d_throttle);
rxInit(&masterConfig.rxConfig);

View file

@ -346,6 +346,9 @@ void mwArm(void)
if (ARMING_FLAG(ARMED)) {
return;
}
if (IS_RC_MODE_ACTIVE(BOXFAILSAFE)) {
return;
}
if (!ARMING_FLAG(PREVENT_ARMING)) {
ENABLE_ARMING_FLAG(ARMED);
headFreeModeHold = heading;

View file

@ -71,6 +71,7 @@ static bool rxFlightChannelsValid = false;
static uint32_t rxUpdateAt = 0;
static uint32_t needRxSignalBefore = 0;
static uint8_t skipRxSamples = 0;
int16_t rcRaw[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
@ -79,6 +80,8 @@ int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
#define DELAY_50_HZ (1000000 / 50)
#define DELAY_10_HZ (1000000 / 10)
#define SKIP_RC_SAMPLES_ON_SUSPEND 75 // approx. 1.5 seconds of samples at 50Hz
#define SKIP_RC_SAMPLES_ON_RESUME 2 // flush 2 samples to drop wrong measurements
rxRuntimeConfig_t rxRuntimeConfig;
static rxConfig_t *rxConfig;
@ -271,6 +274,16 @@ static void resetRxSignalReceivedFlagIfNeeded(uint32_t currentTime)
}
}
void suspendRxSignal(void)
{
skipRxSamples = SKIP_RC_SAMPLES_ON_SUSPEND;
}
void resumeRxSignal(void)
{
skipRxSamples = SKIP_RC_SAMPLES_ON_RESUME;
}
void updateRx(uint32_t currentTime)
{
resetRxSignalReceivedFlagIfNeeded(currentTime);
@ -356,27 +369,29 @@ static uint16_t getRxfailValue(uint8_t channel)
rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &rxConfig->failsafe_channel_configurations[channel];
switch(channelFailsafeConfiguration->mode) {
default:
case RX_FAILSAFE_MODE_AUTO:
switch (channel) {
case ROLL:
case PITCH:
case YAW:
return rxConfig->midrc;
case THROTTLE:
if (feature(FEATURE_3D))
return rxConfig->midrc;
else
return rxConfig->rx_min_usec;
}
// fall though to HOLD if there's nothing specific to do.
/* no break */
default:
case RX_FAILSAFE_MODE_INVALID:
case RX_FAILSAFE_MODE_HOLD:
return rcData[channel];
case RX_FAILSAFE_MODE_SET:
return RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration->step);
}
}
STATIC_UNIT_TESTED uint16_t applyRxChannelRangeConfiguraton(int sample, rxChannelRangeConfiguration_t range)
@ -451,10 +466,11 @@ static void detectAndApplySignalLossBehaviour(void)
rxFlightChannelsValid = rxHaveValidFlightChannels();
if (rxFlightChannelsValid) {
if ((rxFlightChannelsValid) && !IS_RC_MODE_ACTIVE(BOXFAILSAFE)) {
failsafeOnValidDataReceived();
} else {
rxSignalReceived = false;
failsafeOnValidDataFailed();
for (channel = 0; channel < rxRuntimeConfig.channelCount; channel++) {
rcData[channel] = getRxfailValue(channel);
@ -467,8 +483,6 @@ void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime)
{
rxUpdateAt = currentTime + DELAY_50_HZ;
failsafeOnRxCycleStarted();
if (!feature(FEATURE_RX_MSP)) {
// rcData will have already been updated by MSP_SET_RAW_RC
@ -477,9 +491,13 @@ void calculateRxChannelsAndUpdateFailsafe(uint32_t currentTime)
}
}
if (skipRxSamples) {
skipRxSamples--;
return;
}
readRxChannelsApplyRanges();
detectAndApplySignalLossBehaviour();
}
void parseRcChannels(const char *input, rxConfig_t *rxConfig)

View file

@ -85,10 +85,18 @@ typedef enum {
RX_FAILSAFE_MODE_AUTO = 0,
RX_FAILSAFE_MODE_HOLD,
RX_FAILSAFE_MODE_SET,
RX_FAILSAFE_MODE_INVALID,
} rxFailsafeChannelMode_e;
#define RX_FAILSAFE_MODE_COUNT 3
typedef enum {
RX_FAILSAFE_TYPE_FLIGHT = 0,
RX_FAILSAFE_TYPE_AUX,
} rxFailsafeChannelType_e;
#define RX_FAILSAFE_TYPE_COUNT 2
typedef struct rxFailsafeChannelConfiguration_s {
uint8_t mode; // See rxFailsafeChannelMode_e
uint8_t step;
@ -143,3 +151,5 @@ void updateRSSI(uint32_t currentTime);
void resetAllRxChannelRangeConfigurations(rxChannelRangeConfiguration_t *rxChannelRangeConfiguration);
void initRxRefreshRate(uint16_t *rxRefreshRatePtr);
void suspendRxSignal(void);
void resumeRxSignal(void);

View file

@ -31,6 +31,7 @@ extern "C" {
#include "config/runtime_config.h"
#include "io/beeper.h"
#include "io/rc_controls.h"
#include "rx/rx.h"
#include "flight/failsafe.h"
@ -42,6 +43,9 @@ extern "C" {
#include "gtest/gtest.h"
uint32_t testFeatureMask = 0;
uint16_t flightModeFlags = 0;
uint16_t testMinThrottle = 0;
throttleStatus_e throttleStatus = THROTTLE_HIGH;
enum {
COUNTER_MW_DISARM = 0,
@ -56,24 +60,34 @@ void resetCallCounters(void) {
memset(&callCounts, 0, sizeof(callCounts));
}
#define TEST_MID_RC 1495 // something other than the default 1500 will suffice.
#define TEST_MID_RC 1495 // something other than the default 1500 will suffice.
#define TEST_MIN_CHECK 1100;
#define PERIOD_OF_10_SCONDS 10000
#define DE_ACTIVATE_ALL_BOXES 0
rxConfig_t rxConfig;
failsafeConfig_t failsafeConfig;
uint32_t sysTickUptime;
void configureFailsafe(void)
{
memset(&rxConfig, 0, sizeof(rxConfig));
rxConfig.midrc = TEST_MID_RC;
rxConfig.mincheck = TEST_MIN_CHECK;
memset(&failsafeConfig, 0, sizeof(failsafeConfig));
failsafeConfig.failsafe_delay = 10; // 1 second
failsafeConfig.failsafe_off_delay = 50; // 5 seconds
failsafeConfig.failsafe_kill_switch = false;
failsafeConfig.failsafe_throttle = 1200;
failsafeConfig.failsafe_throttle_low_delay = 50; // 5 seconds
sysTickUptime = 0;
}
//
// Stepwise tests
//
/****************************************************************************************/
TEST(FlightFailsafeTest, TestFailsafeInitialState)
{
// given
@ -91,6 +105,7 @@ TEST(FlightFailsafeTest, TestFailsafeInitialState)
EXPECT_EQ(FAILSAFE_IDLE, failsafePhase());
}
/****************************************************************************************/
TEST(FlightFailsafeTest, TestFailsafeStartMonitoring)
{
// when
@ -102,14 +117,16 @@ TEST(FlightFailsafeTest, TestFailsafeStartMonitoring)
EXPECT_EQ(FAILSAFE_IDLE, failsafePhase());
}
/****************************************************************************************/
TEST(FlightFailsafeTest, TestFailsafeFirstArmedCycle)
{
// given
ENABLE_ARMING_FLAG(ARMED);
// when
failsafeOnRxCycleStarted();
failsafeOnValidDataReceived();
failsafeOnValidDataFailed(); // set last invalid sample at current time
sysTickUptime += PERIOD_RXDATA_RECOVERY + 1; // adjust time to point just past the recovery time to
failsafeOnValidDataReceived(); // cause a recovered link
// and
failsafeUpdateState();
@ -119,47 +136,11 @@ TEST(FlightFailsafeTest, TestFailsafeFirstArmedCycle)
EXPECT_EQ(FAILSAFE_IDLE, failsafePhase());
}
/*
* FIXME failsafe assumes that calls to failsafeUpdateState() happen at a set frequency (50hz)
* but that is NOT the case when using a RX_SERIAL or RX_MSP as in that case the rx data is processed as soon
* as it arrives which may be more or less frequent.
*
* Since the failsafe uses a counter the counter would not be updated at the same frequency that the maths
* in the failsafe code is expecting the failsafe will either be triggered to early or too late when using
* RX_SERIAL or RX_MSP.
*
* uint8_t failsafe_delay; // Guard time for failsafe activation after signal lost. 1 step = 0.1sec - 1sec in example (10)
*
* static bool failsafeHasTimerElapsed(void)
* {
* return failsafeState.counter > (5 * failsafeConfig->failsafe_delay);
* }
*
* static bool failsafeShouldHaveCausedLandingByNow(void)
* {
* return failsafeState.counter > 5 * (failsafeConfig->failsafe_delay + failsafeConfig->failsafe_off_delay);
* }
*
* void failsafeOnValidDataReceived(void)
* {
* if (failsafeState.counter > 20)
* failsafeState.counter -= 20;
* else
* failsafeState.counter = 0;
* }
*
* 1000ms / 50hz = 20
*/
#define FAILSAFE_UPDATE_HZ 50
/****************************************************************************************/
TEST(FlightFailsafeTest, TestFailsafeNotActivatedWhenReceivingData)
{
// when
int callsToMakeToSimulateTenSeconds = FAILSAFE_UPDATE_HZ * 10;
for (int i = 0; i < callsToMakeToSimulateTenSeconds; i++) {
failsafeOnRxCycleStarted();
for (sysTickUptime = 0; sysTickUptime < PERIOD_OF_10_SCONDS; sysTickUptime++) {
failsafeOnValidDataReceived();
failsafeUpdateState();
@ -170,108 +151,213 @@ TEST(FlightFailsafeTest, TestFailsafeNotActivatedWhenReceivingData)
}
}
/****************************************************************************************/
TEST(FlightFailsafeTest, TestFailsafeDetectsRxLossAndStartsLanding)
{
// given
ENABLE_ARMING_FLAG(ARMED);
//
// currently 20 cycles must occur before the lack of an update triggers RX loss detection.
//
// FIXME see comments about RX_SERIAL/RX_MSP above, the test should likely deal with time rather than counters.
int failsafeCounterThreshold = 20;
// and
failsafeStartMonitoring();
throttleStatus = THROTTLE_HIGH; // throttle HIGH to go for a failsafe landing procedure
sysTickUptime = 0; // restart time from 0
failsafeOnValidDataReceived(); // set last valid sample at current time
// when
for (int i = 0; i < failsafeCounterThreshold; i++) {
failsafeOnRxCycleStarted();
// no call to failsafeOnValidDataReceived();
for (sysTickUptime = 0; sysTickUptime < (uint32_t)(failsafeConfig.failsafe_delay * MILLIS_PER_TENTH_SECOND + PERIOD_RXDATA_FAILURE); sysTickUptime++) {
failsafeOnValidDataFailed();
failsafeUpdateState();
// then
EXPECT_EQ(false, failsafeIsActive());
EXPECT_EQ(FAILSAFE_IDLE, failsafePhase());
EXPECT_EQ(false, failsafeIsActive());
}
// when
for (int i = 0; i < FAILSAFE_UPDATE_HZ - failsafeCounterThreshold; i++) {
failsafeOnRxCycleStarted();
// no call to failsafeOnValidDataReceived();
failsafeUpdateState();
// then
EXPECT_EQ(FAILSAFE_RX_LOSS_DETECTED, failsafePhase());
EXPECT_EQ(false, failsafeIsActive());
}
//
// one more cycle currently needed before the counter is re-checked.
//
// given
sysTickUptime++; // adjust time to point just past the failure time to
failsafeOnValidDataFailed(); // cause a lost link
// when
failsafeUpdateState();
// then
EXPECT_EQ(FAILSAFE_LANDING, failsafePhase());
EXPECT_EQ(true, failsafeIsActive());
}
/****************************************************************************************/
TEST(FlightFailsafeTest, TestFailsafeCausesLanding)
{
// given
sysTickUptime += failsafeConfig.failsafe_off_delay * MILLIS_PER_TENTH_SECOND;
sysTickUptime++;
// when
failsafeOnRxCycleStarted();
// no call to failsafeOnValidDataReceived();
failsafeUpdateState();
// then
EXPECT_EQ(true, failsafeIsActive());
EXPECT_EQ(FAILSAFE_LANDING, failsafePhase());
}
TEST(FlightFailsafeTest, TestFailsafeCausesLanding)
{
// given
int callsToMakeToSimulateFiveSeconds = FAILSAFE_UPDATE_HZ * 5;
// when
for (int i = 0; i < callsToMakeToSimulateFiveSeconds - 1; i++) {
failsafeOnRxCycleStarted();
// no call to failsafeOnValidDataReceived();
failsafeUpdateState();
// then
EXPECT_EQ(FAILSAFE_LANDING, failsafePhase());
EXPECT_EQ(true, failsafeIsActive());
}
// when
failsafeOnRxCycleStarted();
// no call to failsafeOnValidDataReceived();
failsafeUpdateState();
// then
EXPECT_EQ(false, failsafeIsActive());
EXPECT_EQ(FAILSAFE_LANDED, failsafePhase());
EXPECT_EQ(FAILSAFE_RX_LOSS_MONITORING, failsafePhase());
EXPECT_EQ(1, CALL_COUNTER(COUNTER_MW_DISARM));
EXPECT_TRUE(ARMING_FLAG(PREVENT_ARMING));
// given
DISABLE_ARMING_FLAG(ARMED);
failsafeOnValidDataFailed(); // set last invalid sample at current time
sysTickUptime += PERIOD_RXDATA_RECOVERY + 1; // adjust time to point just past the recovery time to
failsafeOnValidDataReceived(); // cause a recovered link
// when
failsafeUpdateState();
// then
EXPECT_EQ(true, failsafeIsActive());
EXPECT_EQ(FAILSAFE_RX_LOSS_MONITORING, failsafePhase());
EXPECT_EQ(1, CALL_COUNTER(COUNTER_MW_DISARM));
EXPECT_TRUE(ARMING_FLAG(PREVENT_ARMING));
// given
sysTickUptime += PERIOD_OF_30_SECONDS + 1; // adjust time to point just past the required additional recovery time
failsafeOnValidDataReceived();
// when
failsafeOnRxCycleStarted();
// no call to failsafeOnValidDataReceived();
failsafeUpdateState();
// then
EXPECT_EQ(false, failsafeIsActive());
EXPECT_EQ(FAILSAFE_LANDED, failsafePhase());
EXPECT_EQ(FAILSAFE_IDLE, failsafePhase());
EXPECT_EQ(1, CALL_COUNTER(COUNTER_MW_DISARM)); // disarm not called repeatedly.
EXPECT_TRUE(ARMING_FLAG(PREVENT_ARMING));
EXPECT_FALSE(ARMING_FLAG(PREVENT_ARMING));
}
/****************************************************************************************/
TEST(FlightFailsafeTest, TestFailsafeDetectsRxLossAndJustDisarms)
{
// given
DISABLE_ARMING_FLAG(ARMED);
resetCallCounters();
// and
failsafeStartMonitoring();
throttleStatus = THROTTLE_LOW; // throttle LOW to go for a failsafe just-disarm procedure
sysTickUptime = 0; // restart time from 0
failsafeOnValidDataReceived(); // set last valid sample at current time
// when
for (sysTickUptime = 0; sysTickUptime < (uint32_t)(failsafeConfig.failsafe_delay * MILLIS_PER_TENTH_SECOND + PERIOD_RXDATA_FAILURE); sysTickUptime++) {
failsafeOnValidDataFailed();
failsafeUpdateState();
// then
EXPECT_EQ(false, failsafeIsActive());
EXPECT_EQ(FAILSAFE_IDLE, failsafePhase());
}
// given
sysTickUptime++; // adjust time to point just past the failure time to
failsafeOnValidDataFailed(); // cause a lost link
ENABLE_ARMING_FLAG(ARMED); // armed from here (disarmed state has cleared throttleLowPeriod).
// when
failsafeUpdateState();
// then
EXPECT_EQ(true, failsafeIsActive());
EXPECT_EQ(FAILSAFE_RX_LOSS_MONITORING, failsafePhase());
EXPECT_EQ(1, CALL_COUNTER(COUNTER_MW_DISARM));
EXPECT_TRUE(ARMING_FLAG(PREVENT_ARMING));
// given
failsafeOnValidDataFailed(); // set last invalid sample at current time
sysTickUptime += PERIOD_RXDATA_RECOVERY + 1; // adjust time to point just past the recovery time to
failsafeOnValidDataReceived(); // cause a recovered link
// when
failsafeUpdateState();
// then
EXPECT_EQ(true, failsafeIsActive());
EXPECT_EQ(FAILSAFE_RX_LOSS_MONITORING, failsafePhase());
EXPECT_EQ(1, CALL_COUNTER(COUNTER_MW_DISARM));
EXPECT_TRUE(ARMING_FLAG(PREVENT_ARMING));
// given
sysTickUptime += PERIOD_OF_3_SECONDS + 1; // adjust time to point just past the required additional recovery time
failsafeOnValidDataReceived();
// when
failsafeUpdateState();
// then
EXPECT_EQ(false, failsafeIsActive());
EXPECT_EQ(FAILSAFE_IDLE, failsafePhase());
EXPECT_EQ(1, CALL_COUNTER(COUNTER_MW_DISARM)); // disarm not called repeatedly.
EXPECT_FALSE(ARMING_FLAG(PREVENT_ARMING));
}
/****************************************************************************************/
TEST(FlightFailsafeTest, TestFailsafeDetectsKillswitchEvent)
{
// given
ENABLE_ARMING_FLAG(ARMED);
resetCallCounters();
failsafeStartMonitoring();
// and
throttleStatus = THROTTLE_HIGH; // throttle HIGH to go for a failsafe landing procedure
failsafeConfig.failsafe_kill_switch = 1; // configure AUX switch as kill switch
ACTIVATE_RC_MODE(BOXFAILSAFE); // and activate it
sysTickUptime = 0; // restart time from 0
failsafeOnValidDataReceived(); // set last valid sample at current time
sysTickUptime = PERIOD_RXDATA_FAILURE + 1; // adjust time to point just past the failure time to
failsafeOnValidDataFailed(); // cause a lost link
// when
failsafeUpdateState(); // kill switch handling should come first
// then
EXPECT_EQ(true, failsafeIsActive());
EXPECT_TRUE(ARMING_FLAG(PREVENT_ARMING));
EXPECT_EQ(1, CALL_COUNTER(COUNTER_MW_DISARM));
EXPECT_EQ(FAILSAFE_RX_LOSS_MONITORING, failsafePhase());
// given
failsafeOnValidDataFailed(); // set last invalid sample at current time
sysTickUptime += PERIOD_RXDATA_RECOVERY + 1; // adjust time to point just past the recovery time to
failsafeOnValidDataReceived(); // cause a recovered link
rcModeActivationMask = DE_ACTIVATE_ALL_BOXES; // BOXFAILSAFE must be off (kill switch)
// when
failsafeUpdateState();
// then
EXPECT_EQ(true, failsafeIsActive());
EXPECT_TRUE(ARMING_FLAG(PREVENT_ARMING));
EXPECT_EQ(1, CALL_COUNTER(COUNTER_MW_DISARM));
EXPECT_EQ(FAILSAFE_RX_LOSS_MONITORING, failsafePhase());
// given
sysTickUptime += PERIOD_OF_1_SECONDS + 1; // adjust time to point just past the required additional recovery time
failsafeOnValidDataReceived();
// when
failsafeUpdateState();
// then
EXPECT_EQ(false, failsafeIsActive());
EXPECT_EQ(FAILSAFE_IDLE, failsafePhase());
EXPECT_EQ(1, CALL_COUNTER(COUNTER_MW_DISARM)); // disarm not called repeatedly.
EXPECT_FALSE(ARMING_FLAG(PREVENT_ARMING));
}
/****************************************************************************************/
//
// Additional non-stepwise tests
//
/****************************************************************************************/
TEST(FlightFailsafeTest, TestFailsafeNotActivatedWhenDisarmedAndRXLossIsDetected)
{
// given
@ -288,28 +374,58 @@ TEST(FlightFailsafeTest, TestFailsafeNotActivatedWhenDisarmedAndRXLossIsDetected
failsafeStartMonitoring();
// and
int callsToMakeToSimulateTenSeconds = FAILSAFE_UPDATE_HZ * 10;
sysTickUptime = 0; // restart time from 0
failsafeOnValidDataReceived(); // set last valid sample at current time
for (int i = 0; i < callsToMakeToSimulateTenSeconds; i++) {
failsafeOnRxCycleStarted();
// no call to failsafeOnValidDataReceived();
// when
for (sysTickUptime = 0; sysTickUptime < PERIOD_RXDATA_FAILURE; sysTickUptime++) {
failsafeOnValidDataFailed();
failsafeUpdateState();
// then
EXPECT_EQ(true, failsafeIsMonitoring());
EXPECT_EQ(false, failsafeIsActive());
EXPECT_EQ(FAILSAFE_IDLE, failsafePhase());
}
}
// given
sysTickUptime++; // adjust time to point just past the failure time to
failsafeOnValidDataFailed(); // cause a lost link
// when
failsafeUpdateState();
// then
EXPECT_EQ(true, failsafeIsMonitoring());
EXPECT_EQ(false, failsafeIsActive());
EXPECT_EQ(FAILSAFE_IDLE, failsafePhase());
EXPECT_EQ(1, CALL_COUNTER(COUNTER_MW_DISARM));
EXPECT_FALSE(ARMING_FLAG(PREVENT_ARMING));
}
// STUBS
extern "C" {
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
uint8_t armingFlags;
int16_t rcCommand[4];
uint32_t rcModeActivationMask;
int16_t debug[DEBUG16_VALUE_COUNT];
bool isUsingSticksToArm = true;
// Return system uptime in milliseconds (rollover in 49 days)
uint32_t millis(void)
{
return sysTickUptime;
}
throttleStatus_e calculateThrottleStatus(rxConfig_t *rxConfig, uint16_t deadband3d_throttle)
{
UNUSED(rxConfig);
UNUSED(deadband3d_throttle);
return throttleStatus;
}
void delay(uint32_t) {}
@ -325,4 +441,26 @@ void beeper(beeperMode_e mode) {
UNUSED(mode);
}
uint16_t enableFlightMode(flightModeFlags_e mask)
{
flightModeFlags |= (mask);
return flightModeFlags;
}
uint16_t disableFlightMode(flightModeFlags_e mask)
{
flightModeFlags &= ~(mask);
return flightModeFlags;
}
uint16_t getCurrentMinthrottle(void)
{
return testMinThrottle;
}
bool isUsingSticksForArming(void)
{
return isUsingSticksToArm;
}
}

View file

@ -298,6 +298,26 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsSticksInMiddle)
TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp)
{
// given
controlRateConfig_t controlRateConfig = {
.rcRate8 = 90,
.rcExpo8 = 0,
.thrMid8 = 0,
.thrExpo8 = 0,
.rates = {0,0,0},
.dynThrPID = 0,
.rcYawExpo8 = 0,
.tpa_breakpoint = 0
};
// and
memset(&rxConfig, 0, sizeof (rxConfig));
rxConfig.mincheck = DEFAULT_MIN_CHECK;
rxConfig.maxcheck = DEFAULT_MAX_CHECK;
rxConfig.midrc = 1500;
// and
adjustmentStateMask = 0;
memset(&adjustmentStates, 0, sizeof(adjustmentStates));
configureAdjustment(0, AUX3 - NON_AUX_CHANNEL_COUNT, &rateAdjustmentConfig);
// and

View file

@ -31,7 +31,11 @@ extern "C" {
#include "unittest_macros.h"
#include "gtest/gtest.h"
#define DE_ACTIVATE_ALL_BOXES 0
extern "C" {
uint32_t rcModeActivationMask;
extern uint16_t applyRxChannelRangeConfiguraton(int sample, rxChannelRangeConfiguration_t range);
}
@ -39,6 +43,8 @@ extern uint16_t applyRxChannelRangeConfiguraton(int sample, rxChannelRangeConfig
TEST(RxChannelRangeTest, TestRxChannelRanges)
{
rcModeActivationMask = DE_ACTIVATE_ALL_BOXES; // BOXFAILSAFE must be OFF
// No signal, special condition
EXPECT_EQ(applyRxChannelRangeConfiguraton(0, RANGE_CONFIGURATION(1000, 2000)), 0);
EXPECT_EQ(applyRxChannelRangeConfiguraton(0, RANGE_CONFIGURATION(1300, 1700)), 0);
@ -184,7 +190,7 @@ void failsafeOnValidDataReceived(void)
{
}
void failsafeOnRxCycleStarted(void)
void failsafeOnValidDataFailed(void)
{
}

View file

@ -25,6 +25,8 @@ extern "C" {
#include "rx/rx.h"
uint32_t rcModeActivationMask;
void rxInit(rxConfig_t *rxConfig);
void rxResetFlightChannelStatus(void);
bool rxHaveValidFlightChannels(void);
@ -35,6 +37,8 @@ extern "C" {
#include "unittest_macros.h"
#include "gtest/gtest.h"
#define DE_ACTIVATE_ALL_BOXES 0
typedef struct testData_s {
bool isPPMDataBeingReceived;
bool isPWMDataBeingReceived;
@ -46,6 +50,7 @@ TEST(RxTest, TestValidFlightChannels)
{
// given
memset(&testData, 0, sizeof(testData));
rcModeActivationMask = DE_ACTIVATE_ALL_BOXES; // BOXFAILSAFE must be OFF
// and
rxConfig_t rxConfig;
@ -131,7 +136,7 @@ TEST(RxTest, TestInvalidFlightChannels)
// STUBS
extern "C" {
void failsafeOnRxCycleStarted() {}
void failsafeOnValidDataFailed() {}
void failsafeOnValidDataReceived() {}
bool feature(uint32_t mask) {