1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-14 20:10:15 +03:00

Refactor LC, GF and GVAR to use single scheduler task

This commit is contained in:
Pawel Spychalski (DzikuVx) 2020-07-08 15:18:52 +02:00
parent 5ef91047f0
commit 47cd8f317d
20 changed files with 120 additions and 73 deletions

View file

@ -14,9 +14,6 @@ COMMON_SRC = \
common/filter.c \
common/gps_conversion.c \
common/log.c \
common/logic_condition.c \
common/global_functions.c \
common/global_variables.c \
common/maths.c \
common/memory.c \
common/olc.c \
@ -26,6 +23,10 @@ COMMON_SRC = \
common/time.c \
common/typeconversion.c \
common/uvarint.c \
programming/logic_condition.c \
programming/global_functions.c \
programming/global_variables.c \
programming/programming_task.c \
config/config_eeprom.c \
config/config_streamer.c \
config/feature.c \

View file

@ -43,8 +43,8 @@ extern uint8_t __config_end;
#include "common/memory.h"
#include "common/time.h"
#include "common/typeconversion.h"
#include "common/global_functions.h"
#include "common/global_variables.h"
#include "programming/global_functions.h"
#include "programming/global_variables.h"
#include "config/config_eeprom.h"
#include "config/feature.h"
@ -1682,7 +1682,7 @@ static void printServoMix(uint8_t dumpMask, const servoMixer_t *customServoMixer
&& customServoMixer.inputSource == customServoMixerDefault.inputSource
&& customServoMixer.rate == customServoMixerDefault.rate
&& customServoMixer.speed == customServoMixerDefault.speed
#ifdef USE_LOGIC_CONDITIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
&& customServoMixer.conditionId == customServoMixerDefault.conditionId
#endif
;
@ -1693,7 +1693,7 @@ static void printServoMix(uint8_t dumpMask, const servoMixer_t *customServoMixer
customServoMixerDefault.inputSource,
customServoMixerDefault.rate,
customServoMixerDefault.speed,
#ifdef USE_LOGIC_CONDITIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
customServoMixer.conditionId
#else
0
@ -1706,7 +1706,7 @@ static void printServoMix(uint8_t dumpMask, const servoMixer_t *customServoMixer
customServoMixer.inputSource,
customServoMixer.rate,
customServoMixer.speed,
#ifdef USE_LOGIC_CONDITIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
customServoMixer.conditionId
#else
0
@ -1753,7 +1753,7 @@ static void cliServoMix(char *cmdline)
customServoMixersMutable(i)->inputSource = args[INPUT];
customServoMixersMutable(i)->rate = args[RATE];
customServoMixersMutable(i)->speed = args[SPEED];
#ifdef USE_LOGIC_CONDITIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
customServoMixersMutable(i)->conditionId = args[CONDITION];
#endif
cliServoMix("");
@ -1763,7 +1763,7 @@ static void cliServoMix(char *cmdline)
}
}
#ifdef USE_LOGIC_CONDITIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
static void printLogic(uint8_t dumpMask, const logicCondition_t *logicConditions, const logicCondition_t *defaultLogicConditions)
{
@ -1950,7 +1950,7 @@ static void cliGvar(char *cmdline) {
#endif
#ifdef USE_GLOBAL_FUNCTIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
static void printGlobalFunctions(uint8_t dumpMask, const globalFunction_t *globalFunctions, const globalFunction_t *defaultGlobalFunctions)
{
@ -3321,7 +3321,7 @@ static void printConfig(const char *cmdline, bool doDiff)
cliPrintHashLine("servo");
printServo(dumpMask, servoParams_CopyArray, servoParams(0));
#ifdef USE_LOGIC_CONDITIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
cliPrintHashLine("logic");
printLogic(dumpMask, logicConditions_CopyArray, logicConditions(0));
@ -3329,7 +3329,7 @@ static void printConfig(const char *cmdline, bool doDiff)
printGvar(dumpMask, globalVariableConfigs_CopyArray, globalVariableConfigs(0));
#endif
#ifdef USE_GLOBAL_FUNCTIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
cliPrintHashLine("gf");
printGlobalFunctions(dumpMask, globalFunctions_CopyArray, globalFunctions(0));
#endif
@ -3576,7 +3576,7 @@ const clicmd_t cmdTable[] = {
CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data to port", "<id> [baud] [mode] : passthrough to serial", cliSerialPassthrough),
#endif
CLI_COMMAND_DEF("servo", "configure servos", NULL, cliServo),
#ifdef USE_LOGIC_CONDITIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
CLI_COMMAND_DEF("logic", "configure logic conditions",
"<rule> <enabled> <activatorId> <operation> <operand A type> <operand A value> <operand B type> <operand B value> <flags>\r\n"
"\treset\r\n", cliLogic),
@ -3585,7 +3585,7 @@ const clicmd_t cmdTable[] = {
"<gvar> <default> <min> <max>\r\n"
"\treset\r\n", cliGvar),
#endif
#ifdef USE_GLOBAL_FUNCTIONS
#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),

View file

@ -32,7 +32,7 @@ FILE_COMPILE_FOR_SPEED
#include "common/color.h"
#include "common/utils.h"
#include "common/filter.h"
#include "common/global_functions.h"
#include "programming/global_functions.h"
#include "drivers/light_led.h"
#include "drivers/serial.h"
@ -446,7 +446,7 @@ void releaseSharedTelemetryPorts(void) {
void tryArm(void)
{
updateArmingStatus();
#ifdef USE_GLOBAL_FUNCTIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
if (
!isArmingDisabled() ||
emergencyArmingIsEnabled() ||

View file

@ -35,7 +35,7 @@
#include "common/maths.h"
#include "common/memory.h"
#include "common/printf.h"
#include "common/global_variables.h"
#include "programming/global_variables.h"
#include "config/config_eeprom.h"
#include "config/feature.h"
@ -286,7 +286,7 @@ void init(void)
logInit();
#endif
#ifdef USE_LOGIC_CONDITIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
gvInit();
#endif

View file

@ -35,8 +35,8 @@
#include "common/bitarray.h"
#include "common/time.h"
#include "common/utils.h"
#include "common/global_functions.h"
#include "common/global_variables.h"
#include "programming/global_functions.h"
#include "programming/global_variables.h"
#include "config/parameter_group_ids.h"
@ -520,14 +520,14 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU8(dst, customServoMixers(i)->inputSource);
sbufWriteU16(dst, customServoMixers(i)->rate);
sbufWriteU8(dst, customServoMixers(i)->speed);
#ifdef USE_LOGIC_CONDITIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
sbufWriteU8(dst, customServoMixers(i)->conditionId);
#else
sbufWriteU8(dst, -1);
#endif
}
break;
#ifdef USE_LOGIC_CONDITIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
case MSP2_INAV_LOGIC_CONDITIONS:
for (int i = 0; i < MAX_LOGIC_CONDITIONS; i++) {
sbufWriteU8(dst, logicConditions(i)->enabled);
@ -551,7 +551,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
}
break;
#endif
#ifdef USE_GLOBAL_FUNCTIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
case MSP2_INAV_GLOBAL_FUNCTIONS:
for (int i = 0; i < MAX_GLOBAL_FUNCTIONS; i++) {
sbufWriteU8(dst, globalFunctions(i)->enabled);
@ -1928,7 +1928,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
customServoMixersMutable(tmp_u8)->inputSource = sbufReadU8(src);
customServoMixersMutable(tmp_u8)->rate = sbufReadU16(src);
customServoMixersMutable(tmp_u8)->speed = sbufReadU8(src);
#ifdef USE_LOGIC_CONDITIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
customServoMixersMutable(tmp_u8)->conditionId = sbufReadU8(src);
#else
sbufReadU8(src);
@ -1937,7 +1937,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
} else
return MSP_RESULT_ERROR;
break;
#ifdef USE_LOGIC_CONDITIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
case MSP2_INAV_SET_LOGIC_CONDITIONS:
sbufReadU8Safe(&tmp_u8, src);
if ((dataSize == 15) && (tmp_u8 < MAX_LOGIC_CONDITIONS)) {
@ -1953,7 +1953,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
return MSP_RESULT_ERROR;
break;
#endif
#ifdef USE_GLOBAL_FUNCTIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
case MSP2_INAV_SET_GLOBAL_FUNCTIONS:
sbufReadU8Safe(&tmp_u8, src);
if ((dataSize == 10) && (tmp_u8 < MAX_GLOBAL_FUNCTIONS)) {

View file

@ -26,8 +26,7 @@
#include "common/axis.h"
#include "common/color.h"
#include "common/utils.h"
#include "common/logic_condition.h"
#include "common/global_functions.h"
#include "programming/programming_task.h"
#include "drivers/accgyro/accgyro.h"
#include "drivers/compass/compass.h"
@ -355,11 +354,8 @@ void fcTasksInit(void)
#ifdef USE_RCDEVICE
setTaskEnabled(TASK_RCDEVICE, rcdeviceIsEnabled());
#endif
#ifdef USE_LOGIC_CONDITIONS
setTaskEnabled(TASK_LOGIC_CONDITIONS, true);
#endif
#ifdef USE_GLOBAL_FUNCTIONS
setTaskEnabled(TASK_GLOBAL_FUNCTIONS, true);
#ifdef USE_PROGRAMMING_FRAMEWORK
setTaskEnabled(TASK_PROGRAMMING_FRAMEWORK, true);
#endif
#ifdef USE_IRLOCK
setTaskEnabled(TASK_IRLOCK, irlockHasBeenDetected());
@ -578,18 +574,10 @@ cfTask_t cfTasks[TASK_COUNT] = {
.staticPriority = TASK_PRIORITY_IDLE,
},
#endif
#ifdef USE_LOGIC_CONDITIONS
[TASK_LOGIC_CONDITIONS] = {
.taskName = "LOGIC",
.taskFunc = logicConditionUpdateTask,
.desiredPeriod = TASK_PERIOD_HZ(10), // 10Hz @100msec
.staticPriority = TASK_PRIORITY_IDLE,
},
#endif
#ifdef USE_GLOBAL_FUNCTIONS
[TASK_GLOBAL_FUNCTIONS] = {
.taskName = "G_FNK",
.taskFunc = globalFunctionsUpdateTask,
#ifdef USE_PROGRAMMING_FRAMEWORK
[TASK_PROGRAMMING_FRAMEWORK] = {
.taskName = "PROGRAMMING",
.taskFunc = programmingFrameworkUpdateTask,
.desiredPeriod = TASK_PERIOD_HZ(10), // 10Hz @100msec
.staticPriority = TASK_PRIORITY_IDLE,
},

View file

@ -29,7 +29,7 @@ FILE_COMPILE_FOR_SPEED
#include "common/filter.h"
#include "common/maths.h"
#include "common/utils.h"
#include "common/global_functions.h"
#include "programming/global_functions.h"
#include "config/feature.h"
#include "config/parameter_group.h"
@ -479,7 +479,7 @@ void FAST_CODE mixTable(const float dT)
int16_t throttleMin, throttleMax;
// Find min and max throttle based on condition.
#ifdef USE_GLOBAL_FUNCTIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE)) {
throttleRangeMin = throttleIdleValue;
throttleRangeMax = motorConfig()->maxthrottle;
@ -514,7 +514,7 @@ void FAST_CODE mixTable(const float dT)
throttleRangeMax = motorConfig()->maxthrottle;
// Throttle scaling to limit max throttle when battery is full
#ifdef USE_GLOBAL_FUNCTIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
mixerThrottleCommand = ((mixerThrottleCommand - throttleRangeMin) * getThrottleScale(motorConfig()->throttleScale)) + throttleRangeMin;
#else
mixerThrottleCommand = ((mixerThrottleCommand - throttleRangeMin) * motorConfig()->throttleScale) + throttleRangeMin;

View file

@ -57,7 +57,7 @@ FILE_COMPILE_FOR_SPEED
#include "sensors/acceleration.h"
#include "sensors/compass.h"
#include "sensors/pitotmeter.h"
#include "common/global_functions.h"
#include "programming/global_functions.h"
typedef struct {
float kP; // Proportional gain
@ -958,7 +958,7 @@ void FAST_CODE pidController(float dT)
if (axis == FD_YAW && headingHoldState == HEADING_HOLD_ENABLED) {
rateTarget = pidHeadingHold(dT);
} else {
#ifdef USE_GLOBAL_FUNCTIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
rateTarget = pidRcCommandToRate(getRcCommandOverride(rcCommand, axis), currentControlRateProfile->stabilized.rates[axis]);
#else
rateTarget = pidRcCommandToRate(rcCommand[axis], currentControlRateProfile->stabilized.rates[axis]);

View file

@ -28,7 +28,7 @@
#include "common/axis.h"
#include "common/filter.h"
#include "common/maths.h"
#include "common/global_variables.h"
#include "programming/global_variables.h"
#include "config/config_reset.h"
#include "config/feature.h"
@ -75,7 +75,7 @@ void pgResetFn_customServoMixers(servoMixer_t *instance)
.inputSource = 0,
.rate = 0,
.speed = 0
#ifdef USE_LOGIC_CONDITIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
,.conditionId = -1
#endif
);
@ -266,7 +266,7 @@ void servoMixer(float dT)
input[INPUT_FEATURE_FLAPS] = FLIGHT_MODE(FLAPERON) ? servoConfig()->flaperon_throw_offset : 0;
input[INPUT_MAX] = 500;
#ifdef USE_LOGIC_CONDITIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
input[INPUT_GVAR_0] = constrain(gvGet(0), -1000, 1000);
input[INPUT_GVAR_1] = constrain(gvGet(1), -1000, 1000);
input[INPUT_GVAR_2] = constrain(gvGet(2), -1000, 1000);
@ -318,7 +318,7 @@ void servoMixer(float dT)
/*
* Check if conditions for a rule are met, not all conditions apply all the time
*/
#ifdef USE_LOGIC_CONDITIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
if (!logicConditionGetValue(currentServoMixer[i].conditionId)) {
continue;
}

View file

@ -18,7 +18,7 @@
#pragma once
#include "config/parameter_group.h"
#include "common/logic_condition.h"
#include "programming/logic_condition.h"
#define MAX_SUPPORTED_SERVOS 16
@ -105,7 +105,7 @@ typedef struct servoMixer_s {
uint8_t inputSource; // input channel for this rule
int16_t rate; // range [-1000;+1000] ; can be used to adjust a rate 0-1000% and a direction
uint8_t speed; // reduces the speed of the rule, 0=unlimited speed
#ifdef USE_LOGIC_CONDITIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
int8_t conditionId;
#endif
} servoMixer_t;

View file

@ -28,13 +28,13 @@
#include "common/utils.h"
#include "common/maths.h"
#include "common/global_functions.h"
#include "common/logic_condition.h"
#include "programming/global_functions.h"
#include "programming/logic_condition.h"
#include "io/vtx.h"
#include "drivers/vtx_common.h"
#ifdef USE_GLOBAL_FUNCTIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
#include "common/axis.h"

View file

@ -24,7 +24,7 @@
#pragma once
#include "config/parameter_group.h"
#include "common/logic_condition.h"
#include "programming/logic_condition.h"
#define MAX_GLOBAL_FUNCTIONS 8

View file

@ -26,13 +26,13 @@
FILE_COMPILE_FOR_SIZE
#ifdef USE_LOGIC_CONDITIONS
#ifdef USE_PROGRAMMING_FRAMEWORK
#include <stdint.h>
#include "config/config_reset.h"
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "common/global_variables.h"
#include "programming/global_variables.h"
#include "common/maths.h"
#include "build/build_config.h"

View file

@ -28,11 +28,11 @@
#include "config/parameter_group.h"
#include "config/parameter_group_ids.h"
#include "common/logic_condition.h"
#include "common/global_variables.h"
#include "programming/logic_condition.h"
#include "programming/global_variables.h"
#include "common/utils.h"
#include "rx/rx.h"
#include "maths.h"
#include "common/maths.h"
#include "fc/fc_core.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"

View file

@ -0,0 +1,35 @@
/*
* 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 "platform.h"
FILE_COMPILE_FOR_SIZE
#include "programming/logic_condition.h"
#include "programming/global_functions.h"
void programmingFrameworkUpdateTask(timeUs_t currentTimeUs) {
logicConditionUpdateTask(currentTimeUs);
globalFunctionsUpdateTask(currentTimeUs);
}

View file

@ -0,0 +1,27 @@
/*
* 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
void programmingFrameworkUpdateTask(timeUs_t currentTimeUs);

View file

@ -110,11 +110,8 @@ typedef enum {
#ifdef USE_VTX_CONTROL
TASK_VTXCTRL,
#endif
#ifdef USE_LOGIC_CONDITIONS
TASK_LOGIC_CONDITIONS,
#endif
#ifdef USE_GLOBAL_FUNCTIONS
TASK_GLOBAL_FUNCTIONS,
#ifdef USE_PROGRAMMING_FRAMEWORK
TASK_PROGRAMMING_FRAMEWORK,
#endif
#ifdef USE_RPM_FILTER
TASK_RPM_FILTER,

View file

@ -162,8 +162,7 @@
#define USE_VTX_FFPV
#ifndef STM32F3 //F3 series does not have enoug RAM to support logic conditions
#define USE_LOGIC_CONDITIONS
#define USE_GLOBAL_FUNCTIONS
#define USE_PROGRAMMING_FRAMEWORK
#define USE_CLI_BATCH
#endif