Merge pull request #5092 from etracer65/airmode_activate_3d_fix
Change airmode activation to be throttle percent based to fix 3D mode
This commit is contained in:
commit
8738e7d623
|
@ -97,8 +97,6 @@ enum {
|
|||
|
||||
#define GYRO_WATCHDOG_DELAY 80 // delay for gyro sync
|
||||
|
||||
#define AIRMODE_THOTTLE_THRESHOLD 1350 // Make configurable in the future. ~35% throttle should be fine
|
||||
|
||||
#ifdef USE_RUNAWAY_TAKEOFF
|
||||
#define RUNAWAY_TAKEOFF_DEACTIVATE_STICK_PERCENT 15 // 15% - minimum stick deflection during deactivation phase
|
||||
#define RUNAWAY_TAKEOFF_DEACTIVATE_PIDSUM_LIMIT 100 // 10.0% - pidSum limit during deactivation phase
|
||||
|
@ -446,6 +444,7 @@ bool areSticksActive(uint8_t stickPercentLimit)
|
|||
}
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
// calculate the throttle stick percent - integer math is good enough here.
|
||||
|
@ -470,7 +469,7 @@ uint8_t calculateThrottlePercent(void)
|
|||
}
|
||||
return ret;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
/*
|
||||
* processRx called from taskUpdateRxMain
|
||||
|
@ -498,9 +497,10 @@ bool processRx(timeUs_t currentTimeUs)
|
|||
failsafeUpdateState();
|
||||
|
||||
const throttleStatus_e throttleStatus = calculateThrottleStatus();
|
||||
const uint8_t throttlePercent = calculateThrottlePercent();
|
||||
|
||||
if (isAirmodeActive() && ARMING_FLAG(ARMED)) {
|
||||
if (rcData[THROTTLE] >= rxConfig()->airModeActivateThreshold) {
|
||||
if (throttlePercent >= rxConfig()->airModeActivateThreshold) {
|
||||
airmodeIsActivated = true; // Prevent Iterm from being reset
|
||||
}
|
||||
} else {
|
||||
|
@ -538,7 +538,7 @@ bool processRx(timeUs_t currentTimeUs)
|
|||
// - pidSum on all axis is less then runaway_takeoff_deactivate_pidlimit
|
||||
bool inStableFlight = false;
|
||||
if (!feature(FEATURE_MOTOR_STOP) || isAirmodeActive() || (throttleStatus != THROTTLE_LOW)) { // are motors running?
|
||||
if ((calculateThrottlePercent() >= pidConfig()->runaway_takeoff_deactivate_throttle)
|
||||
if ((throttlePercent >= pidConfig()->runaway_takeoff_deactivate_throttle)
|
||||
&& areSticksActive(RUNAWAY_TAKEOFF_DEACTIVATE_STICK_PERCENT)
|
||||
&& (fabsf(axisPIDSum[FD_PITCH]) < RUNAWAY_TAKEOFF_DEACTIVATE_PIDSUM_LIMIT)
|
||||
&& (fabsf(axisPIDSum[FD_ROLL]) < RUNAWAY_TAKEOFF_DEACTIVATE_PIDSUM_LIMIT)
|
||||
|
|
|
@ -1015,7 +1015,7 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
|
|||
sbufWriteU16(dst, rxConfig()->rx_max_usec);
|
||||
sbufWriteU8(dst, rxConfig()->rcInterpolation);
|
||||
sbufWriteU8(dst, rxConfig()->rcInterpolationInterval);
|
||||
sbufWriteU16(dst, rxConfig()->airModeActivateThreshold);
|
||||
sbufWriteU16(dst, rxConfig()->airModeActivateThreshold * 10 + 1000);
|
||||
sbufWriteU8(dst, rxConfig()->rx_spi_protocol);
|
||||
sbufWriteU32(dst, rxConfig()->rx_spi_id);
|
||||
sbufWriteU8(dst, rxConfig()->rx_spi_rf_channel_count);
|
||||
|
@ -1878,7 +1878,7 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
if (sbufBytesRemaining(src) >= 4) {
|
||||
rxConfigMutable()->rcInterpolation = sbufReadU8(src);
|
||||
rxConfigMutable()->rcInterpolationInterval = sbufReadU8(src);
|
||||
rxConfigMutable()->airModeActivateThreshold = sbufReadU16(src);
|
||||
rxConfigMutable()->airModeActivateThreshold = (sbufReadU16(src) - 1000) / 10;
|
||||
}
|
||||
if (sbufBytesRemaining(src) >= 6) {
|
||||
rxConfigMutable()->rx_spi_protocol = sbufReadU8(src);
|
||||
|
|
|
@ -421,7 +421,7 @@ const clivalue_t valueTable[] = {
|
|||
{ "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, .config.minmax = { SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX}, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_sat_bind) },
|
||||
{ "spektrum_sat_bind_autoreset",VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_sat_bind_autoreset) },
|
||||
#endif
|
||||
{ "airmode_start_throttle", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 1000, 2000 }, PG_RX_CONFIG, offsetof(rxConfig_t, airModeActivateThreshold) },
|
||||
{ "airmode_start_throttle_percent", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_RX_CONFIG, offsetof(rxConfig_t, airModeActivateThreshold) },
|
||||
{ "rx_min_usec", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX }, PG_RX_CONFIG, offsetof(rxConfig_t, rx_min_usec) },
|
||||
{ "rx_max_usec", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX }, PG_RX_CONFIG, offsetof(rxConfig_t, rx_max_usec) },
|
||||
{ "serialrx_halfduplex", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, halfDuplex) },
|
||||
|
|
|
@ -124,7 +124,7 @@ static uint8_t rcSampleIndex = 0;
|
|||
#define BINDPLUG_PIN NONE
|
||||
#endif
|
||||
|
||||
PG_REGISTER_WITH_RESET_FN(rxConfig_t, rxConfig, PG_RX_CONFIG, 1);
|
||||
PG_REGISTER_WITH_RESET_FN(rxConfig_t, rxConfig, PG_RX_CONFIG, 2);
|
||||
void pgResetFn_rxConfig(rxConfig_t *rxConfig)
|
||||
{
|
||||
RESET_CONFIG_2(rxConfig_t, rxConfig,
|
||||
|
@ -148,7 +148,7 @@ void pgResetFn_rxConfig(rxConfig_t *rxConfig)
|
|||
.rcInterpolationChannels = 0,
|
||||
.rcInterpolationInterval = 19,
|
||||
.fpvCamAngleDegrees = 0,
|
||||
.airModeActivateThreshold = 1350,
|
||||
.airModeActivateThreshold = 32,
|
||||
.max_aux_channel = DEFAULT_AUX_CHANNEL_COUNT
|
||||
);
|
||||
|
||||
|
|
|
@ -139,7 +139,7 @@ typedef struct rxConfig_s {
|
|||
uint8_t rcInterpolationChannels;
|
||||
uint8_t rcInterpolationInterval;
|
||||
uint8_t fpvCamAngleDegrees; // Camera angle to be scaled into rc commands
|
||||
uint16_t airModeActivateThreshold; // Throttle setpoint where airmode gets activated
|
||||
uint8_t airModeActivateThreshold; // Throttle setpoint percent where airmode gets activated
|
||||
|
||||
uint16_t rx_min_usec;
|
||||
uint16_t rx_max_usec;
|
||||
|
|
Loading…
Reference in New Issue