Merge branch 'master' into airmode_fix

This commit is contained in:
rav-rav 2018-10-25 11:13:54 +02:00 committed by GitHub
commit 5530eb3eb5
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
12 changed files with 70 additions and 50 deletions

View File

@ -578,7 +578,7 @@ bool processRx(timeUs_t currentTimeUs)
const throttleStatus_e throttleStatus = calculateThrottleStatus();
const uint8_t throttlePercent = calculateThrottlePercent();
if (isAirmodeActive() && ARMING_FLAG(ARMED)) {
if (airmodeIsEnabled() && ARMING_FLAG(ARMED)) {
if (throttlePercent >= rxConfig()->airModeActivateThreshold) {
airmodeIsActivated = true; // Prevent iterm from being reset
}
@ -618,7 +618,7 @@ bool processRx(timeUs_t currentTimeUs)
// - sticks are active and have deflection greater than runaway_takeoff_deactivate_stick_percent
// - pidSum on all axis is less then runaway_takeoff_deactivate_pidlimit
bool inStableFlight = false;
if (!featureIsEnabled(FEATURE_MOTOR_STOP) || isAirmodeActive() || (throttleStatus != THROTTLE_LOW)) { // are motors running?
if (!featureIsEnabled(FEATURE_MOTOR_STOP) || airmodeIsEnabled() || (throttleStatus != THROTTLE_LOW)) { // are motors running?
const uint8_t lowThrottleLimit = pidConfig()->runaway_takeoff_deactivate_throttle;
const uint8_t midThrottleLimit = constrain(lowThrottleLimit * 2, lowThrottleLimit * 2, RUNAWAY_TAKEOFF_HIGH_THROTTLE_PERCENT);
if ((((throttlePercent >= lowThrottleLimit) && areSticksActive(RUNAWAY_TAKEOFF_DEACTIVATE_STICK_PERCENT)) || (throttlePercent >= midThrottleLimit))
@ -674,7 +674,7 @@ bool processRx(timeUs_t currentTimeUs)
&& featureIsEnabled(FEATURE_MOTOR_STOP)
&& !STATE(FIXED_WING)
&& !featureIsEnabled(FEATURE_3D)
&& !isAirmodeActive()
&& !airmodeIsEnabled()
) {
if (isUsingSticksForArming()) {
if (throttleStatus == THROTTLE_LOW) {
@ -872,7 +872,7 @@ static FAST_CODE void subTaskPidController(timeUs_t currentTimeUs)
&& !runawayTakeoffCheckDisabled
&& !flipOverAfterCrashMode
&& !runawayTakeoffTemporarilyDisabled
&& (!featureIsEnabled(FEATURE_MOTOR_STOP) || isAirmodeActive() || (calculateThrottleStatus() != THROTTLE_LOW))) {
&& (!featureIsEnabled(FEATURE_MOTOR_STOP) || airmodeIsEnabled() || (calculateThrottleStatus() != THROTTLE_LOW))) {
if (((fabsf(pidData[FD_PITCH].Sum) >= RUNAWAY_TAKEOFF_PIDSUM_THRESHOLD)
|| (fabsf(pidData[FD_ROLL].Sum) >= RUNAWAY_TAKEOFF_PIDSUM_THRESHOLD)

View File

@ -216,7 +216,8 @@ void processRcStickPositions()
if (!ARMING_FLAG(ARMED)) {
// Arm via YAW
tryArm();
if (isTryingToArm()) {
if (isTryingToArm() ||
((getArmingDisableFlags() == ARMING_DISABLED_CALIBRATING) && armingConfig()->gyro_cal_on_first_arm)) {
doNotRepeat = false;
}
} else {

View File

@ -45,6 +45,8 @@
boxBitmask_t rcModeActivationMask; // one bit per mode defined in boxId_e
static boxBitmask_t stickyModesEverDisabled;
static bool airmodeEnabled;
PG_REGISTER_ARRAY(modeActivationCondition_t, MAX_MODE_ACTIVATION_CONDITION_COUNT, modeActivationConditions,
PG_MODE_ACTIVATION_PROFILE, 1);
@ -58,8 +60,8 @@ void rcModeUpdate(boxBitmask_t *newState)
rcModeActivationMask = *newState;
}
bool isAirmodeActive(void) {
return (IS_RC_MODE_ACTIVE(BOXAIRMODE) || featureIsEnabled(FEATURE_AIRMODE));
bool airmodeIsEnabled(void) {
return airmodeEnabled;
}
bool isRangeActive(uint8_t auxChannelIndex, const channelRange_t *range) {
@ -136,6 +138,8 @@ void updateActivatedModes(void)
}
rcModeUpdate(&newMask);
airmodeEnabled = featureIsEnabled(FEATURE_AIRMODE) || IS_RC_MODE_ACTIVE(BOXAIRMODE);
}
bool isModeActivationConditionPresent(boxId_e modeId)

View File

@ -126,7 +126,7 @@ typedef struct modeActivationProfile_s {
bool IS_RC_MODE_ACTIVE(boxId_e boxId);
void rcModeUpdate(boxBitmask_t *newState);
bool isAirmodeActive(void);
bool airmodeIsEnabled(void);
bool isRangeActive(uint8_t auxChannelIndex, const channelRange_t *range);
void updateActivatedModes(void);

View File

@ -785,10 +785,12 @@ FAST_CODE_NOINLINE void mixTable(timeUs_t currentTimeUs, uint8_t vbatPidCompensa
throttle = applyThrottleLimit(throttle);
}
const bool airmodeEnabled = airmodeIsEnabled();
#ifdef USE_YAW_SPIN_RECOVERY
// 50% throttle provides the maximum authority for yaw recovery when airmode is not active.
// When airmode is active the throttle setting doesn't impact recovery authority.
if (yawSpinDetected && !isAirmodeActive()) {
if (yawSpinDetected && !airmodeEnabled) {
throttle = 0.5f; //
}
#endif // USE_YAW_SPIN_RECOVERY
@ -835,11 +837,11 @@ FAST_CODE_NOINLINE void mixTable(timeUs_t currentTimeUs, uint8_t vbatPidCompensa
motorMix[i] /= motorMixRange;
}
// Get the maximum correction by setting offset to center when airmode enabled
if (isAirmodeActive()) {
if (airmodeEnabled) {
throttle = 0.5f;
}
} else {
if (isAirmodeActive() || throttle > 0.5f) { // Only automatically adjust throttle when airmode enabled. Airmode logic is always active on high throttle
if (airmodeEnabled || throttle > 0.5f) { // Only automatically adjust throttle when airmode enabled. Airmode logic is always active on high throttle
throttle = constrainf(throttle, -motorMixMin, 1.0f - motorMixMax);
}
}
@ -847,7 +849,7 @@ FAST_CODE_NOINLINE void mixTable(timeUs_t currentTimeUs, uint8_t vbatPidCompensa
if (featureIsEnabled(FEATURE_MOTOR_STOP)
&& ARMING_FLAG(ARMED)
&& !featureIsEnabled(FEATURE_3D)
&& !isAirmodeActive()
&& !airmodeEnabled
&& (rcData[THROTTLE] < rxConfig()->mincheck)) {
// motor_stop handling
applyMotorStop();

View File

@ -177,8 +177,7 @@ static uint8_t beep_multiBeeps[MAX_MULTI_BEEPS + 1];
#define BEEPER_WARNING_BEEP_2_DURATION 5
#define BEEPER_WARNING_BEEP_GAP_DURATION 10
// Beeper off = 0 Beeper on = 1
static uint8_t beeperIsOn = 0;
static bool beeperIsOn = false;
// Place in current sequence
static uint16_t beeperPos = 0;
@ -283,12 +282,11 @@ void beeper(beeperMode_e mode)
void beeperSilence(void)
{
BEEP_OFF;
beeperIsOn = false;
warningLedDisable();
warningLedRefresh();
beeperIsOn = 0;
beeperNextToggleTime = 0;
beeperPos = 0;
@ -399,8 +397,6 @@ void beeperUpdate(timeUs_t currentTimeUs)
}
if (!beeperIsOn) {
beeperIsOn = 1;
#ifdef USE_DSHOT
if (!areMotorsRunning()
&& ((currentBeeperEntry->mode == BEEPER_RX_SET && !(beeperConfig()->dshotBeaconOffFlags & BEEPER_GET_FLAG(BEEPER_RX_SET)))
@ -414,8 +410,11 @@ void beeperUpdate(timeUs_t currentTimeUs)
#endif
if (currentBeeperEntry->sequence[beeperPos] != 0) {
if (!(beeperConfigMutable()->beeper_off_flags & BEEPER_GET_FLAG(currentBeeperEntry->mode)))
if (!(beeperConfigMutable()->beeper_off_flags & BEEPER_GET_FLAG(currentBeeperEntry->mode))) {
BEEP_ON;
beeperIsOn = true;
}
warningLedEnable();
warningLedRefresh();
// if this was arming beep then mark time (for blackbox)
@ -427,9 +426,10 @@ void beeperUpdate(timeUs_t currentTimeUs)
}
}
} else {
beeperIsOn = 0;
if (currentBeeperEntry->sequence[beeperPos] != 0) {
BEEP_OFF;
beeperIsOn = false;
warningLedDisable();
warningLedRefresh();
}

View File

@ -268,13 +268,13 @@ static int32_t osdGetMetersToSelectedUnit(int32_t meters)
}
#if defined(USE_ADC_INTERNAL) || defined(USE_ESC_SENSOR)
STATIC_UNIT_TESTED int osdConvertTemperatureToSelectedUnit(int tempInDeciDegrees)
STATIC_UNIT_TESTED int osdConvertTemperatureToSelectedUnit(int tempInDegreesCelcius)
{
switch (osdConfig()->units) {
case OSD_UNIT_IMPERIAL:
return ((tempInDeciDegrees * 9) / 5) + 320;
return lrintf(((tempInDegreesCelcius * 9.0f) / 5) + 32);
default:
return tempInDeciDegrees;
return tempInDegreesCelcius;
}
}
@ -604,13 +604,13 @@ static bool osdDrawSingleElement(uint8_t item)
case OSD_REMAINING_TIME_ESTIMATE:
{
const int mAhDrawn = getMAhDrawn();
const int remaining_time = (int)((osdConfig()->cap_alarm - mAhDrawn) * ((float)flyTime) / mAhDrawn);
if (mAhDrawn < 0.1 * osdConfig()->cap_alarm) {
if (mAhDrawn <= 0.1 * osdConfig()->cap_alarm) { // also handles the mAhDrawn == 0 condition
tfp_sprintf(buff, "--:--");
} else if (mAhDrawn > osdConfig()->cap_alarm) {
tfp_sprintf(buff, "00:00");
} else {
const int remaining_time = (int)((osdConfig()->cap_alarm - mAhDrawn) * ((float)flyTime) / mAhDrawn);
osdFormatTime(buff, OSD_TIMER_PREC_SECOND, remaining_time);
}
break;
@ -637,7 +637,7 @@ static bool osdDrawSingleElement(uint8_t item)
strcpy(buff, "HOR ");
} else if (IS_RC_MODE_ACTIVE(BOXACROTRAINER)) {
strcpy(buff, "ATRN");
} else if (isAirmodeActive()) {
} else if (airmodeIsEnabled()) {
strcpy(buff, "AIR ");
} else {
strcpy(buff, "ACRO");
@ -745,8 +745,11 @@ static bool osdDrawSingleElement(uint8_t item)
}
case OSD_G_FORCE:
tfp_sprintf(buff, "%01d.%01dG", (int)osdGForce, (int)(osdGForce * 10) % 10);
break;
{
const int gForce = lrintf(osdGForce * 10);
tfp_sprintf(buff, "%01d.%01dG", gForce / 10, gForce % 10);
break;
}
case OSD_ROLL_PIDS:
osdFormatPID(buff, "ROL", &currentPidProfile->pid[PID_ROLL]);
@ -848,10 +851,10 @@ static bool osdDrawSingleElement(uint8_t item)
}
#ifdef USE_ADC_INTERNAL
uint8_t coreTemperature = getCoreTemperatureCelsius();
const int16_t coreTemperature = getCoreTemperatureCelsius();
if (osdWarnGetState(OSD_WARNING_CORE_TEMPERATURE) && coreTemperature >= osdConfig()->core_temp_alarm) {
char coreTemperatureWarningMsg[OSD_FORMAT_MESSAGE_BUFFER_SIZE];
tfp_sprintf(coreTemperatureWarningMsg, "CORE: %3d%c", osdConvertTemperatureToSelectedUnit(getCoreTemperatureCelsius() * 10) / 10, osdGetTemperatureSymbolForSelectedUnit());
tfp_sprintf(coreTemperatureWarningMsg, "CORE: %3d%c", osdConvertTemperatureToSelectedUnit(coreTemperature), osdGetTemperatureSymbolForSelectedUnit());
osdFormatMessage(buff, OSD_FORMAT_MESSAGE_BUFFER_SIZE, coreTemperatureWarningMsg);
@ -1019,7 +1022,7 @@ static bool osdDrawSingleElement(uint8_t item)
#ifdef USE_ESC_SENSOR
case OSD_ESC_TMP:
if (featureIsEnabled(FEATURE_ESC_SENSOR)) {
tfp_sprintf(buff, "%3d%c", osdConvertTemperatureToSelectedUnit(escDataCombined->temperature * 10) / 10, osdGetTemperatureSymbolForSelectedUnit());
tfp_sprintf(buff, "%3d%c", osdConvertTemperatureToSelectedUnit(escDataCombined->temperature), osdGetTemperatureSymbolForSelectedUnit());
}
break;
@ -1046,7 +1049,7 @@ static bool osdDrawSingleElement(uint8_t item)
#ifdef USE_ADC_INTERNAL
case OSD_CORE_TEMPERATURE:
tfp_sprintf(buff, "%3d%c", osdConvertTemperatureToSelectedUnit(getCoreTemperatureCelsius() * 10) / 10, osdGetTemperatureSymbolForSelectedUnit());
tfp_sprintf(buff, "%3d%c", osdConvertTemperatureToSelectedUnit(getCoreTemperatureCelsius()), osdGetTemperatureSymbolForSelectedUnit());
break;
#endif
@ -1080,13 +1083,16 @@ static void osdDrawElements(void)
return;
}
osdGForce = 0.0f;
if (sensors(SENSOR_ACC)) {
osdGForce = 0.0f;
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
const float a = accAverage[axis];
osdGForce += a * a;
// only calculate the G force if the element is visible or the stat is enabled
if (VISIBLE(osdConfig()->item_pos[OSD_G_FORCE]) || osdStatGetState(OSD_STAT_MAX_G_FORCE)) {
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
const float a = accAverage[axis];
osdGForce += a * a;
}
osdGForce = sqrtf(osdGForce) * acc.dev.acc_1G_rec;
}
osdGForce = sqrtf(osdGForce) * acc.dev.acc_1G_rec;
osdDrawSingleElement(OSD_ARTIFICIAL_HORIZON);
osdDrawSingleElement(OSD_G_FORCE);
}
@ -1387,7 +1393,7 @@ static void osdUpdateStats(void)
#endif
#ifdef USE_ESC_SENSOR
if (featureIsEnabled(FEATURE_ESC_SENSOR)) {
value = (escDataCombined->temperature * 10) / 10;
value = escDataCombined->temperature;
if (stats.max_esc_temp < value) {
stats.max_esc_temp = value;
}
@ -1554,13 +1560,15 @@ static void osdShowStats(uint16_t endBatteryVoltage)
}
#endif
if (osdStatGetState(OSD_STAT_MAX_G_FORCE)) {
tfp_sprintf(buff, "%01d.%01dG", (int)stats.max_g_force, (int)(stats.max_g_force * 10) % 10);
if (osdStatGetState(OSD_STAT_MAX_G_FORCE) && sensors(SENSOR_ACC)) {
const int gForce = lrintf(stats.max_g_force * 10);
tfp_sprintf(buff, "%01d.%01dG", gForce / 10, gForce % 10);
osdDisplayStatisticLabel(top++, "MAX G-FORCE", buff);
}
#ifdef USE_ESC_SENSOR
if (osdStatGetState(OSD_STAT_MAX_ESC_TEMP)) {
tfp_sprintf(buff, "%3d%c", osdConvertTemperatureToSelectedUnit(stats.max_esc_temp * 10) / 10, osdGetTemperatureSymbolForSelectedUnit());
tfp_sprintf(buff, "%3d%c", osdConvertTemperatureToSelectedUnit(stats.max_esc_temp), osdGetTemperatureSymbolForSelectedUnit());
osdDisplayStatisticLabel(top++, "MAX ESC TEMP", buff);
}
@ -1568,6 +1576,7 @@ static void osdShowStats(uint16_t endBatteryVoltage)
itoa(stats.max_esc_rpm, buff, 10);
osdDisplayStatisticLabel(top++, "MAX ESC RPM", buff);
}
#endif
}

View File

@ -64,7 +64,7 @@
#define USE_SDCARD_SPI
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_PIN PE15
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream3
#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
#define SDCARD_DMA_CHANNEL 0
#define USE_VCP

View File

@ -268,7 +268,7 @@ void crsfFrameFlightMode(sbuf_t *dst)
// use same logic as OSD, so telemetry displays same flight text as OSD
const char *flightMode = "ACRO";
if (isAirmodeActive()) {
if (airmodeIsEnabled()) {
flightMode = "AIR";
}
if (FLIGHT_MODE(FAILSAFE_MODE)) {

View File

@ -58,7 +58,7 @@ extern "C" {
void osdRefresh(timeUs_t currentTimeUs);
void osdFormatTime(char * buff, osd_timer_precision_e precision, timeUs_t time);
void osdFormatTimer(char *buff, bool showSymbol, int timerIndex);
int osdConvertTemperatureToSelectedUnit(int tempInDeciDegrees);
int osdConvertTemperatureToSelectedUnit(int tempInDegreesCelcius);
uint16_t rssi;
attitudeEulerAngles_t attitude;
@ -941,11 +941,15 @@ TEST(OsdTest, TestConvertTemperatureUnits)
{
/* In Celsius */
osdConfigMutable()->units = OSD_UNIT_METRIC;
EXPECT_EQ(osdConvertTemperatureToSelectedUnit(330), 330);
EXPECT_EQ(osdConvertTemperatureToSelectedUnit(40), 40);
/* In Fahrenheit */
osdConfigMutable()->units = OSD_UNIT_IMPERIAL;
EXPECT_EQ(osdConvertTemperatureToSelectedUnit(330), 914);
EXPECT_EQ(osdConvertTemperatureToSelectedUnit(40), 104);
/* In Fahrenheit with rounding */
osdConfigMutable()->units = OSD_UNIT_IMPERIAL;
EXPECT_EQ(osdConvertTemperatureToSelectedUnit(41), 106);
}
// STUBS
@ -972,7 +976,7 @@ extern "C" {
return false;
}
bool isAirmodeActive() {
bool airmodeIsEnabled() {
return false;
}

View File

@ -278,7 +278,7 @@ extern "C" {
bool featureIsEnabled(uint32_t) {return false;}
bool isAirmodeActive(void) {return true;}
bool airmodeIsEnabled(void) {return true;}
mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn) {

View File

@ -312,7 +312,7 @@ bool telemetryCheckRxPortShared(const serialPortConfig_t *) {return true;}
portSharing_e determinePortSharing(const serialPortConfig_t *, serialPortFunction_e) {return PORTSHARING_NOT_SHARED;}
bool isAirmodeActive(void) {return airMode;}
bool airmodeIsEnabled(void) {return airMode;}
int32_t getAmperage(void) {
return testAmperage;