1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-13 11:29:56 +03:00

Merge branch 'master' of https://github.com/iNavFlight/inav into submit-gps-fix-estimation

This commit is contained in:
Roman Lut 2023-11-03 14:40:40 +01:00
commit 9a633d1337
32 changed files with 960 additions and 368 deletions

View file

@ -486,7 +486,6 @@ static int logicConditionCompute(
return operandA;
break;
#endif
#ifdef USE_GPS_FIX_ESTIMATION
case LOGIC_CONDITION_DISABLE_GPS_FIX:
if (operandA > 0) {
@ -877,13 +876,18 @@ static int logicConditionGetFlightModeOperandValue(int operand) {
return (bool) FLIGHT_MODE(HORIZON_MODE);
break;
case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ANGLEHOLD:
return (bool) FLIGHT_MODE(ANGLEHOLD_MODE);
break;
case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_AIR:
return (bool) FLIGHT_MODE(AIRMODE_ACTIVE);
break;
case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ACRO:
return (((bool) FLIGHT_MODE(ANGLE_MODE) || (bool) FLIGHT_MODE(HORIZON_MODE) || (bool) FLIGHT_MODE(MANUAL_MODE) || (bool) FLIGHT_MODE(NAV_RTH_MODE) ||
(bool) FLIGHT_MODE(NAV_POSHOLD_MODE) || (bool) FLIGHT_MODE(NAV_COURSE_HOLD_MODE) || (bool) FLIGHT_MODE(NAV_WP_MODE)) == false);
return (((bool) FLIGHT_MODE(ANGLE_MODE) || (bool) FLIGHT_MODE(HORIZON_MODE) || (bool) FLIGHT_MODE(ANGLEHOLD_MODE) ||
(bool) FLIGHT_MODE(MANUAL_MODE) || (bool) FLIGHT_MODE(NAV_RTH_MODE) || (bool) FLIGHT_MODE(NAV_POSHOLD_MODE) ||
(bool) FLIGHT_MODE(NAV_COURSE_HOLD_MODE) || (bool) FLIGHT_MODE(NAV_WP_MODE)) == false);
break;
case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER1: