mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-13 11:29:56 +03:00
Bugfixes and prepare configurator integration
This commit is contained in:
parent
9330784729
commit
f330bdd621
27 changed files with 166 additions and 246 deletions
|
@ -811,16 +811,12 @@ static int logicConditionGetFlightModeOperandValue(int operand) {
|
|||
return (bool) FLIGHT_MODE(NAV_POSHOLD_MODE);
|
||||
break;
|
||||
|
||||
case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_WAYPOINT_MISSION:
|
||||
return (bool) FLIGHT_MODE(NAV_WP_MODE);
|
||||
break;
|
||||
|
||||
case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_COURSE_HOLD:
|
||||
return ((bool) FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && !(bool)FLIGHT_MODE(NAV_ALTHOLD_MODE));
|
||||
return (bool) FLIGHT_MODE(NAV_COURSE_HOLD_MODE);
|
||||
break;
|
||||
|
||||
case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_CRUISE:
|
||||
return (bool) (FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && FLIGHT_MODE(NAV_ALTHOLD_MODE));
|
||||
return (bool)(FLIGHT_MODE(NAV_COURSE_HOLD_MODE) && FLIGHT_MODE(NAV_ALTHOLD_MODE));
|
||||
break;
|
||||
|
||||
case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_ALTHOLD:
|
||||
|
@ -839,11 +835,6 @@ static int logicConditionGetFlightModeOperandValue(int operand) {
|
|||
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);
|
||||
break;
|
||||
|
||||
case LOGIC_CONDITION_OPERAND_FLIGHT_MODE_USER1:
|
||||
return IS_RC_MODE_ACTIVE(BOXUSER1);
|
||||
break;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue