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

Merge pull request #5971 from iNavFlight/dzikuvx-logic-condition-global-function-unification

Unify Global Functions and Logic Conditions into single entity
This commit is contained in:
Paweł Spychalski 2020-07-23 12:21:26 +02:00 committed by GitHub
commit 75066b30dd
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
14 changed files with 254 additions and 526 deletions

View file

@ -1,79 +0,0 @@
# Global Functions
_Global Functions_ (abbr. GF) are a mechanism allowing to override certain flight parameters (during flight). Global Functions are activated by [Logic Conditions](Logic%20Conditions.md)
## CLI
`gf <rule> <enabled> <logic condition> <action> <operand type> <operand value> <flags>`
* `<rule>` - GF ID, indexed from `0`
* `<enabled>` - `0` evaluates as disabled, `1` evaluates as enabled. Only enabled GFs are executed
* `<logic condition>` - the ID of _LogicCondition_ used to trigger GF On/Off. Then LC evaluates `true`, GlobalFunction will be come active
* `<action>` - action to execute when GF is active
* `<operand type>` - allows to pass arguments into Global Function action. Syntax is the same as in case of Logic Conditions operands. Used only when `action` requires it. Should be kept at `0` in other case. See [Logic Conditions](Logic%20Conditions.md)
* `<operand value>` - allows to pass arguments into Global Function action. Syntax is the same as in case of Logic Conditions operands. Used only when `action` requires it. Should be kept at `0` in other case. See [Logic Conditions](Logic%20Conditions.md)
* `<flags>` - allows to pass arguments into Global Function action. Syntax is the same as in case of Logic Conditions operands
## Actions
| Action ID | Name | Notes |
|---- |---- |---- |
| 0 | OVERRIDE_ARMING_SAFETY | Allows to arm on any angle even without GPS fix |
| 1 | OVERRIDE_THROTTLE_SCALE | Override throttle scale to the value defined by operand. Operand type `0` and value `50` means throttle will be scaled by 50%. |
| 2 | SWAP_ROLL_YAW | basically, when activated, yaw stick will control roll and roll stick will control yaw. Required for tail-sitters VTOL during vertical-horizonral transition when body frame changes |
| 3 | SET_VTX_POWER_LEVEL | Sets VTX power level. Accepted values are `0-3` for SmartAudio and `0-4` for Tramp protocol |
| 4 | INVERT_ROLL | Inverts ROLL axis input for PID/PIFF controller |
| 5 | INVERT_PITCH | Inverts PITCH axis input for PID/PIFF controller |
| 6 | INVERT_YAW | Inverts YAW axis input for PID/PIFF controller |
| 7 | OVERRIDE_THROTTLE | Override throttle value that is fed to the motors by mixer. Operand is scaled in us. `1000` means throttle cut, `1500` means half throttle |
| 8 | SET_VTX_BAND | Sets VTX band. Accepted values are `1-5` |
| 9 | SET_VTX_CHANNEL | Sets VTX channel. Accepted values are `1-8` |
| 10 | SET_OSD_LAYOUT | Sets OSD layout. Accepted values are `0-3` |
## Flags
Current no flags are implemented
## Example
### Dynamic THROTTLE scale
`gf 0 1 0 1 0 50 0`
Limits the THROTTLE output to 50% when Logic Condition `0` evaluates as `true`
### Set VTX power level via Smart Audio
`gf 0 1 0 3 0 3 0`
Sets VTX power level to `3` when Logic Condition `0` evaluates as `true`
### Invert ROLL and PITCH when rear facing camera FPV is used
Solves the problem from [https://github.com/iNavFlight/inav/issues/4439](https://github.com/iNavFlight/inav/issues/4439)
```
gf 0 1 0 4 0 0 0
gf 1 1 0 5 0 0 0
```
Inverts ROLL and PITCH input when Logic Condition `0` evaluates as `true`. Moving Pitch stick up will cause pitch down (up for rear facing camera). Moving Roll stick right will cause roll left of a quad (right in rear facing camera)
### Cut motors but keep other throttle bindings active
`gf 0 1 0 7 0 1000 0`
Sets Thhrottle output to `0%` when Logic Condition `0` evaluates as `true`
### Set throttle to 50% and keep other throttle bindings active
`gf 0 1 0 7 0 1500 0`
Sets Thhrottle output to about `50%` when Logic Condition `0` evaluates as `true`
### Set throttle control to different RC channel
`gf 0 1 0 7 1 7 0`
If Logic Condition `0` evaluates as `true`, motor throttle control is bound to RC channel 7 instead of throttle channel

View file

@ -1,11 +1,16 @@
# Logic Conditions
# INAV Programming Framework
Logic Conditions (abbr. LC) is a mechanism that allows to evaluate cenrtain flight parameters (RC channels, switches, altitude, distance, timers, other logic conditions) and use the value of evaluated expression in different places of INAV. Currently, the result of LCs can be used in:
INAV Programming Framework (abbr. IPF) is a mechanism that allows to evaluate cenrtain flight parameters (RC channels, switches, altitude, distance, timers, other logic conditions) and use the value of evaluated expression in different places of INAV. Currently, the result of LCs can be used in:
* [Servo mixer](Mixer.md) to activate/deactivate certain servo mix rulers
* [Global functions](Global%20Functions.md) to activate/deactivate system overrides
* To activate/deactivate system overrides
Logic conditions can be edited using INAV Configurator user interface, of via CLI
INAV Programming Framework coinsists of:
* Logic Conditions - each Logic Condition can be understood as a single command, a single line of code
* Global Variables - variables that can store values from and for LogiC Conditions and servo mixer
IPF can be edited using INAV Configurator user interface, of via CLI
## CLI
@ -46,7 +51,19 @@ Logic conditions can be edited using INAV Configurator user interface, of via CL
| 18 | GVAR SET | Store value from `Operand B` into the Global Variable addressed by `Operand B`. Bear in mind, that operand `Global Variable` means: Value stored in Global Variable of an index! To store in GVAR 1 use `Value 1` not `Global Variable 1` |
| 19 | GVAR INC | Increase the GVAR indexed by `Operand A` with value from `Operand B` |
| 20 | GVAR DEC | Decrease the GVAR indexed by `Operand A` with value from `Operand B` |
| 128 | IO PORT SET | Set I2C IO Expander pin `Operand A` to value of `Operand B`. `Operand A` accepts values `0-7` and `Operand B` accepts `0` and `1` |
| 21 | IO PORT SET | Set I2C IO Expander pin `Operand A` to value of `Operand B`. `Operand A` accepts values `0-7` and `Operand B` accepts `0` and `1` |
| 22 | OVERRIDE_ARMING_SAFETY | Allows to arm on any angle even without GPS fix |
| 23 | OVERRIDE_THROTTLE_SCALE | Override throttle scale to the value defined by operand. Operand type `0` and value `50` means throttle will be scaled by 50%. |
| 24 | SWAP_ROLL_YAW | basically, when activated, yaw stick will control roll and roll stick will control yaw. Required for tail-sitters VTOL during vertical-horizonral transition when body frame changes |
| 25 | SET_VTX_POWER_LEVEL | Sets VTX power level. Accepted values are `0-3` for SmartAudio and `0-4` for Tramp protocol |
| 26 | INVERT_ROLL | Inverts ROLL axis input for PID/PIFF controller |
| 27 | INVERT_PITCH | Inverts PITCH axis input for PID/PIFF controller |
| 28 | INVERT_YAW | Inverts YAW axis input for PID/PIFF controller |
| 29 | OVERRIDE_THROTTLE | Override throttle value that is fed to the motors by mixer. Operand is scaled in us. `1000` means throttle cut, `1500` means half throttle |
| 30 | SET_VTX_BAND | Sets VTX band. Accepted values are `1-5` |
| 31 | SET_VTX_CHANNEL | Sets VTX channel. Accepted values are `1-8` |
| 32 | SET_OSD_LAYOUT | Sets OSD layout. Accepted values are `0-3` |
### Operands
@ -112,3 +129,47 @@ All flags are reseted on ARM and DISARM event.
| bit | Decimal | Function |
|---- |---- |---- |
| 0 | 1 | Latch - after activation LC will stay active until LATCH flag is reseted |
## Examples
### Dynamic THROTTLE scale
`logic 0 1 0 23 0 50 0 0 0`
Limits the THROTTLE output to 50% when Logic Condition `0` evaluates as `true`
### Set VTX power level via Smart Audio
`logic 0 1 0 25 0 3 0 0 0`
Sets VTX power level to `3` when Logic Condition `0` evaluates as `true`
### Invert ROLL and PITCH when rear facing camera FPV is used
Solves the problem from [https://github.com/iNavFlight/inav/issues/4439](https://github.com/iNavFlight/inav/issues/4439)
```
logic 0 1 0 26 0 0 0 0 0
logic 1 1 0 27 0 0 0 0 0
```
Inverts ROLL and PITCH input when Logic Condition `0` evaluates as `true`. Moving Pitch stick up will cause pitch down (up for rear facing camera). Moving Roll stick right will cause roll left of a quad (right in rear facing camera)
### Cut motors but keep other throttle bindings active
`logic 0 1 0 29 0 1000 0 0 0`
Sets Thhrottle output to `0%` when Logic Condition `0` evaluates as `true`
### Set throttle to 50% and keep other throttle bindings active
`logic 0 1 0 29 0 1500 0 0 0`
Sets Thhrottle output to about `50%` when Logic Condition `0` evaluates as `true`
### Set throttle control to different RC channel
`logic 0 1 0 29 1 7 0 0 0`
If Logic Condition `0` evaluates as `true`, motor throttle control is bound to RC channel 7 instead of throttle channel

View file

@ -38,7 +38,6 @@ MAIN_SRC = \
common/time.c \
common/uvarint.c \
programming/logic_condition.c \
programming/global_functions.c \
programming/global_variables.c \
programming/programming_task.c \
config/config_eeprom.c \

View file

@ -43,7 +43,6 @@ extern uint8_t __config_end;
#include "common/memory.h"
#include "common/time.h"
#include "common/typeconversion.h"
#include "programming/global_functions.h"
#include "programming/global_variables.h"
#include "config/config_eeprom.h"
@ -1950,104 +1949,6 @@ static void cliGvar(char *cmdline) {
#endif
#ifdef USE_PROGRAMMING_FRAMEWORK
static void printGlobalFunctions(uint8_t dumpMask, const globalFunction_t *globalFunctions, const globalFunction_t *defaultGlobalFunctions)
{
const char *format = "gf %d %d %d %d %d %d %d";
for (uint32_t i = 0; i < MAX_GLOBAL_FUNCTIONS; i++) {
const globalFunction_t gf = globalFunctions[i];
bool equalsDefault = false;
if (defaultGlobalFunctions) {
globalFunction_t defaultValue = defaultGlobalFunctions[i];
equalsDefault =
gf.enabled == defaultValue.enabled &&
gf.conditionId == defaultValue.conditionId &&
gf.action == defaultValue.action &&
gf.withValue.type == defaultValue.withValue.type &&
gf.withValue.value == defaultValue.withValue.value &&
gf.flags == defaultValue.flags;
cliDefaultPrintLinef(dumpMask, equalsDefault, format,
i,
gf.enabled,
gf.conditionId,
gf.action,
gf.withValue.type,
gf.withValue.value,
gf.flags
);
}
cliDumpPrintLinef(dumpMask, equalsDefault, format,
i,
gf.enabled,
gf.conditionId,
gf.action,
gf.withValue.type,
gf.withValue.value,
gf.flags
);
}
}
static void cliGlobalFunctions(char *cmdline) {
char * saveptr;
int args[7], check = 0;
uint8_t len = strlen(cmdline);
if (len == 0) {
printGlobalFunctions(DUMP_MASTER, globalFunctions(0), NULL);
} else if (sl_strncasecmp(cmdline, "reset", 5) == 0) {
pgResetCopy(globalFunctionsMutable(0), PG_GLOBAL_FUNCTIONS);
} else {
enum {
INDEX = 0,
ENABLED,
CONDITION_ID,
ACTION,
VALUE_TYPE,
VALUE_VALUE,
FLAGS,
ARGS_COUNT
};
char *ptr = strtok_r(cmdline, " ", &saveptr);
while (ptr != NULL && check < ARGS_COUNT) {
args[check++] = fastA2I(ptr);
ptr = strtok_r(NULL, " ", &saveptr);
}
if (ptr != NULL || check != ARGS_COUNT) {
cliShowParseError();
return;
}
int32_t i = args[INDEX];
if (
i >= 0 && i < MAX_GLOBAL_FUNCTIONS &&
args[ENABLED] >= 0 && args[ENABLED] <= 1 &&
args[CONDITION_ID] >= -1 && args[CONDITION_ID] < MAX_LOGIC_CONDITIONS &&
args[ACTION] >= 0 && args[ACTION] < GLOBAL_FUNCTION_ACTION_LAST &&
args[VALUE_TYPE] >= 0 && args[VALUE_TYPE] < LOGIC_CONDITION_OPERAND_TYPE_LAST &&
args[VALUE_VALUE] >= -1000000 && args[VALUE_VALUE] <= 1000000 &&
args[FLAGS] >= 0 && args[FLAGS] <= 255
) {
globalFunctionsMutable(i)->enabled = args[ENABLED];
globalFunctionsMutable(i)->conditionId = args[CONDITION_ID];
globalFunctionsMutable(i)->action = args[ACTION];
globalFunctionsMutable(i)->withValue.type = args[VALUE_TYPE];
globalFunctionsMutable(i)->withValue.value = args[VALUE_VALUE];
globalFunctionsMutable(i)->flags = args[FLAGS];
cliGlobalFunctions("");
} else {
cliShowParseError();
}
}
}
#endif
#ifdef USE_SDCARD
static void cliWriteBytes(const uint8_t *buffer, int count)
@ -3329,11 +3230,6 @@ static void printConfig(const char *cmdline, bool doDiff)
printGvar(dumpMask, globalVariableConfigs_CopyArray, globalVariableConfigs(0));
#endif
#ifdef USE_PROGRAMMING_FRAMEWORK
cliPrintHashLine("gf");
printGlobalFunctions(dumpMask, globalFunctions_CopyArray, globalFunctions(0));
#endif
cliPrintHashLine("feature");
printFeature(dumpMask, &featureConfig_Copy, featureConfig());
@ -3580,11 +3476,6 @@ const clicmd_t cmdTable[] = {
CLI_COMMAND_DEF("gvar", "configure global variables",
"<gvar> <default> <min> <max>\r\n"
"\treset\r\n", cliGvar),
#endif
#ifdef USE_PROGRAMMING_FRAMEWORK
CLI_COMMAND_DEF("gf", "configure global functions",
"<rule> <enabled> <logic condition> <action> <operand type> <operand value> <flags>\r\n"
"\treset\r\n", cliGlobalFunctions),
#endif
CLI_COMMAND_DEF("set", "change setting", "[<name>=<value>]", cliSet),
CLI_COMMAND_DEF("smix", "servo mixer",

View file

@ -32,7 +32,6 @@ FILE_COMPILE_FOR_SPEED
#include "common/color.h"
#include "common/utils.h"
#include "common/filter.h"
#include "programming/global_functions.h"
#include "drivers/light_led.h"
#include "drivers/serial.h"
@ -450,7 +449,7 @@ void tryArm(void)
if (
!isArmingDisabled() ||
emergencyArmingIsEnabled() ||
GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_ARMING_SAFETY)
LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY)
) {
#else
if (

View file

@ -35,7 +35,6 @@
#include "common/bitarray.h"
#include "common/time.h"
#include "common/utils.h"
#include "programming/global_functions.h"
#include "programming/global_variables.h"
#include "config/parameter_group_ids.h"
@ -551,18 +550,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU32(dst, gvGet(i));
}
break;
#endif
#ifdef USE_PROGRAMMING_FRAMEWORK
case MSP2_INAV_GLOBAL_FUNCTIONS:
for (int i = 0; i < MAX_GLOBAL_FUNCTIONS; i++) {
sbufWriteU8(dst, globalFunctions(i)->enabled);
sbufWriteU8(dst, globalFunctions(i)->conditionId);
sbufWriteU8(dst, globalFunctions(i)->action);
sbufWriteU8(dst, globalFunctions(i)->withValue.type);
sbufWriteU32(dst, globalFunctions(i)->withValue.value);
sbufWriteU8(dst, logicConditions(i)->flags);
}
break;
#endif
case MSP2_COMMON_MOTOR_MIXER:
for (uint8_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
@ -1953,20 +1940,6 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
} else
return MSP_RESULT_ERROR;
break;
#endif
#ifdef USE_PROGRAMMING_FRAMEWORK
case MSP2_INAV_SET_GLOBAL_FUNCTIONS:
sbufReadU8Safe(&tmp_u8, src);
if ((dataSize == 10) && (tmp_u8 < MAX_GLOBAL_FUNCTIONS)) {
globalFunctionsMutable(tmp_u8)->enabled = sbufReadU8(src);
globalFunctionsMutable(tmp_u8)->conditionId = sbufReadU8(src);
globalFunctionsMutable(tmp_u8)->action = sbufReadU8(src);
globalFunctionsMutable(tmp_u8)->withValue.type = sbufReadU8(src);
globalFunctionsMutable(tmp_u8)->withValue.value = sbufReadU32(src);
globalFunctionsMutable(tmp_u8)->flags = sbufReadU8(src);
} else
return MSP_RESULT_ERROR;
break;
#endif
case MSP2_COMMON_SET_MOTOR_MIXER:
sbufReadU8Safe(&tmp_u8, src);

View file

@ -29,7 +29,6 @@ FILE_COMPILE_FOR_SPEED
#include "common/filter.h"
#include "common/maths.h"
#include "common/utils.h"
#include "programming/global_functions.h"
#include "config/feature.h"
#include "config/parameter_group.h"
@ -480,10 +479,10 @@ void FAST_CODE mixTable(const float dT)
// Find min and max throttle based on condition.
#ifdef USE_PROGRAMMING_FRAMEWORK
if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE)) {
if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE)) {
throttleRangeMin = throttleIdleValue;
throttleRangeMax = motorConfig()->maxthrottle;
mixerThrottleCommand = constrain(globalFunctionValues[GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE], throttleRangeMin, throttleRangeMax);
mixerThrottleCommand = constrain(logicConditionValuesByType[LOGIC_CONDITION_OVERRIDE_THROTTLE], throttleRangeMin, throttleRangeMax);
} else
#endif
if (feature(FEATURE_REVERSIBLE_MOTORS)) {

View file

@ -57,10 +57,11 @@ FILE_COMPILE_FOR_SPEED
#include "sensors/acceleration.h"
#include "sensors/compass.h"
#include "sensors/pitotmeter.h"
#include "programming/global_functions.h"
#include "scheduler/scheduler.h"
#include "programming/logic_condition.h"
typedef struct {
float kP; // Proportional gain
float kI; // Integral gain

View file

@ -52,7 +52,6 @@ FILE_COMPILE_FOR_SPEED
#include "common/time.h"
#include "common/typeconversion.h"
#include "common/utils.h"
#include "programming/global_functions.h"
#include "config/feature.h"
#include "config/parameter_group.h"
@ -104,6 +103,8 @@ FILE_COMPILE_FOR_SPEED
#include "sensors/temperature.h"
#include "sensors/esc_sensor.h"
#include "programming/logic_condition.h"
#ifdef USE_HARDWARE_REVISION_DETECTION
#include "hardware_revision.h"
#endif
@ -3243,8 +3244,8 @@ void osdUpdate(timeUs_t currentTimeUs)
activeLayout = 1;
else
#ifdef USE_PROGRAMMING_FRAMEWORK
if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_OSD_LAYOUT))
activeLayout = constrain(globalFunctionValues[GLOBAL_FUNCTION_ACTION_SET_OSD_LAYOUT], 0, OSD_ALTERNATE_LAYOUT_COUNT);
if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT))
activeLayout = constrain(logicConditionValuesByType[LOGIC_CONDITION_SET_OSD_LAYOUT], 0, OSD_ALTERNATE_LAYOUT_COUNT);
else
#endif
activeLayout = 0;

View file

@ -1,189 +0,0 @@
/*
* This file is part of INAV Project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
* You can obtain one at http://mozilla.org/MPL/2.0/.
*
* Alternatively, the contents of this file may be used under the terms
* of the GNU General Public License Version 3, as described below:
*
* This file is free software: you may copy, redistribute and/or modify
* it under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
* Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see http://www.gnu.org/licenses/.
*/
#include "config/config_reset.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "common/utils.h"
#include "common/maths.h"
#include "programming/global_functions.h"
#include "programming/logic_condition.h"
#include "io/vtx.h"
#include "drivers/vtx_common.h"
#ifdef USE_PROGRAMMING_FRAMEWORK
#include "common/axis.h"
PG_REGISTER_ARRAY_WITH_RESET_FN(globalFunction_t, MAX_GLOBAL_FUNCTIONS, globalFunctions, PG_GLOBAL_FUNCTIONS, 0);
EXTENDED_FASTRAM uint64_t globalFunctionsFlags = 0;
EXTENDED_FASTRAM globalFunctionState_t globalFunctionsStates[MAX_GLOBAL_FUNCTIONS];
EXTENDED_FASTRAM int globalFunctionValues[GLOBAL_FUNCTION_ACTION_LAST];
void pgResetFn_globalFunctions(globalFunction_t *instance)
{
for (int i = 0; i < MAX_GLOBAL_FUNCTIONS; i++) {
RESET_CONFIG(globalFunction_t, &instance[i],
.enabled = 0,
.conditionId = -1,
.action = 0,
.withValue = {
.type = LOGIC_CONDITION_OPERAND_TYPE_VALUE,
.value = 0
},
.flags = 0
);
}
}
void globalFunctionsProcess(int8_t functionId) {
//Process only activated functions
if (globalFunctions(functionId)->enabled) {
const int conditionValue = logicConditionGetValue(globalFunctions(functionId)->conditionId);
const int previousValue = globalFunctionsStates[functionId].active;
globalFunctionsStates[functionId].active = (bool) conditionValue;
globalFunctionsStates[functionId].value = logicConditionGetOperandValue(
globalFunctions(functionId)->withValue.type,
globalFunctions(functionId)->withValue.value
);
switch (globalFunctions(functionId)->action) {
case GLOBAL_FUNCTION_ACTION_OVERRIDE_ARMING_SAFETY:
if (conditionValue) {
GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_ARMING_SAFETY);
}
break;
case GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE_SCALE:
if (conditionValue) {
globalFunctionValues[GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE_SCALE] = globalFunctionsStates[functionId].value;
GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE_SCALE);
}
break;
case GLOBAL_FUNCTION_ACTION_SWAP_ROLL_YAW:
if (conditionValue) {
GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_SWAP_ROLL_YAW);
}
break;
case GLOBAL_FUNCTION_ACTION_SET_VTX_POWER_LEVEL:
if (conditionValue && !previousValue) {
vtxDeviceCapability_t vtxDeviceCapability;
if (vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability)) {
vtxSettingsConfigMutable()->power = constrain(globalFunctionsStates[functionId].value, VTX_SETTINGS_MIN_POWER, vtxDeviceCapability.powerCount);
}
}
break;
case GLOBAL_FUNCTION_ACTION_SET_VTX_BAND:
if (conditionValue && !previousValue) {
vtxDeviceCapability_t vtxDeviceCapability;
if (vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability)) {
vtxSettingsConfigMutable()->band = constrain(globalFunctionsStates[functionId].value, VTX_SETTINGS_MIN_BAND, VTX_SETTINGS_MAX_BAND);
}
}
break;
case GLOBAL_FUNCTION_ACTION_SET_VTX_CHANNEL:
if (conditionValue && !previousValue) {
vtxDeviceCapability_t vtxDeviceCapability;
if (vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability)) {
vtxSettingsConfigMutable()->channel = constrain(globalFunctionsStates[functionId].value, VTX_SETTINGS_MIN_CHANNEL, VTX_SETTINGS_MAX_CHANNEL);
}
}
break;
case GLOBAL_FUNCTION_ACTION_INVERT_ROLL:
if (conditionValue) {
GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_ROLL);
}
break;
case GLOBAL_FUNCTION_ACTION_INVERT_PITCH:
if (conditionValue) {
GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_PITCH);
}
break;
case GLOBAL_FUNCTION_ACTION_INVERT_YAW:
if (conditionValue) {
GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_YAW);
}
break;
case GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE:
if (conditionValue) {
globalFunctionValues[GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE] = globalFunctionsStates[functionId].value;
GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE);
}
break;
case GLOBAL_FUNCTION_ACTION_SET_OSD_LAYOUT:
if(conditionValue){
globalFunctionValues[GLOBAL_FUNCTION_ACTION_SET_OSD_LAYOUT] = globalFunctionsStates[functionId].value;
GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_OSD_LAYOUT);
}
break;
}
}
}
void NOINLINE globalFunctionsUpdateTask(timeUs_t currentTimeUs) {
UNUSED(currentTimeUs);
//Disable all flags
globalFunctionsFlags = 0;
for (uint8_t i = 0; i < MAX_GLOBAL_FUNCTIONS; i++) {
globalFunctionsProcess(i);
}
}
float NOINLINE getThrottleScale(float globalThrottleScale) {
if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE_SCALE)) {
return constrainf(globalFunctionValues[GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE_SCALE] / 100.0f, 0.0f, 1.0f);
} else {
return globalThrottleScale;
}
}
int16_t getRcCommandOverride(int16_t command[], uint8_t axis) {
int16_t outputValue = command[axis];
if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_SWAP_ROLL_YAW) && axis == FD_ROLL) {
outputValue = command[FD_YAW];
} else if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_SWAP_ROLL_YAW) && axis == FD_YAW) {
outputValue = command[FD_ROLL];
}
if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_ROLL) && axis == FD_ROLL) {
outputValue *= -1;
}
if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_PITCH) && axis == FD_PITCH) {
outputValue *= -1;
}
if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_YAW) && axis == FD_YAW) {
outputValue *= -1;
}
return outputValue;
}
#endif

View file

@ -1,82 +0,0 @@
/*
* This file is part of INAV Project.
*
* This Source Code Form is subject to the terms of the Mozilla Public
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
* You can obtain one at http://mozilla.org/MPL/2.0/.
*
* Alternatively, the contents of this file may be used under the terms
* of the GNU General Public License Version 3, as described below:
*
* This file is free software: you may copy, redistribute and/or modify
* it under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or (at your
* option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General
* Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see http://www.gnu.org/licenses/.
*/
#pragma once
#include "config/parameter_group.h"
#include "programming/logic_condition.h"
#define MAX_GLOBAL_FUNCTIONS 8
typedef enum {
GLOBAL_FUNCTION_ACTION_OVERRIDE_ARMING_SAFETY = 0, // 0
GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE_SCALE, // 1
GLOBAL_FUNCTION_ACTION_SWAP_ROLL_YAW, // 2
GLOBAL_FUNCTION_ACTION_SET_VTX_POWER_LEVEL, // 3
GLOBAL_FUNCTION_ACTION_INVERT_ROLL, // 4
GLOBAL_FUNCTION_ACTION_INVERT_PITCH, // 5
GLOBAL_FUNCTION_ACTION_INVERT_YAW, // 6
GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE, // 7
GLOBAL_FUNCTION_ACTION_SET_VTX_BAND, // 8
GLOBAL_FUNCTION_ACTION_SET_VTX_CHANNEL, // 9
GLOBAL_FUNCTION_ACTION_SET_OSD_LAYOUT, // 10
GLOBAL_FUNCTION_ACTION_LAST
} globalFunctionActions_e;
typedef enum {
GLOBAL_FUNCTION_FLAG_OVERRIDE_ARMING_SAFETY = (1 << 0),
GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE_SCALE = (1 << 1),
GLOBAL_FUNCTION_FLAG_OVERRIDE_SWAP_ROLL_YAW = (1 << 2),
GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_ROLL = (1 << 3),
GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_PITCH = (1 << 4),
GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_YAW = (1 << 5),
GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE = (1 << 6),
GLOBAL_FUNCTION_FLAG_OVERRIDE_OSD_LAYOUT = (1 << 7),
} globalFunctionFlags_t;
typedef struct globalFunction_s {
uint8_t enabled;
int8_t conditionId;
uint8_t action;
logicOperand_t withValue;
uint8_t flags;
} globalFunction_t;
typedef struct globalFunctionState_s {
uint8_t active;
int value;
uint8_t flags;
} globalFunctionState_t;
extern uint64_t globalFunctionsFlags;
#define GLOBAL_FUNCTION_FLAG_DISABLE(mask) (globalFunctionsFlags &= ~(mask))
#define GLOBAL_FUNCTION_FLAG_ENABLE(mask) (globalFunctionsFlags |= (mask))
#define GLOBAL_FUNCTION_FLAG(mask) (globalFunctionsFlags & (mask))
PG_DECLARE_ARRAY(globalFunction_t, MAX_GLOBAL_FUNCTIONS, globalFunctions);
extern int globalFunctionValues[GLOBAL_FUNCTION_ACTION_LAST];
void globalFunctionsUpdateTask(timeUs_t currentTimeUs);
float getThrottleScale(float globalThrottleScale);
int16_t getRcCommandOverride(int16_t command[], uint8_t axis);

View file

@ -46,8 +46,14 @@
#include "navigation/navigation.h"
#include "navigation/navigation_private.h"
#include "io/vtx.h"
#include "drivers/vtx_common.h"
PG_REGISTER_ARRAY_WITH_RESET_FN(logicCondition_t, MAX_LOGIC_CONDITIONS, logicConditions, PG_LOGIC_CONDITIONS, 1);
EXTENDED_FASTRAM uint64_t logicConditionsGlobalFlags;
EXTENDED_FASTRAM int logicConditionValuesByType[LOGIC_CONDITION_LAST];
void pgResetFn_logicConditions(logicCondition_t *instance)
{
for (int i = 0; i < MAX_LOGIC_CONDITIONS; i++) {
@ -77,6 +83,8 @@ static int logicConditionCompute(
int operandB
) {
int temporaryValue;
vtxDeviceCapability_t vtxDeviceCapability;
switch (operation) {
case LOGIC_CONDITION_TRUE:
@ -181,6 +189,88 @@ static int logicConditionCompute(
return operandA;
}
break;
case LOGIC_CONDITION_OVERRIDE_ARMING_SAFETY:
LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY);
return true;
break;
case LOGIC_CONDITION_OVERRIDE_THROTTLE_SCALE:
logicConditionValuesByType[LOGIC_CONDITION_OVERRIDE_THROTTLE_SCALE] = operandA;
LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE_SCALE);
return true;
break;
case LOGIC_CONDITION_SWAP_ROLL_YAW:
LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_SWAP_ROLL_YAW);
return true;
break;
case LOGIC_CONDITION_SET_VTX_POWER_LEVEL:
if (
logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_POWER_LEVEL] != operandA &&
vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability)
) {
logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_POWER_LEVEL] = constrain(operandA, VTX_SETTINGS_MIN_POWER, vtxDeviceCapability.powerCount);
vtxSettingsConfigMutable()->power = logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_POWER_LEVEL];
return logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_POWER_LEVEL];
} else {
return false;
}
break;
case LOGIC_CONDITION_SET_VTX_BAND:
if (
logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_BAND] != operandA &&
vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability)
) {
logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_BAND] = constrain(operandA, VTX_SETTINGS_MIN_BAND, VTX_SETTINGS_MAX_BAND);
vtxSettingsConfigMutable()->band = logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_BAND];
return logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_BAND];
} else {
return false;
}
break;
case LOGIC_CONDITION_SET_VTX_CHANNEL:
if (
logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_CHANNEL] != operandA &&
vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability)
) {
logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_CHANNEL] = constrain(operandA, VTX_SETTINGS_MIN_CHANNEL, VTX_SETTINGS_MAX_CHANNEL);
vtxSettingsConfigMutable()->channel = logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_CHANNEL];
return logicConditionValuesByType[LOGIC_CONDITION_SET_VTX_CHANNEL];
} else {
return false;
}
break;
case LOGIC_CONDITION_INVERT_ROLL:
LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_ROLL);
return true;
break;
case LOGIC_CONDITION_INVERT_PITCH:
LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_PITCH);
return true;
break;
case LOGIC_CONDITION_INVERT_YAW:
LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_YAW);
return true;
break;
case LOGIC_CONDITION_OVERRIDE_THROTTLE:
logicConditionValuesByType[LOGIC_CONDITION_OVERRIDE_THROTTLE] = operandA;
LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE);
return operandA;
break;
case LOGIC_CONDITION_SET_OSD_LAYOUT:
logicConditionValuesByType[LOGIC_CONDITION_SET_OSD_LAYOUT] = operandA;
LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT);
return operandA;
break;
#ifdef USE_I2C_IO_EXPANDER
case LOGIC_CONDITION_PORT_SET:
ioPortExpanderSet((uint8_t)operandA, (uint8_t)operandB);
@ -459,6 +549,10 @@ int logicConditionGetValue(int8_t conditionId) {
void logicConditionUpdateTask(timeUs_t currentTimeUs) {
UNUSED(currentTimeUs);
//Disable all flags
logicConditionsGlobalFlags = 0;
for (uint8_t i = 0; i < MAX_LOGIC_CONDITIONS; i++) {
logicConditionProcess(i);
}
@ -473,3 +567,33 @@ void logicConditionReset(void) {
logicConditionStates[i].flags = 0;
}
}
float NOINLINE getThrottleScale(float globalThrottleScale) {
if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE_SCALE)) {
return constrainf(logicConditionValuesByType[LOGIC_CONDITION_OVERRIDE_THROTTLE_SCALE] / 100.0f, 0.0f, 1.0f);
} else {
return globalThrottleScale;
}
}
int16_t getRcCommandOverride(int16_t command[], uint8_t axis) {
int16_t outputValue = command[axis];
if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_SWAP_ROLL_YAW) && axis == FD_ROLL) {
outputValue = command[FD_YAW];
} else if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_SWAP_ROLL_YAW) && axis == FD_YAW) {
outputValue = command[FD_ROLL];
}
if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_ROLL) && axis == FD_ROLL) {
outputValue *= -1;
}
if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_PITCH) && axis == FD_PITCH) {
outputValue *= -1;
}
if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_YAW) && axis == FD_YAW) {
outputValue *= -1;
}
return outputValue;
}

View file

@ -29,29 +29,40 @@
#define MAX_LOGIC_CONDITIONS 16
typedef enum {
LOGIC_CONDITION_TRUE = 0,
LOGIC_CONDITION_EQUAL = 1,
LOGIC_CONDITION_GREATER_THAN = 2,
LOGIC_CONDITION_LOWER_THAN = 3,
LOGIC_CONDITION_LOW = 4,
LOGIC_CONDITION_MID = 5,
LOGIC_CONDITION_HIGH = 6,
LOGIC_CONDITION_AND = 7,
LOGIC_CONDITION_OR = 8,
LOGIC_CONDITION_XOR = 9,
LOGIC_CONDITION_NAND = 10,
LOGIC_CONDITION_NOR = 11,
LOGIC_CONDITION_NOT = 12,
LOGIC_CONDITION_STICKY = 13,
LOGIC_CONDITION_ADD = 14,
LOGIC_CONDITION_SUB = 15,
LOGIC_CONDITION_MUL = 16,
LOGIC_CONDITION_DIV = 17,
LOGIC_CONDITION_GVAR_SET = 18,
LOGIC_CONDITION_GVAR_INC = 19,
LOGIC_CONDITION_GVAR_DEC = 20,
LOGIC_CONDITION_PORT_SET = 128,
LOGIC_CONDITION_LAST
LOGIC_CONDITION_TRUE = 0,
LOGIC_CONDITION_EQUAL = 1,
LOGIC_CONDITION_GREATER_THAN = 2,
LOGIC_CONDITION_LOWER_THAN = 3,
LOGIC_CONDITION_LOW = 4,
LOGIC_CONDITION_MID = 5,
LOGIC_CONDITION_HIGH = 6,
LOGIC_CONDITION_AND = 7,
LOGIC_CONDITION_OR = 8,
LOGIC_CONDITION_XOR = 9,
LOGIC_CONDITION_NAND = 10,
LOGIC_CONDITION_NOR = 11,
LOGIC_CONDITION_NOT = 12,
LOGIC_CONDITION_STICKY = 13,
LOGIC_CONDITION_ADD = 14,
LOGIC_CONDITION_SUB = 15,
LOGIC_CONDITION_MUL = 16,
LOGIC_CONDITION_DIV = 17,
LOGIC_CONDITION_GVAR_SET = 18,
LOGIC_CONDITION_GVAR_INC = 19,
LOGIC_CONDITION_GVAR_DEC = 20,
LOGIC_CONDITION_PORT_SET = 21,
LOGIC_CONDITION_OVERRIDE_ARMING_SAFETY = 22,
LOGIC_CONDITION_OVERRIDE_THROTTLE_SCALE = 23,
LOGIC_CONDITION_SWAP_ROLL_YAW = 24,
LOGIC_CONDITION_SET_VTX_POWER_LEVEL = 25,
LOGIC_CONDITION_INVERT_ROLL = 26,
LOGIC_CONDITION_INVERT_PITCH = 27,
LOGIC_CONDITION_INVERT_YAW = 28,
LOGIC_CONDITION_OVERRIDE_THROTTLE = 29,
LOGIC_CONDITION_SET_VTX_BAND = 30,
LOGIC_CONDITION_SET_VTX_CHANNEL = 31,
LOGIC_CONDITION_SET_OSD_LAYOUT = 32,
LOGIC_CONDITION_LAST = 33,
} logicOperation_e;
typedef enum logicOperandType_s {
@ -108,6 +119,17 @@ typedef enum {
LOGIC_CONDITION_OPERAND_FLIGHT_MODE_AIR,
} logicFlightModeOperands_e;
typedef enum {
LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY = (1 << 0),
LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE_SCALE = (1 << 1),
LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_SWAP_ROLL_YAW = (1 << 2),
LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_ROLL = (1 << 3),
LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_PITCH = (1 << 4),
LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_INVERT_YAW = (1 << 5),
LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE = (1 << 6),
LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_OSD_LAYOUT = (1 << 7),
} logicConditionsGlobalFlags_t;
typedef enum {
LOGIC_CONDITION_FLAG_LATCH = 1 << 0,
} logicConditionFlags_e;
@ -133,6 +155,13 @@ typedef struct logicConditionState_s {
uint8_t flags;
} logicConditionState_t;
extern int logicConditionValuesByType[LOGIC_CONDITION_LAST];
extern uint64_t logicConditionsGlobalFlags;
#define LOGIC_CONDITION_GLOBAL_FLAG_DISABLE(mask) (logicConditionsGlobalFlags &= ~(mask))
#define LOGIC_CONDITION_GLOBAL_FLAG_ENABLE(mask) (logicConditionsGlobalFlags |= (mask))
#define LOGIC_CONDITION_GLOBAL_FLAG(mask) (logicConditionsGlobalFlags & (mask))
void logicConditionProcess(uint8_t i);
int logicConditionGetOperandValue(logicOperandType_e type, int operand);
@ -140,3 +169,6 @@ int logicConditionGetOperandValue(logicOperandType_e type, int operand);
int logicConditionGetValue(int8_t conditionId);
void logicConditionUpdateTask(timeUs_t currentTimeUs);
void logicConditionReset(void);
float getThrottleScale(float globalThrottleScale);
int16_t getRcCommandOverride(int16_t command[], uint8_t axis);

View file

@ -27,9 +27,7 @@
FILE_COMPILE_FOR_SIZE
#include "programming/logic_condition.h"
#include "programming/global_functions.h"
void programmingFrameworkUpdateTask(timeUs_t currentTimeUs) {
logicConditionUpdateTask(currentTimeUs);
globalFunctionsUpdateTask(currentTimeUs);
}