1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-21 15:25:36 +03:00

Improved fixed wing detection.

This commit is contained in:
mikeller 2019-11-17 14:05:07 +13:00
parent 33ba8a043e
commit e0a6f1ab14
9 changed files with 52 additions and 33 deletions

View file

@ -197,7 +197,7 @@ static bool isCalibrating(void)
#ifdef USE_LAUNCH_CONTROL #ifdef USE_LAUNCH_CONTROL
bool canUseLaunchControl(void) bool canUseLaunchControl(void)
{ {
if (!STATE(FIXED_WING) if (!isFixedWing()
&& !isUsingSticksForArming() // require switch arming for safety && !isUsingSticksForArming() // require switch arming for safety
&& IS_RC_MODE_ACTIVE(BOXLAUNCHCONTROL) && IS_RC_MODE_ACTIVE(BOXLAUNCHCONTROL)
&& (!featureIsEnabled(FEATURE_MOTOR_STOP) || airmodeIsEnabled()) // can't use when motors are stopped && (!featureIsEnabled(FEATURE_MOTOR_STOP) || airmodeIsEnabled()) // can't use when motors are stopped
@ -795,7 +795,7 @@ bool processRx(timeUs_t currentTimeUs)
&& !runawayTakeoffCheckDisabled && !runawayTakeoffCheckDisabled
&& !flipOverAfterCrashActive && !flipOverAfterCrashActive
&& !runawayTakeoffTemporarilyDisabled && !runawayTakeoffTemporarilyDisabled
&& !STATE(FIXED_WING)) { && !isFixedWing()) {
// Determine if we're in "flight" // Determine if we're in "flight"
// - motors running // - motors running
@ -880,7 +880,7 @@ bool processRx(timeUs_t currentTimeUs)
const timeUs_t autoDisarmDelayUs = armingConfig()->auto_disarm_delay * 1e6; const timeUs_t autoDisarmDelayUs = armingConfig()->auto_disarm_delay * 1e6;
if (ARMING_FLAG(ARMED) if (ARMING_FLAG(ARMED)
&& featureIsEnabled(FEATURE_MOTOR_STOP) && featureIsEnabled(FEATURE_MOTOR_STOP)
&& !STATE(FIXED_WING) && !isFixedWing()
&& !featureIsEnabled(FEATURE_3D) && !featureIsEnabled(FEATURE_3D)
&& !airmodeIsEnabled() && !airmodeIsEnabled()
&& !FLIGHT_MODE(GPS_RESCUE_MODE) // disable auto-disarm when GPS Rescue is active && !FLIGHT_MODE(GPS_RESCUE_MODE) // disable auto-disarm when GPS Rescue is active
@ -1082,7 +1082,7 @@ static FAST_CODE void subTaskPidController(timeUs_t currentTimeUs)
// and gyro rate for any axis is above the limit for at least the activate delay period. // and gyro rate for any axis is above the limit for at least the activate delay period.
// If so, disarm for safety // If so, disarm for safety
if (ARMING_FLAG(ARMED) if (ARMING_FLAG(ARMED)
&& !STATE(FIXED_WING) && !isFixedWing()
&& pidConfig()->runaway_takeoff_prevention && pidConfig()->runaway_takeoff_prevention
&& !runawayTakeoffCheckDisabled && !runawayTakeoffCheckDisabled
&& !flipOverAfterCrashActive && !flipOverAfterCrashActive

View file

@ -115,7 +115,6 @@ typedef enum {
GPS_FIX = (1 << 1), GPS_FIX = (1 << 1),
CALIBRATE_MAG = (1 << 2), CALIBRATE_MAG = (1 << 2),
SMALL_ANGLE = (1 << 3), SMALL_ANGLE = (1 << 3),
FIXED_WING = (1 << 4) // set when in flying_wing or airplane mode. currently used by althold selection code
} stateFlags_t; } stateFlags_t;
#define DISABLE_STATE(mask) (stateFlags &= ~(mask)) #define DISABLE_STATE(mask) (stateFlags &= ~(mask))

View file

@ -451,7 +451,7 @@ static void imuCalculateEstimatedAttitude(timeUs_t currentTimeUs)
#if defined(USE_GPS) #if defined(USE_GPS)
if (!useMag && sensors(SENSOR_GPS) && STATE(GPS_FIX) && gpsSol.numSat >= 5 && gpsSol.groundSpeed >= GPS_COG_MIN_GROUNDSPEED) { if (!useMag && sensors(SENSOR_GPS) && STATE(GPS_FIX) && gpsSol.numSat >= 5 && gpsSol.groundSpeed >= GPS_COG_MIN_GROUNDSPEED) {
// Use GPS course over ground to correct attitude.values.yaw // Use GPS course over ground to correct attitude.values.yaw
if (STATE(FIXED_WING)) { if (isFixedWing()) {
courseOverGround = DECIDEGREES_TO_RADIANS(gpsSol.groundCourse); courseOverGround = DECIDEGREES_TO_RADIANS(gpsSol.groundCourse);
useCOG = true; useCOG = true;
} else { } else {

View file

@ -938,3 +938,25 @@ float mixerGetThrottle(void)
{ {
return mixerThrottle; return mixerThrottle;
} }
mixerMode_e getMixerMode(void)
{
return currentMixerMode;
}
bool isFixedWing(void)
{
switch (currentMixerMode) {
case MIXER_FLYING_WING:
case MIXER_AIRPLANE:
case MIXER_CUSTOM_AIRPLANE:
return true;
break;
default:
return false;
break;
}
}

View file

@ -112,3 +112,5 @@ bool mixerIsTricopter(void);
void mixerSetThrottleAngleCorrection(int correctionValue); void mixerSetThrottleAngleCorrection(int correctionValue);
float mixerGetThrottle(void); float mixerGetThrottle(void);
mixerMode_e getMixerMode(void);
bool isFixedWing(void);

View file

@ -32,15 +32,12 @@
#include "common/filter.h" #include "common/filter.h"
#include "common/maths.h" #include "common/maths.h"
#include "config/config.h"
#include "config/config_reset.h" #include "config/config_reset.h"
#include "config/feature.h" #include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "drivers/pwm_output.h" #include "drivers/pwm_output.h"
#include "config/config.h"
#include "fc/rc_controls.h" #include "fc/rc_controls.h"
#include "fc/rc_modes.h" #include "fc/rc_modes.h"
#include "fc/runtime_config.h" #include "fc/runtime_config.h"
@ -52,11 +49,13 @@
#include "io/gimbal.h" #include "io/gimbal.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "rx/rx.h" #include "rx/rx.h"
extern mixerMode_e currentMixerMode;
PG_REGISTER_WITH_RESET_FN(servoConfig_t, servoConfig, PG_SERVO_CONFIG, 0); PG_REGISTER_WITH_RESET_FN(servoConfig_t, servoConfig, PG_SERVO_CONFIG, 0);
void pgResetFn_servoConfig(servoConfig_t *servoConfig) void pgResetFn_servoConfig(servoConfig_t *servoConfig)
@ -222,7 +221,7 @@ int servoDirection(int servoIndex, int inputSource)
void servosInit(void) void servosInit(void)
{ {
// enable servos for mixes that require them. note, this shifts motor counts. // enable servos for mixes that require them. note, this shifts motor counts.
useServo = mixers[currentMixerMode].useServo; useServo = mixers[getMixerMode()].useServo;
// if we want camstab/trig, that also enables servos, even if mixer doesn't // if we want camstab/trig, that also enables servos, even if mixer doesn't
if (featureIsEnabled(FEATURE_SERVO_TILT) || featureIsEnabled(FEATURE_CHANNEL_FORWARDING)) { if (featureIsEnabled(FEATURE_SERVO_TILT) || featureIsEnabled(FEATURE_CHANNEL_FORWARDING)) {
useServo = 1; useServo = 1;
@ -258,27 +257,21 @@ void loadCustomServoMixer(void)
void servoConfigureOutput(void) void servoConfigureOutput(void)
{ {
if (useServo) { if (useServo) {
servoRuleCount = servoMixers[currentMixerMode].servoRuleCount; servoRuleCount = servoMixers[getMixerMode()].servoRuleCount;
if (servoMixers[currentMixerMode].rule) { if (servoMixers[getMixerMode()].rule) {
for (int i = 0; i < servoRuleCount; i++) for (int i = 0; i < servoRuleCount; i++)
currentServoMixer[i] = servoMixers[currentMixerMode].rule[i]; currentServoMixer[i] = servoMixers[getMixerMode()].rule[i];
} }
} }
// set flag that we're on something with wings switch (getMixerMode()) {
if (currentMixerMode == MIXER_FLYING_WING || case MIXER_CUSTOM_AIRPLANE:
currentMixerMode == MIXER_AIRPLANE || case MIXER_CUSTOM_TRI:
currentMixerMode == MIXER_CUSTOM_AIRPLANE loadCustomServoMixer();
) {
ENABLE_STATE(FIXED_WING); break;
if (currentMixerMode == MIXER_CUSTOM_AIRPLANE) { default:
loadCustomServoMixer(); break;
}
} else {
DISABLE_STATE(FIXED_WING);
if (currentMixerMode == MIXER_CUSTOM_TRI) {
loadCustomServoMixer();
}
} }
} }
@ -333,7 +326,7 @@ void writeServos(void)
filterServos(); filterServos();
uint8_t servoIndex = 0; uint8_t servoIndex = 0;
switch (currentMixerMode) { switch (getMixerMode()) {
case MIXER_TRI: case MIXER_TRI:
case MIXER_CUSTOM_TRI: case MIXER_CUSTOM_TRI:
// We move servo if unarmed flag set or armed // We move servo if unarmed flag set or armed
@ -385,7 +378,7 @@ void writeServos(void)
} }
// Two servos for SERVO_TILT, if enabled // Two servos for SERVO_TILT, if enabled
if (featureIsEnabled(FEATURE_SERVO_TILT) || currentMixerMode == MIXER_GIMBAL) { if (featureIsEnabled(FEATURE_SERVO_TILT) || getMixerMode() == MIXER_GIMBAL) {
updateGimbalServos(servoIndex); updateGimbalServos(servoIndex);
servoIndex += 2; servoIndex += 2;
} }
@ -486,7 +479,7 @@ void servoMixer(void)
static void servoTable(void) static void servoTable(void)
{ {
// airplane / servo mixes // airplane / servo mixes
switch (currentMixerMode) { switch (getMixerMode()) {
case MIXER_CUSTOM_TRI: case MIXER_CUSTOM_TRI:
case MIXER_TRI: case MIXER_TRI:
servosTricopterMixer(); servosTricopterMixer();

View file

@ -1090,4 +1090,5 @@ extern "C" {
float getCosTiltAngle(void) { return 0.0f; } float getCosTiltAngle(void) { return 0.0f; }
void pidSetItermReset(bool) {} void pidSetItermReset(bool) {}
void applyAccelerometerTrimsDelta(rollAndPitchTrims_t*) {} void applyAccelerometerTrimsDelta(rollAndPitchTrims_t*) {}
bool isFixedWing(void) { return false; }
} }

View file

@ -246,4 +246,5 @@ bool gyroGetAccumulationAverage(float *) { return false; }
bool accGetAccumulationAverage(float *) { return false; } bool accGetAccumulationAverage(float *) { return false; }
void mixerSetThrottleAngleCorrection(int) {}; void mixerSetThrottleAngleCorrection(int) {};
bool gpsRescueIsRunning(void) { return false; } bool gpsRescueIsRunning(void) { return false; }
bool isFixedWing(void) { return false; }
} }

View file

@ -178,4 +178,5 @@ extern "C" {
void osdSuppressStats(bool) {} void osdSuppressStats(bool) {}
void pidSetItermReset(bool) {} void pidSetItermReset(bool) {}
void applyAccelerometerTrimsDelta(rollAndPitchTrims_t*) {} void applyAccelerometerTrimsDelta(rollAndPitchTrims_t*) {}
bool isFixedWing(void) { return false; }
} }