1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-18 22:05:15 +03:00

add flown loiter radius for fixed wing

This commit is contained in:
breadoven 2024-06-29 13:43:10 +01:00
parent 41c89a7784
commit 817981fa4b
4 changed files with 65 additions and 51 deletions

View file

@ -5074,5 +5074,12 @@ bool canFwLandingBeCancelled(void)
{ {
return FLIGHT_MODE(NAV_FW_AUTOLAND) && posControl.navState != NAV_STATE_FW_LANDING_FLARE; return FLIGHT_MODE(NAV_FW_AUTOLAND) && posControl.navState != NAV_STATE_FW_LANDING_FLARE;
} }
#endif #endif
uint16_t getFlownLoiterRadius(void)
{
if (STATE(AIRPLANE) && navGetCurrentStateFlags() & NAV_CTL_HOLD) {
return CENTIMETERS_TO_METERS(calculateDistanceToDestination(&posControl.desiredState.pos));
}
return 0;
}

View file

@ -694,6 +694,7 @@ bool rthAltControlStickOverrideCheck(uint8_t axis);
int8_t navCheckActiveAngleHoldAxis(void); int8_t navCheckActiveAngleHoldAxis(void);
uint8_t getActiveWpNumber(void); uint8_t getActiveWpNumber(void);
uint16_t getFlownLoiterRadius(void);
/* Returns the heading recorded when home position was acquired. /* Returns the heading recorded when home position was acquired.
* Note that the navigation system uses deg*100 as unit and angles * Note that the navigation system uses deg*100 as unit and angles

View file

@ -97,7 +97,7 @@ static int logicConditionCompute(
int temporaryValue; int temporaryValue;
#if defined(USE_VTX_CONTROL) #if defined(USE_VTX_CONTROL)
vtxDeviceCapability_t vtxDeviceCapability; vtxDeviceCapability_t vtxDeviceCapability;
#endif #endif
switch (operation) { switch (operation) {
@ -154,7 +154,7 @@ static int logicConditionCompute(
case LOGIC_CONDITION_NOR: case LOGIC_CONDITION_NOR:
return !(operandA || operandB); return !(operandA || operandB);
break; break;
case LOGIC_CONDITION_NOT: case LOGIC_CONDITION_NOT:
return !operandA; return !operandA;
@ -170,7 +170,7 @@ static int logicConditionCompute(
return false; return false;
} }
//When both operands are not met, keep current value //When both operands are not met, keep current value
return currentValue; return currentValue;
break; break;
@ -238,7 +238,7 @@ static int logicConditionCompute(
gvSet(operandA, operandB); gvSet(operandA, operandB);
return operandB; return operandB;
break; break;
case LOGIC_CONDITION_GVAR_INC: case LOGIC_CONDITION_GVAR_INC:
temporaryValue = gvGet(operandA) + operandB; temporaryValue = gvGet(operandA) + operandB;
gvSet(operandA, temporaryValue); gvSet(operandA, temporaryValue);
@ -270,7 +270,7 @@ static int logicConditionCompute(
return operandA; return operandA;
} }
break; break;
case LOGIC_CONDITION_OVERRIDE_ARMING_SAFETY: case LOGIC_CONDITION_OVERRIDE_ARMING_SAFETY:
LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY); LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY);
return true; return true;
@ -293,12 +293,12 @@ static int logicConditionCompute(
ENABLE_STATE(CALIBRATE_MAG); ENABLE_STATE(CALIBRATE_MAG);
return true; return true;
break; break;
#endif #endif
case LOGIC_CONDITION_SET_VTX_POWER_LEVEL: case LOGIC_CONDITION_SET_VTX_POWER_LEVEL:
#if defined(USE_VTX_CONTROL) #if defined(USE_VTX_CONTROL)
#if(defined(USE_VTX_SMARTAUDIO) || defined(USE_VTX_TRAMP)) #if(defined(USE_VTX_SMARTAUDIO) || defined(USE_VTX_TRAMP))
if ( if (
logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_POWER_LEVEL] != operandA && logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_POWER_LEVEL] != operandA &&
vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability) vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability)
) { ) {
logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_POWER_LEVEL] = constrain(operandA, VTX_SETTINGS_MIN_POWER, vtxDeviceCapability.powerCount); logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_POWER_LEVEL] = constrain(operandA, VTX_SETTINGS_MIN_POWER, vtxDeviceCapability.powerCount);
@ -346,18 +346,18 @@ static int logicConditionCompute(
LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_PITCH); LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_PITCH);
return true; return true;
break; break;
case LOGIC_CONDITION_INVERT_YAW: case LOGIC_CONDITION_INVERT_YAW:
LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_YAW); LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_YAW);
return true; return true;
break; break;
case LOGIC_CONDITION_OVERRIDE_THROTTLE: case LOGIC_CONDITION_OVERRIDE_THROTTLE:
logicConditionValuesByType[LOGIC_CONDITION_OVERRIDE_THROTTLE] = operandA; logicConditionValuesByType[LOGIC_CONDITION_OVERRIDE_THROTTLE] = operandA;
LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE); LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE);
return operandA; return operandA;
break; break;
case LOGIC_CONDITION_SET_OSD_LAYOUT: case LOGIC_CONDITION_SET_OSD_LAYOUT:
logicConditionValuesByType[LOGIC_CONDITION_SET_OSD_LAYOUT] = operandA; logicConditionValuesByType[LOGIC_CONDITION_SET_OSD_LAYOUT] = operandA;
LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT); LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT);
@ -373,18 +373,18 @@ static int logicConditionCompute(
case LOGIC_CONDITION_SIN: case LOGIC_CONDITION_SIN:
temporaryValue = (operandB == 0) ? 500 : operandB; temporaryValue = (operandB == 0) ? 500 : operandB;
return sin_approx(DEGREES_TO_RADIANS(operandA)) * temporaryValue; return sin_approx(DEGREES_TO_RADIANS(operandA)) * temporaryValue;
break; break;
case LOGIC_CONDITION_COS: case LOGIC_CONDITION_COS:
temporaryValue = (operandB == 0) ? 500 : operandB; temporaryValue = (operandB == 0) ? 500 : operandB;
return cos_approx(DEGREES_TO_RADIANS(operandA)) * temporaryValue; return cos_approx(DEGREES_TO_RADIANS(operandA)) * temporaryValue;
break; break;
break; break;
case LOGIC_CONDITION_TAN: case LOGIC_CONDITION_TAN:
temporaryValue = (operandB == 0) ? 500 : operandB; temporaryValue = (operandB == 0) ? 500 : operandB;
return tan_approx(DEGREES_TO_RADIANS(operandA)) * temporaryValue; return tan_approx(DEGREES_TO_RADIANS(operandA)) * temporaryValue;
break; break;
case LOGIC_CONDITION_MIN: case LOGIC_CONDITION_MIN:
@ -394,11 +394,11 @@ static int logicConditionCompute(
case LOGIC_CONDITION_MAX: case LOGIC_CONDITION_MAX:
return (operandA > operandB) ? operandA : operandB; return (operandA > operandB) ? operandA : operandB;
break; break;
case LOGIC_CONDITION_MAP_INPUT: case LOGIC_CONDITION_MAP_INPUT:
return scaleRange(constrain(operandA, 0, operandB), 0, operandB, 0, 1000); return scaleRange(constrain(operandA, 0, operandB), 0, operandB, 0, 1000);
break; break;
case LOGIC_CONDITION_MAP_OUTPUT: case LOGIC_CONDITION_MAP_OUTPUT:
return scaleRange(constrain(operandA, 0, 1000), 0, 1000, 0, operandB); return scaleRange(constrain(operandA, 0, 1000), 0, 1000, 0, operandB);
break; break;
@ -507,7 +507,7 @@ static int logicConditionCompute(
default: default:
return false; return false;
break; break;
} }
} }
@ -516,7 +516,7 @@ void logicConditionProcess(uint8_t i) {
const int activatorValue = logicConditionGetValue(logicConditions(i)->activatorId); const int activatorValue = logicConditionGetValue(logicConditions(i)->activatorId);
if (logicConditions(i)->enabled && activatorValue && !cliMode) { if (logicConditions(i)->enabled && activatorValue && !cliMode) {
/* /*
* Process condition only when latch flag is not set * Process condition only when latch flag is not set
* Latched LCs can only go from OFF to ON, not the other way * Latched LCs can only go from OFF to ON, not the other way
@ -525,13 +525,13 @@ void logicConditionProcess(uint8_t i) {
const int operandAValue = logicConditionGetOperandValue(logicConditions(i)->operandA.type, logicConditions(i)->operandA.value); const int operandAValue = logicConditionGetOperandValue(logicConditions(i)->operandA.type, logicConditions(i)->operandA.value);
const int operandBValue = logicConditionGetOperandValue(logicConditions(i)->operandB.type, logicConditions(i)->operandB.value); const int operandBValue = logicConditionGetOperandValue(logicConditions(i)->operandB.type, logicConditions(i)->operandB.value);
const int newValue = logicConditionCompute( const int newValue = logicConditionCompute(
logicConditionStates[i].value, logicConditionStates[i].value,
logicConditions(i)->operation, logicConditions(i)->operation,
operandAValue, operandAValue,
operandBValue, operandBValue,
i i
); );
logicConditionStates[i].value = newValue; logicConditionStates[i].value = newValue;
/* /*
@ -606,7 +606,7 @@ static int logicConditionGetWaypointOperandValue(int operand) {
return distance; return distance;
} }
break; break;
case LOGIC_CONDITION_OPERAND_WAYPOINTS_USER1_ACTION: case LOGIC_CONDITION_OPERAND_WAYPOINTS_USER1_ACTION:
return (NAV_Status.activeWpIndex > 0) ? ((posControl.waypointList[NAV_Status.activeWpIndex-1].p3 & NAV_WP_USER1) == NAV_WP_USER1) : 0; return (NAV_Status.activeWpIndex > 0) ? ((posControl.waypointList[NAV_Status.activeWpIndex-1].p3 & NAV_WP_USER1) == NAV_WP_USER1) : 0;
break; break;
@ -652,11 +652,11 @@ static int logicConditionGetFlightOperandValue(int operand) {
case LOGIC_CONDITION_OPERAND_FLIGHT_ARM_TIMER: // in s case LOGIC_CONDITION_OPERAND_FLIGHT_ARM_TIMER: // in s
return constrain((uint32_t)getFlightTime(), 0, INT16_MAX); return constrain((uint32_t)getFlightTime(), 0, INT16_MAX);
break; break;
case LOGIC_CONDITION_OPERAND_FLIGHT_HOME_DISTANCE: //in m case LOGIC_CONDITION_OPERAND_FLIGHT_HOME_DISTANCE: //in m
return constrain(GPS_distanceToHome, 0, INT16_MAX); return constrain(GPS_distanceToHome, 0, INT16_MAX);
break; break;
case LOGIC_CONDITION_OPERAND_FLIGHT_TRIP_DISTANCE: //in m case LOGIC_CONDITION_OPERAND_FLIGHT_TRIP_DISTANCE: //in m
return constrain(getTotalTravelDistance() / 100, 0, INT16_MAX); return constrain(getTotalTravelDistance() / 100, 0, INT16_MAX);
break; break;
@ -664,7 +664,7 @@ static int logicConditionGetFlightOperandValue(int operand) {
case LOGIC_CONDITION_OPERAND_FLIGHT_RSSI: case LOGIC_CONDITION_OPERAND_FLIGHT_RSSI:
return constrain(getRSSI() * 100 / RSSI_MAX_VALUE, 0, 99); return constrain(getRSSI() * 100 / RSSI_MAX_VALUE, 0, 99);
break; break;
case LOGIC_CONDITION_OPERAND_FLIGHT_VBAT: // V / 100 case LOGIC_CONDITION_OPERAND_FLIGHT_VBAT: // V / 100
return getBatteryVoltage(); return getBatteryVoltage();
break; break;
@ -680,7 +680,7 @@ static int logicConditionGetFlightOperandValue(int operand) {
case LOGIC_CONDITION_OPERAND_FLIGHT_CURRENT: // Amp / 100 case LOGIC_CONDITION_OPERAND_FLIGHT_CURRENT: // Amp / 100
return getAmperage(); return getAmperage();
break; break;
case LOGIC_CONDITION_OPERAND_FLIGHT_MAH_DRAWN: // mAh case LOGIC_CONDITION_OPERAND_FLIGHT_MAH_DRAWN: // mAh
return getMAhDrawn(); return getMAhDrawn();
break; break;
@ -697,7 +697,7 @@ static int logicConditionGetFlightOperandValue(int operand) {
return gpsSol.numSat; return gpsSol.numSat;
} }
break; break;
case LOGIC_CONDITION_OPERAND_FLIGHT_GPS_VALID: // 0/1 case LOGIC_CONDITION_OPERAND_FLIGHT_GPS_VALID: // 0/1
return STATE(GPS_FIX) ? 1 : 0; return STATE(GPS_FIX) ? 1 : 0;
break; break;
@ -749,15 +749,15 @@ static int logicConditionGetFlightOperandValue(int operand) {
case LOGIC_CONDITION_OPERAND_FLIGHT_IS_AUTOLAUNCH: // 0/1 case LOGIC_CONDITION_OPERAND_FLIGHT_IS_AUTOLAUNCH: // 0/1
return (navGetCurrentStateFlags() & NAV_CTL_LAUNCH) ? 1 : 0; return (navGetCurrentStateFlags() & NAV_CTL_LAUNCH) ? 1 : 0;
break; break;
case LOGIC_CONDITION_OPERAND_FLIGHT_IS_ALTITUDE_CONTROL: // 0/1 case LOGIC_CONDITION_OPERAND_FLIGHT_IS_ALTITUDE_CONTROL: // 0/1
return (navGetCurrentStateFlags() & NAV_CTL_ALT) ? 1 : 0; return (navGetCurrentStateFlags() & NAV_CTL_ALT) ? 1 : 0;
break; break;
case LOGIC_CONDITION_OPERAND_FLIGHT_IS_POSITION_CONTROL: // 0/1 case LOGIC_CONDITION_OPERAND_FLIGHT_IS_POSITION_CONTROL: // 0/1
return (navGetCurrentStateFlags() & NAV_CTL_POS) ? 1 : 0; return (navGetCurrentStateFlags() & NAV_CTL_POS) ? 1 : 0;
break; break;
case LOGIC_CONDITION_OPERAND_FLIGHT_IS_EMERGENCY_LANDING: // 0/1 case LOGIC_CONDITION_OPERAND_FLIGHT_IS_EMERGENCY_LANDING: // 0/1
return (navGetCurrentStateFlags() & NAV_CTL_EMERG) ? 1 : 0; return (navGetCurrentStateFlags() & NAV_CTL_EMERG) ? 1 : 0;
@ -765,7 +765,7 @@ static int logicConditionGetFlightOperandValue(int operand) {
case LOGIC_CONDITION_OPERAND_FLIGHT_IS_RTH: // 0/1 case LOGIC_CONDITION_OPERAND_FLIGHT_IS_RTH: // 0/1
return (navGetCurrentStateFlags() & NAV_AUTO_RTH) ? 1 : 0; return (navGetCurrentStateFlags() & NAV_AUTO_RTH) ? 1 : 0;
break; break;
case LOGIC_CONDITION_OPERAND_FLIGHT_IS_LANDING: // 0/1 case LOGIC_CONDITION_OPERAND_FLIGHT_IS_LANDING: // 0/1
#ifdef USE_FW_AUTOLAND #ifdef USE_FW_AUTOLAND
@ -773,22 +773,22 @@ static int logicConditionGetFlightOperandValue(int operand) {
#else #else
return ((navGetCurrentStateFlags() & NAV_CTL_LAND)) ? 1 : 0; return ((navGetCurrentStateFlags() & NAV_CTL_LAND)) ? 1 : 0;
#endif #endif
break; break;
case LOGIC_CONDITION_OPERAND_FLIGHT_IS_FAILSAFE: // 0/1 case LOGIC_CONDITION_OPERAND_FLIGHT_IS_FAILSAFE: // 0/1
return (failsafePhase() != FAILSAFE_IDLE) ? 1 : 0; return (failsafePhase() != FAILSAFE_IDLE) ? 1 : 0;
break; break;
case LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_YAW: // case LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_YAW: //
return axisPID[YAW]; return axisPID[YAW];
break; break;
case LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_ROLL: // case LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_ROLL: //
return axisPID[ROLL]; return axisPID[ROLL];
break; break;
case LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_PITCH: // case LOGIC_CONDITION_OPERAND_FLIGHT_STABILIZED_PITCH: //
return axisPID[PITCH]; return axisPID[PITCH];
break; break;
@ -819,7 +819,7 @@ static int logicConditionGetFlightOperandValue(int operand) {
case LOGIC_CONDITION_OPERAND_FLIGHT_BATT_PROFILE: //int case LOGIC_CONDITION_OPERAND_FLIGHT_BATT_PROFILE: //int
return getConfigBatteryProfile() + 1; return getConfigBatteryProfile() + 1;
break; break;
case LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_MIXER_PROFILE: // int case LOGIC_CONDITION_OPERAND_FLIGHT_ACTIVE_MIXER_PROFILE: // int
return currentMixerProfileIndex + 1; return currentMixerProfileIndex + 1;
break; break;
@ -830,15 +830,20 @@ static int logicConditionGetFlightOperandValue(int operand) {
case LOGIC_CONDITION_OPERAND_FLIGHT_LOITER_RADIUS: case LOGIC_CONDITION_OPERAND_FLIGHT_LOITER_RADIUS:
return getLoiterRadius(navConfig()->fw.loiter_radius); return getLoiterRadius(navConfig()->fw.loiter_radius);
break;
case LOGIC_CONDITION_OPERAND_FLIGHT_FLOWN_LOITER_RADIUS:
return getFlownLoiterRadius();
break;
case LOGIC_CONDITION_OPERAND_FLIGHT_AGL_STATUS: case LOGIC_CONDITION_OPERAND_FLIGHT_AGL_STATUS:
return isEstimatedAglTrusted(); return isEstimatedAglTrusted();
break; break;
case LOGIC_CONDITION_OPERAND_FLIGHT_AGL: case LOGIC_CONDITION_OPERAND_FLIGHT_AGL:
return getEstimatedAglPosition(); return getEstimatedAglPosition();
break; break;
case LOGIC_CONDITION_OPERAND_FLIGHT_RANGEFINDER_RAW: case LOGIC_CONDITION_OPERAND_FLIGHT_RANGEFINDER_RAW:
return rangefinderGetLatestRawAltitude(); return rangefinderGetLatestRawAltitude();
break; break;
@ -946,7 +951,7 @@ int logicConditionGetOperandValue(logicOperandType_e type, int operand) {
//Extract RC channel raw value //Extract RC channel raw value
if (operand >= 1 && operand <= MAX_SUPPORTED_RC_CHANNEL_COUNT) { if (operand >= 1 && operand <= MAX_SUPPORTED_RC_CHANNEL_COUNT) {
retVal = rxGetChannelValue(operand - 1); retVal = rxGetChannelValue(operand - 1);
} }
break; break;
case LOGIC_CONDITION_OPERAND_TYPE_FLIGHT: case LOGIC_CONDITION_OPERAND_TYPE_FLIGHT:
@ -974,7 +979,7 @@ int logicConditionGetOperandValue(logicOperandType_e type, int operand) {
retVal = programmingPidGetOutput(operand); retVal = programmingPidGetOutput(operand);
} }
break; break;
case LOGIC_CONDITION_OPERAND_TYPE_WAYPOINTS: case LOGIC_CONDITION_OPERAND_TYPE_WAYPOINTS:
retVal = logicConditionGetWaypointOperandValue(operand); retVal = logicConditionGetWaypointOperandValue(operand);
break; break;
@ -988,7 +993,7 @@ int logicConditionGetOperandValue(logicOperandType_e type, int operand) {
/* /*
* conditionId == -1 is always evaluated as true * conditionId == -1 is always evaluated as true
*/ */
int logicConditionGetValue(int8_t conditionId) { int logicConditionGetValue(int8_t conditionId) {
if (conditionId >= 0) { if (conditionId >= 0) {
return logicConditionStates[conditionId].value; return logicConditionStates[conditionId].value;
@ -1070,7 +1075,7 @@ int16_t getRcChannelOverride(uint8_t channel, int16_t originalValue) {
uint32_t getLoiterRadius(uint32_t loiterRadius) { uint32_t getLoiterRadius(uint32_t loiterRadius) {
#ifdef USE_PROGRAMMING_FRAMEWORK #ifdef USE_PROGRAMMING_FRAMEWORK
if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_LOITER_RADIUS) && if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_LOITER_RADIUS) &&
!(FLIGHT_MODE(FAILSAFE_MODE) || FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding())) { !(FLIGHT_MODE(FAILSAFE_MODE) || FLIGHT_MODE(NAV_RTH_MODE) || FLIGHT_MODE(NAV_WP_MODE) || navigationIsExecutingAnEmergencyLanding())) {
return constrain(logicConditionValuesByType[LOGIC_CONDITION_LOITER_OVERRIDE], loiterRadius, 100000); return constrain(logicConditionValuesByType[LOGIC_CONDITION_LOITER_OVERRIDE], loiterRadius, 100000);
} else { } else {

View file

@ -143,6 +143,7 @@ typedef enum {
LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_YAW, // deg // 40 LOGIC_CONDITION_OPERAND_FLIGHT_ATTITUDE_YAW, // deg // 40
LOGIC_CONDITION_OPERAND_FLIGHT_FW_LAND_STATE, // 41 LOGIC_CONDITION_OPERAND_FLIGHT_FW_LAND_STATE, // 41
LOGIC_CONDITION_OPERAND_FLIGHT_BATT_PROFILE, // int // 42 LOGIC_CONDITION_OPERAND_FLIGHT_BATT_PROFILE, // int // 42
LOGIC_CONDITION_OPERAND_FLIGHT_FLOWN_LOITER_RADIUS, // 43
} logicFlightOperands_e; } logicFlightOperands_e;
typedef enum { typedef enum {