mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 04:15:44 +03:00
Removed 'slots' from the adjustment range configuration. (#8369)
Removed 'slots' from the adjustment range configuration.
This commit is contained in:
commit
d486c47bc1
7 changed files with 252 additions and 351 deletions
|
@ -1368,7 +1368,7 @@ static void cliSerialPassthrough(char *cmdline)
|
|||
|
||||
static void printAdjustmentRange(dumpFlags_t dumpMask, const adjustmentRange_t *adjustmentRanges, const adjustmentRange_t *defaultAdjustmentRanges, const char *headingStr)
|
||||
{
|
||||
const char *format = "adjrange %u %u %u %u %u %u %u %u %u";
|
||||
const char *format = "adjrange %u 0 %u %u %u %u %u %u %u";
|
||||
// print out adjustment ranges channel settings
|
||||
headingStr = cliPrintSectionHeading(dumpMask, false, headingStr);
|
||||
for (uint32_t i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
|
||||
|
@ -1380,7 +1380,6 @@ static void printAdjustmentRange(dumpFlags_t dumpMask, const adjustmentRange_t *
|
|||
headingStr = cliPrintSectionHeading(dumpMask, !equalsDefault, headingStr);
|
||||
cliDefaultPrintLinef(dumpMask, equalsDefault, format,
|
||||
i,
|
||||
arDefault->adjustmentIndex,
|
||||
arDefault->auxChannelIndex,
|
||||
MODE_STEP_TO_CHANNEL_VALUE(arDefault->range.startStep),
|
||||
MODE_STEP_TO_CHANNEL_VALUE(arDefault->range.endStep),
|
||||
|
@ -1392,7 +1391,6 @@ static void printAdjustmentRange(dumpFlags_t dumpMask, const adjustmentRange_t *
|
|||
}
|
||||
cliDumpPrintLinef(dumpMask, equalsDefault, format,
|
||||
i,
|
||||
ar->adjustmentIndex,
|
||||
ar->auxChannelIndex,
|
||||
MODE_STEP_TO_CHANNEL_VALUE(ar->range.startStep),
|
||||
MODE_STEP_TO_CHANNEL_VALUE(ar->range.endStep),
|
||||
|
@ -1406,7 +1404,7 @@ static void printAdjustmentRange(dumpFlags_t dumpMask, const adjustmentRange_t *
|
|||
|
||||
static void cliAdjustmentRange(char *cmdline)
|
||||
{
|
||||
const char *format = "adjrange %u %u %u %u %u %u %u %u %u";
|
||||
const char *format = "adjrange %u 0 %u %u %u %u %u %u %u";
|
||||
int i, val = 0;
|
||||
const char *ptr;
|
||||
|
||||
|
@ -1422,10 +1420,9 @@ static void cliAdjustmentRange(char *cmdline)
|
|||
ptr = nextArg(ptr);
|
||||
if (ptr) {
|
||||
val = atoi(ptr);
|
||||
if (val >= 0 && val < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) {
|
||||
ar->adjustmentIndex = val;
|
||||
validArgumentCount++;
|
||||
}
|
||||
// Was: slot
|
||||
// Keeping the parameter to retain backwards compatibility for the command format.
|
||||
validArgumentCount++;
|
||||
}
|
||||
ptr = nextArg(ptr);
|
||||
if (ptr) {
|
||||
|
@ -1482,7 +1479,6 @@ static void cliAdjustmentRange(char *cmdline)
|
|||
|
||||
cliDumpPrintLinef(0, false, format,
|
||||
i,
|
||||
ar->adjustmentIndex,
|
||||
ar->auxChannelIndex,
|
||||
MODE_STEP_TO_CHANNEL_VALUE(ar->range.startStep),
|
||||
MODE_STEP_TO_CHANNEL_VALUE(ar->range.endStep),
|
||||
|
@ -5806,7 +5802,7 @@ static void cliHelp(char *cmdline);
|
|||
|
||||
// should be sorted a..z for bsearch()
|
||||
const clicmd_t cmdTable[] = {
|
||||
CLI_COMMAND_DEF("adjrange", "configure adjustment ranges", NULL, cliAdjustmentRange),
|
||||
CLI_COMMAND_DEF("adjrange", "configure adjustment ranges", "<index> <unused> <range channel> <start> <end> <function> <select channel> [<center> <scale>]", cliAdjustmentRange),
|
||||
CLI_COMMAND_DEF("aux", "configure modes", "<index> <mode> <aux> <start> <end> <logic>", cliAux),
|
||||
#ifdef USE_CLI_BATCH
|
||||
CLI_COMMAND_DEF("batch", "start or end a batch of commands", "start | end", cliBatch),
|
||||
|
|
|
@ -142,7 +142,7 @@ static void activateConfig(void)
|
|||
|
||||
initRcProcessing();
|
||||
|
||||
resetAdjustmentStates();
|
||||
activeAdjustmentRangeReset();
|
||||
|
||||
pidInit(currentPidProfile);
|
||||
|
||||
|
|
|
@ -63,7 +63,7 @@
|
|||
|
||||
#define ADJUSTMENT_RANGE_COUNT_INVALID -1
|
||||
|
||||
PG_REGISTER_ARRAY(adjustmentRange_t, MAX_ADJUSTMENT_RANGE_COUNT, adjustmentRanges, PG_ADJUSTMENT_RANGE_CONFIG, 1);
|
||||
PG_REGISTER_ARRAY(adjustmentRange_t, MAX_ADJUSTMENT_RANGE_COUNT, adjustmentRanges, PG_ADJUSTMENT_RANGE_CONFIG, 2);
|
||||
|
||||
uint8_t pidAudioPositionToModeMap[7] = {
|
||||
// on a pot with a center detent, it's easy to have center area for off/default, then three positions to the left and three to the right.
|
||||
|
@ -80,10 +80,11 @@ uint8_t pidAudioPositionToModeMap[7] = {
|
|||
// Note: Last 3 positions are currently pending implementations and use PID_AUDIO_OFF for now.
|
||||
};
|
||||
|
||||
static int activeAdjustmentCount = ADJUSTMENT_RANGE_COUNT_INVALID;
|
||||
static uint8_t activeAdjustmentArray[MAX_ADJUSTMENT_RANGE_COUNT];
|
||||
static int activeAbsoluteAdjustmentCount;
|
||||
static uint8_t activeAbsoluteAdjustmentArray[MAX_ADJUSTMENT_RANGE_COUNT];
|
||||
STATIC_UNIT_TESTED int stepwiseAdjustmentCount = ADJUSTMENT_RANGE_COUNT_INVALID;
|
||||
STATIC_UNIT_TESTED timedAdjustmentState_t stepwiseAdjustments[MAX_ADJUSTMENT_RANGE_COUNT];
|
||||
|
||||
STATIC_UNIT_TESTED int continuosAdjustmentCount;
|
||||
STATIC_UNIT_TESTED continuosAdjustmentState_t continuosAdjustments[MAX_ADJUSTMENT_RANGE_COUNT];
|
||||
|
||||
static void blackboxLogInflightAdjustmentEvent(adjustmentFunction_e adjustmentFunction, int32_t newValue)
|
||||
{
|
||||
|
@ -101,13 +102,6 @@ static void blackboxLogInflightAdjustmentEvent(adjustmentFunction_e adjustmentFu
|
|||
#endif
|
||||
}
|
||||
|
||||
STATIC_UNIT_TESTED uint8_t adjustmentStateMask = 0;
|
||||
|
||||
#define MARK_ADJUSTMENT_FUNCTION_AS_BUSY(adjustmentIndex) adjustmentStateMask |= (1 << adjustmentIndex)
|
||||
#define MARK_ADJUSTMENT_FUNCTION_AS_READY(adjustmentIndex) adjustmentStateMask &= ~(1 << adjustmentIndex)
|
||||
|
||||
#define IS_ADJUSTMENT_FUNCTION_BUSY(adjustmentIndex) (adjustmentStateMask & (1 << adjustmentIndex))
|
||||
|
||||
// sync with adjustmentFunction_e
|
||||
static const adjustmentConfig_t defaultAdjustmentConfigs[ADJUSTMENT_FUNCTION_COUNT - 1] = {
|
||||
{
|
||||
|
@ -274,25 +268,6 @@ static int adjustmentRangeNameIndex = 0;
|
|||
static int adjustmentRangeValue = -1;
|
||||
#endif
|
||||
|
||||
#define ADJUSTMENT_FUNCTION_CONFIG_INDEX_OFFSET 1
|
||||
|
||||
STATIC_UNIT_TESTED adjustmentState_t adjustmentStates[MAX_SIMULTANEOUS_ADJUSTMENT_COUNT];
|
||||
|
||||
STATIC_UNIT_TESTED void configureAdjustment(uint8_t index, uint8_t auxSwitchChannelIndex, const adjustmentConfig_t *adjustmentConfig)
|
||||
{
|
||||
adjustmentState_t *adjustmentState = &adjustmentStates[index];
|
||||
|
||||
if (adjustmentState->config == adjustmentConfig) {
|
||||
// already configured
|
||||
return;
|
||||
}
|
||||
adjustmentState->auxChannelIndex = auxSwitchChannelIndex;
|
||||
adjustmentState->config = adjustmentConfig;
|
||||
adjustmentState->timeoutAt = 0;
|
||||
|
||||
MARK_ADJUSTMENT_FUNCTION_AS_READY(index);
|
||||
}
|
||||
|
||||
static int applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t adjustmentFunction, int delta)
|
||||
{
|
||||
|
||||
|
@ -682,154 +657,184 @@ static uint8_t applySelectAdjustment(adjustmentFunction_e adjustmentFunction, ui
|
|||
return position;
|
||||
}
|
||||
|
||||
#define ADJUSTMENT_FUNCTION_CONFIG_INDEX_OFFSET 1
|
||||
|
||||
static void calcActiveAdjustmentRanges(void)
|
||||
{
|
||||
adjustmentRange_t defaultAdjustmentRange;
|
||||
memset(&defaultAdjustmentRange, 0, sizeof(defaultAdjustmentRange));
|
||||
|
||||
activeAdjustmentCount = 0;
|
||||
activeAbsoluteAdjustmentCount = 0;
|
||||
stepwiseAdjustmentCount = 0;
|
||||
continuosAdjustmentCount = 0;
|
||||
for (int i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
|
||||
const adjustmentRange_t * const adjustmentRange = adjustmentRanges(i);
|
||||
if (memcmp(adjustmentRange, &defaultAdjustmentRange, sizeof(defaultAdjustmentRange)) != 0) {
|
||||
if (adjustmentRange->adjustmentCenter == 0) {
|
||||
activeAdjustmentArray[activeAdjustmentCount++] = i;
|
||||
const adjustmentConfig_t *adjustmentConfig = &defaultAdjustmentConfigs[adjustmentRange->adjustmentConfig - ADJUSTMENT_FUNCTION_CONFIG_INDEX_OFFSET];
|
||||
if (adjustmentRange->adjustmentCenter == 0 && adjustmentConfig->mode != ADJUSTMENT_MODE_SELECT) {
|
||||
timedAdjustmentState_t *adjustmentState = &stepwiseAdjustments[stepwiseAdjustmentCount++];
|
||||
adjustmentState->adjustmentRangeIndex = i;
|
||||
adjustmentState->timeoutAt = 0;
|
||||
adjustmentState->ready = true;
|
||||
} else {
|
||||
activeAbsoluteAdjustmentArray[activeAbsoluteAdjustmentCount++] = i;
|
||||
continuosAdjustmentState_t *adjustmentState = &continuosAdjustments[continuosAdjustmentCount++];
|
||||
adjustmentState->adjustmentRangeIndex = i;
|
||||
adjustmentState->lastRcData = 0;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void updateAdjustmentStates(void)
|
||||
#define VALUE_DISPLAY_LATENCY_MS 2000
|
||||
|
||||
#if defined(USE_OSD) && defined(USE_OSD_ADJUSTMENTS)
|
||||
static void updateOsdAdjustmentData(int newValue, adjustmentFunction_e adjustmentFunction)
|
||||
{
|
||||
for (int index = 0; index < activeAdjustmentCount; index++) {
|
||||
const adjustmentRange_t * const adjustmentRange = adjustmentRanges(activeAdjustmentArray[index]);
|
||||
// Only use slots if center value has not been specified, otherwise apply values directly (scaled) from aux channel
|
||||
if (isRangeActive(adjustmentRange->auxChannelIndex, &adjustmentRange->range) &&
|
||||
(adjustmentRange->adjustmentCenter == 0)) {
|
||||
const adjustmentConfig_t *adjustmentConfig = &defaultAdjustmentConfigs[adjustmentRange->adjustmentConfig - ADJUSTMENT_FUNCTION_CONFIG_INDEX_OFFSET];
|
||||
configureAdjustment(adjustmentRange->adjustmentIndex, adjustmentRange->auxSwitchChannelIndex, adjustmentConfig);
|
||||
}
|
||||
static timeMs_t lastValueChangeMs;
|
||||
|
||||
timeMs_t currentTimeMs = millis();
|
||||
if (newValue != -1
|
||||
&& adjustmentFunction != ADJUSTMENT_RATE_PROFILE // Rate profile already has an OSD element
|
||||
#ifdef USE_OSD_PROFILES
|
||||
&& adjustmentFunction != ADJUSTMENT_OSD_PROFILE
|
||||
#endif
|
||||
) {
|
||||
adjustmentRangeNameIndex = adjustmentFunction;
|
||||
adjustmentRangeValue = newValue;
|
||||
|
||||
lastValueChangeMs = currentTimeMs;
|
||||
}
|
||||
|
||||
if (cmp32(currentTimeMs, lastValueChangeMs + VALUE_DISPLAY_LATENCY_MS) >= 0) {
|
||||
adjustmentRangeNameIndex = 0;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#define RESET_FREQUENCY_2HZ (1000 / 2)
|
||||
|
||||
void processRcAdjustments(controlRateConfig_t *controlRateConfig)
|
||||
static void processStepwiseAdjustments(controlRateConfig_t *controlRateConfig, const bool canUseRxData)
|
||||
{
|
||||
const uint32_t now = millis();
|
||||
const timeMs_t now = millis();
|
||||
|
||||
int newValue = -1;
|
||||
for (int index = 0; index < stepwiseAdjustmentCount; index++) {
|
||||
timedAdjustmentState_t *adjustmentState = &stepwiseAdjustments[index];
|
||||
const adjustmentRange_t *const adjustmentRange = adjustmentRanges(adjustmentState->adjustmentRangeIndex);
|
||||
const adjustmentConfig_t *adjustmentConfig = &defaultAdjustmentConfigs[adjustmentRange->adjustmentConfig - ADJUSTMENT_FUNCTION_CONFIG_INDEX_OFFSET];
|
||||
const adjustmentFunction_e adjustmentFunction = adjustmentConfig->adjustmentFunction;
|
||||
|
||||
const bool canUseRxData = rxIsReceivingSignal();
|
||||
if (!isRangeActive(adjustmentRange->auxChannelIndex, &adjustmentRange->range) ||
|
||||
adjustmentFunction == ADJUSTMENT_NONE) {
|
||||
adjustmentState->timeoutAt = 0;
|
||||
|
||||
// Recalculate the new active adjustments if required
|
||||
if (activeAdjustmentCount == ADJUSTMENT_RANGE_COUNT_INVALID) {
|
||||
calcActiveAdjustmentRanges();
|
||||
}
|
||||
|
||||
updateAdjustmentStates();
|
||||
|
||||
// Process Increment/Decrement adjustments
|
||||
for (int adjustmentIndex = 0; adjustmentIndex < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT; adjustmentIndex++) {
|
||||
adjustmentState_t *adjustmentState = &adjustmentStates[adjustmentIndex];
|
||||
|
||||
if (!adjustmentState->config) {
|
||||
continue;
|
||||
}
|
||||
const adjustmentFunction_e adjustmentFunction = adjustmentState->config->adjustmentFunction;
|
||||
if (adjustmentFunction == ADJUSTMENT_NONE) {
|
||||
continue;
|
||||
}
|
||||
|
||||
if (cmp32(now, adjustmentState->timeoutAt) >= 0) {
|
||||
adjustmentState->timeoutAt = now + RESET_FREQUENCY_2HZ;
|
||||
MARK_ADJUSTMENT_FUNCTION_AS_READY(adjustmentIndex);
|
||||
|
||||
#if defined(USE_OSD) && defined(USE_OSD_ADJUSTMENTS)
|
||||
adjustmentRangeValue = -1;
|
||||
#endif
|
||||
adjustmentState->ready = true;
|
||||
}
|
||||
|
||||
if (!canUseRxData) {
|
||||
continue;
|
||||
}
|
||||
|
||||
const uint8_t channelIndex = NON_AUX_CHANNEL_COUNT + adjustmentState->auxChannelIndex;
|
||||
const uint8_t channelIndex = NON_AUX_CHANNEL_COUNT + adjustmentRange->auxSwitchChannelIndex;
|
||||
|
||||
if (adjustmentState->config->mode == ADJUSTMENT_MODE_STEP) {
|
||||
if (adjustmentConfig->mode == ADJUSTMENT_MODE_STEP) {
|
||||
int delta;
|
||||
if (rcData[channelIndex] > rxConfig()->midrc + 200) {
|
||||
delta = adjustmentState->config->data.step;
|
||||
delta = adjustmentConfig->data.step;
|
||||
} else if (rcData[channelIndex] < rxConfig()->midrc - 200) {
|
||||
delta = -adjustmentState->config->data.step;
|
||||
delta = -adjustmentConfig->data.step;
|
||||
} else {
|
||||
// returning the switch to the middle immediately resets the ready state
|
||||
MARK_ADJUSTMENT_FUNCTION_AS_READY(adjustmentIndex);
|
||||
adjustmentState->ready = true;
|
||||
adjustmentState->timeoutAt = now + RESET_FREQUENCY_2HZ;
|
||||
continue;
|
||||
}
|
||||
if (IS_ADJUSTMENT_FUNCTION_BUSY(adjustmentIndex)) {
|
||||
if (!adjustmentState->ready) {
|
||||
continue;
|
||||
}
|
||||
|
||||
newValue = applyStepAdjustment(controlRateConfig, adjustmentFunction, delta);
|
||||
int newValue = applyStepAdjustment(controlRateConfig, adjustmentFunction, delta);
|
||||
pidInitConfig(currentPidProfile);
|
||||
} else if (adjustmentState->config->mode == ADJUSTMENT_MODE_SELECT) {
|
||||
int switchPositions = adjustmentState->config->data.switchPositions;
|
||||
|
||||
adjustmentState->ready = false;
|
||||
|
||||
#if defined(USE_OSD) && defined(USE_OSD_ADJUSTMENTS)
|
||||
updateOsdAdjustmentData(newValue, adjustmentConfig->adjustmentFunction);
|
||||
#else
|
||||
UNUSED(newValue);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
static void processContinuosAdjustments(controlRateConfig_t *controlRateConfig)
|
||||
{
|
||||
for (int i = 0; i < continuosAdjustmentCount; i++) {
|
||||
continuosAdjustmentState_t *adjustmentState = &continuosAdjustments[i];
|
||||
const adjustmentRange_t * const adjustmentRange = adjustmentRanges(adjustmentState->adjustmentRangeIndex);
|
||||
const uint8_t channelIndex = NON_AUX_CHANNEL_COUNT + adjustmentRange->auxSwitchChannelIndex;
|
||||
const adjustmentConfig_t *adjustmentConfig = &defaultAdjustmentConfigs[adjustmentRange->adjustmentConfig - ADJUSTMENT_FUNCTION_CONFIG_INDEX_OFFSET];
|
||||
const adjustmentFunction_e adjustmentFunction = adjustmentConfig->adjustmentFunction;
|
||||
|
||||
if (!isRangeActive(adjustmentRange->auxChannelIndex, &adjustmentRange->range) ||
|
||||
adjustmentFunction == ADJUSTMENT_NONE ||
|
||||
rcData[channelIndex] == adjustmentState->lastRcData) {
|
||||
continue;
|
||||
}
|
||||
|
||||
adjustmentState->lastRcData = rcData[channelIndex];
|
||||
|
||||
int newValue = -1;
|
||||
|
||||
if (adjustmentConfig->mode == ADJUSTMENT_MODE_SELECT) {
|
||||
int switchPositions = adjustmentConfig->data.switchPositions;
|
||||
if (adjustmentFunction == ADJUSTMENT_RATE_PROFILE && systemConfig()->rateProfile6PosSwitch) {
|
||||
switchPositions = 6;
|
||||
}
|
||||
const uint16_t rangeWidth = (2100 - 900) / switchPositions;
|
||||
const uint8_t position = (constrain(rcData[channelIndex], 900, 2100 - 1) - 900) / rangeWidth;
|
||||
newValue = applySelectAdjustment(adjustmentFunction, position);
|
||||
} else {
|
||||
// If setting is defined for step adjustment and center value has been specified, apply values directly (scaled) from aux channel
|
||||
if (adjustmentRange->adjustmentCenter &&
|
||||
(adjustmentConfig->mode == ADJUSTMENT_MODE_STEP)) {
|
||||
int value = (((rcData[channelIndex] - PWM_RANGE_MIDDLE) * adjustmentRange->adjustmentScale) / (PWM_RANGE_MIDDLE - PWM_RANGE_MIN)) + adjustmentRange->adjustmentCenter;
|
||||
|
||||
newValue = applyAbsoluteAdjustment(controlRateConfig, adjustmentFunction, value);
|
||||
pidInitConfig(currentPidProfile);
|
||||
}
|
||||
}
|
||||
|
||||
#if defined(USE_OSD) && defined(USE_OSD_ADJUSTMENTS)
|
||||
if (newValue != -1
|
||||
&& adjustmentState->config->adjustmentFunction != ADJUSTMENT_RATE_PROFILE // Rate profile already has an OSD element
|
||||
#ifdef USE_OSD_PROFILES
|
||||
&& adjustmentState->config->adjustmentFunction != ADJUSTMENT_OSD_PROFILE
|
||||
#endif
|
||||
#ifdef USE_LED_STRIP
|
||||
&& adjustmentState->config->adjustmentFunction != ADJUSTMENT_LED_PROFILE
|
||||
#endif
|
||||
) {
|
||||
adjustmentRangeNameIndex = adjustmentFunction;
|
||||
adjustmentRangeValue = newValue;
|
||||
}
|
||||
updateOsdAdjustmentData(newValue, adjustmentConfig->adjustmentFunction);
|
||||
#else
|
||||
UNUSED(newValue);
|
||||
#endif
|
||||
MARK_ADJUSTMENT_FUNCTION_AS_BUSY(adjustmentIndex);
|
||||
}
|
||||
|
||||
// Process Absolute adjustments
|
||||
for (int i = 0; i < activeAbsoluteAdjustmentCount; i++) {
|
||||
static int16_t lastRcData[MAX_ADJUSTMENT_RANGE_COUNT] = { 0 };
|
||||
int index = activeAbsoluteAdjustmentArray[i];
|
||||
const adjustmentRange_t * const adjustmentRange = adjustmentRanges(index);
|
||||
const uint8_t channelIndex = NON_AUX_CHANNEL_COUNT + adjustmentRange->auxSwitchChannelIndex;
|
||||
const adjustmentConfig_t *adjustmentConfig = &defaultAdjustmentConfigs[adjustmentRange->adjustmentConfig - ADJUSTMENT_FUNCTION_CONFIG_INDEX_OFFSET];
|
||||
|
||||
// If setting is defined for step adjustment and center value has been specified, apply values directly (scaled) from aux channel
|
||||
if ((rcData[channelIndex] != lastRcData[index]) &&
|
||||
adjustmentRange->adjustmentCenter &&
|
||||
(adjustmentConfig->mode == ADJUSTMENT_MODE_STEP) &&
|
||||
isRangeActive(adjustmentRange->auxChannelIndex, &adjustmentRange->range)) {
|
||||
int value = (((rcData[channelIndex] - PWM_RANGE_MIDDLE) * adjustmentRange->adjustmentScale) / (PWM_RANGE_MIDDLE - PWM_RANGE_MIN)) + adjustmentRange->adjustmentCenter;
|
||||
|
||||
lastRcData[index] = rcData[channelIndex];
|
||||
applyAbsoluteAdjustment(controlRateConfig, adjustmentConfig->adjustmentFunction, value);
|
||||
pidInitConfig(currentPidProfile);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void resetAdjustmentStates(void)
|
||||
void processRcAdjustments(controlRateConfig_t *controlRateConfig)
|
||||
{
|
||||
memset(adjustmentStates, 0, sizeof(adjustmentStates));
|
||||
const bool canUseRxData = rxIsReceivingSignal();
|
||||
|
||||
// Recalculate the new active adjustments if required
|
||||
if (stepwiseAdjustmentCount == ADJUSTMENT_RANGE_COUNT_INVALID) {
|
||||
calcActiveAdjustmentRanges();
|
||||
}
|
||||
|
||||
processStepwiseAdjustments(controlRateConfig, canUseRxData);
|
||||
|
||||
if (canUseRxData) {
|
||||
processContinuosAdjustments(controlRateConfig);
|
||||
}
|
||||
|
||||
#if defined(USE_OSD) && defined(USE_OSD_ADJUSTMENTS)
|
||||
// Hide the element if there is no change
|
||||
updateOsdAdjustmentData(-1, 0);
|
||||
#endif
|
||||
}
|
||||
|
||||
#if defined(USE_OSD) && defined(USE_OSD_ADJUSTMENTS)
|
||||
|
@ -850,5 +855,5 @@ int getAdjustmentsRangeValue(void)
|
|||
|
||||
void activeAdjustmentRangeReset(void)
|
||||
{
|
||||
activeAdjustmentCount = ADJUSTMENT_RANGE_COUNT_INVALID;
|
||||
stepwiseAdjustmentCount = ADJUSTMENT_RANGE_COUNT_INVALID;
|
||||
}
|
||||
|
|
|
@ -21,9 +21,11 @@
|
|||
#pragma once
|
||||
|
||||
#include <stdbool.h>
|
||||
#include "pg/pg.h"
|
||||
|
||||
#include "fc/rc_modes.h"
|
||||
|
||||
#include "pg/pg.h"
|
||||
|
||||
typedef enum {
|
||||
ADJUSTMENT_NONE = 0,
|
||||
ADJUSTMENT_RC_RATE,
|
||||
|
@ -90,27 +92,23 @@ typedef struct adjustmentRange_s {
|
|||
uint8_t adjustmentConfig;
|
||||
uint8_t auxSwitchChannelIndex;
|
||||
|
||||
// ... via slot
|
||||
uint8_t adjustmentIndex;
|
||||
uint16_t adjustmentCenter;
|
||||
uint16_t adjustmentScale;
|
||||
} adjustmentRange_t;
|
||||
|
||||
PG_DECLARE_ARRAY(adjustmentRange_t, MAX_ADJUSTMENT_RANGE_COUNT, adjustmentRanges);
|
||||
|
||||
#define ADJUSTMENT_INDEX_OFFSET 1
|
||||
|
||||
typedef struct adjustmentState_s {
|
||||
uint8_t auxChannelIndex;
|
||||
const adjustmentConfig_t *config;
|
||||
typedef struct timedAdjustmentState_s {
|
||||
uint32_t timeoutAt;
|
||||
} adjustmentState_t;
|
||||
uint8_t adjustmentRangeIndex;
|
||||
bool ready;
|
||||
} timedAdjustmentState_t;
|
||||
|
||||
#ifndef MAX_SIMULTANEOUS_ADJUSTMENT_COUNT
|
||||
#define MAX_SIMULTANEOUS_ADJUSTMENT_COUNT 4 // enough for 4 x 3position switches / 4 aux channel
|
||||
#endif
|
||||
typedef struct continuosAdjustmentState_s {
|
||||
uint8_t adjustmentRangeIndex;
|
||||
int16_t lastRcData;
|
||||
} continuosAdjustmentState_t;
|
||||
|
||||
void resetAdjustmentStates(void);
|
||||
struct controlRateConfig_s;
|
||||
void processRcAdjustments(struct controlRateConfig_s *controlRateConfig);
|
||||
const char *getAdjustmentsRangeName(void);
|
||||
|
|
|
@ -1082,7 +1082,7 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
|
|||
case MSP_ADJUSTMENT_RANGES:
|
||||
for (int i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
|
||||
const adjustmentRange_t *adjRange = adjustmentRanges(i);
|
||||
sbufWriteU8(dst, adjRange->adjustmentIndex);
|
||||
sbufWriteU8(dst, 0); // was adjRange->adjustmentIndex
|
||||
sbufWriteU8(dst, adjRange->auxChannelIndex);
|
||||
sbufWriteU8(dst, adjRange->range.startStep);
|
||||
sbufWriteU8(dst, adjRange->range.endStep);
|
||||
|
@ -1826,17 +1826,13 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
|||
i = sbufReadU8(src);
|
||||
if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
|
||||
adjustmentRange_t *adjRange = adjustmentRangesMutable(i);
|
||||
i = sbufReadU8(src);
|
||||
if (i < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) {
|
||||
adjRange->adjustmentIndex = i;
|
||||
adjRange->auxChannelIndex = sbufReadU8(src);
|
||||
adjRange->range.startStep = sbufReadU8(src);
|
||||
adjRange->range.endStep = sbufReadU8(src);
|
||||
adjRange->adjustmentConfig = sbufReadU8(src);
|
||||
adjRange->auxSwitchChannelIndex = sbufReadU8(src);
|
||||
} else {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
sbufReadU8(src); // was adjRange->adjustmentIndex
|
||||
adjRange->auxChannelIndex = sbufReadU8(src);
|
||||
adjRange->range.startStep = sbufReadU8(src);
|
||||
adjRange->range.endStep = sbufReadU8(src);
|
||||
adjRange->adjustmentConfig = sbufReadU8(src);
|
||||
adjRange->auxSwitchChannelIndex = sbufReadU8(src);
|
||||
|
||||
activeAdjustmentRangeReset();
|
||||
} else {
|
||||
return MSP_RESULT_ERROR;
|
||||
|
|
|
@ -455,8 +455,9 @@ char osdGetTemperatureSymbolForSelectedUnit(void)
|
|||
#ifdef USE_OSD_ADJUSTMENTS
|
||||
static void osdElementAdjustmentRange(osdElementParms_t *element)
|
||||
{
|
||||
if (getAdjustmentsRangeName()) {
|
||||
tfp_sprintf(element->buff, "%s: %3d", getAdjustmentsRangeName(), getAdjustmentsRangeValue());
|
||||
const char *name = getAdjustmentsRangeName();
|
||||
if (name) {
|
||||
tfp_sprintf(element->buff, "%s: %3d", name, getAdjustmentsRangeValue());
|
||||
}
|
||||
}
|
||||
#endif // USE_OSD_ADJUSTMENTS
|
||||
|
|
|
@ -241,17 +241,14 @@ void resetMillis(void) {
|
|||
|
||||
extern "C" {
|
||||
PG_REGISTER(rxConfig_t, rxConfig, PG_RX_CONFIG, 0);
|
||||
void configureAdjustment(uint8_t index, uint8_t auxSwitchChannelIndex, const adjustmentConfig_t *adjustmentConfig);
|
||||
|
||||
extern uint8_t adjustmentStateMask;
|
||||
extern adjustmentState_t adjustmentStates[MAX_SIMULTANEOUS_ADJUSTMENT_COUNT];
|
||||
extern int stepwiseAdjustmentCount;
|
||||
extern timedAdjustmentState_t stepwiseAdjustments[MAX_ADJUSTMENT_RANGE_COUNT];
|
||||
|
||||
static const adjustmentConfig_t rateAdjustmentConfig = {
|
||||
.adjustmentFunction = ADJUSTMENT_RC_RATE,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { 1 }
|
||||
};
|
||||
extern int continuosAdjustmentCount;
|
||||
extern continuosAdjustmentState_t continuosAdjustments[MAX_ADJUSTMENT_RANGE_COUNT];
|
||||
}
|
||||
|
||||
class RcControlsAdjustmentsTest : public ::testing::Test {
|
||||
protected:
|
||||
controlRateConfig_t controlRateConfig = {
|
||||
|
@ -267,10 +264,14 @@ protected:
|
|||
.tpa_breakpoint = 0
|
||||
};
|
||||
|
||||
virtual void SetUp() {
|
||||
adjustmentStateMask = 0;
|
||||
memset(&adjustmentStates, 0, sizeof(adjustmentStates));
|
||||
channelRange_t fullRange = {
|
||||
.startStep = MIN_MODE_RANGE_STEP,
|
||||
.endStep = MAX_MODE_RANGE_STEP
|
||||
};
|
||||
|
||||
int adjustmentRangesIndex;
|
||||
|
||||
virtual void SetUp() {
|
||||
PG_RESET(rxConfig);
|
||||
rxConfigMutable()->mincheck = DEFAULT_MIN_CHECK;
|
||||
rxConfigMutable()->maxcheck = DEFAULT_MAX_CHECK;
|
||||
|
@ -289,13 +290,50 @@ protected:
|
|||
controlRateConfig.dynThrPID = 0;
|
||||
controlRateConfig.tpa_breakpoint = 0;
|
||||
|
||||
PG_RESET(adjustmentRanges);
|
||||
adjustmentRangesIndex = 0;
|
||||
|
||||
stepwiseAdjustmentCount = 0;
|
||||
continuosAdjustmentCount = 0;
|
||||
}
|
||||
|
||||
int configureAdjustmentRange(uint8_t switchChannelIndex, uint8_t adjustmentConfigIndex) {
|
||||
adjustmentRange_t *adjustmentRange = adjustmentRangesMutable(adjustmentRangesIndex);
|
||||
adjustmentRange->auxChannelIndex = AUX1 - NON_AUX_CHANNEL_COUNT;
|
||||
adjustmentRange->range = fullRange;
|
||||
|
||||
adjustmentRange->adjustmentConfig = adjustmentConfigIndex;
|
||||
adjustmentRange->auxSwitchChannelIndex = switchChannelIndex;
|
||||
|
||||
return adjustmentRangesIndex++;
|
||||
}
|
||||
|
||||
timedAdjustmentState_t *configureStepwiseAdjustment(uint8_t switchChannelIndex, uint8_t adjustmentConfigIndex) {
|
||||
int adjustmentRangeIndex = configureAdjustmentRange(switchChannelIndex, adjustmentConfigIndex);
|
||||
|
||||
timedAdjustmentState_t *adjustmentState = &stepwiseAdjustments[stepwiseAdjustmentCount++];
|
||||
adjustmentState->adjustmentRangeIndex = adjustmentRangeIndex;
|
||||
adjustmentState->timeoutAt = 0;
|
||||
adjustmentState->ready = true;
|
||||
|
||||
return adjustmentState;
|
||||
}
|
||||
|
||||
void configureContinuosAdjustment(uint8_t switchChannelIndex, uint8_t adjustmentConfigIndex) {
|
||||
int adjustmentRangeIndex = configureAdjustmentRange(switchChannelIndex, adjustmentConfigIndex);
|
||||
|
||||
continuosAdjustmentState_t *adjustmentState = &continuosAdjustments[continuosAdjustmentCount++];
|
||||
adjustmentState->adjustmentRangeIndex = adjustmentRangeIndex;
|
||||
adjustmentState->lastRcData = 0;
|
||||
}
|
||||
};
|
||||
|
||||
#define ADJUSTMENT_CONFIG_RATE_INDEX 1
|
||||
|
||||
TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsSticksInMiddle)
|
||||
{
|
||||
// given
|
||||
configureAdjustment(0, AUX3 - NON_AUX_CHANNEL_COUNT, &rateAdjustmentConfig);
|
||||
const timedAdjustmentState_t *adjustmentState = configureStepwiseAdjustment(AUX3 - NON_AUX_CHANNEL_COUNT, ADJUSTMENT_CONFIG_RATE_INDEX);
|
||||
|
||||
// and
|
||||
for (int index = AUX1; index < MAX_SUPPORTED_RC_CHANNEL_COUNT; index++) {
|
||||
|
@ -310,10 +348,10 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsSticksInMiddle)
|
|||
processRcAdjustments(&controlRateConfig);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(controlRateConfig.rcRates[FD_ROLL], 90);
|
||||
EXPECT_EQ(controlRateConfig.rcRates[FD_PITCH], 90);
|
||||
EXPECT_EQ(CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP), 0);
|
||||
EXPECT_EQ(adjustmentStateMask, 0);
|
||||
EXPECT_EQ(90, controlRateConfig.rcRates[FD_ROLL]);
|
||||
EXPECT_EQ(90, controlRateConfig.rcRates[FD_PITCH]);
|
||||
EXPECT_EQ(0, CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP));
|
||||
EXPECT_EQ(true, adjustmentState->ready);
|
||||
}
|
||||
|
||||
TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp)
|
||||
|
@ -339,9 +377,7 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
|
|||
rxConfigMutable()->midrc = 1500;
|
||||
|
||||
// and
|
||||
adjustmentStateMask = 0;
|
||||
memset(&adjustmentStates, 0, sizeof(adjustmentStates));
|
||||
configureAdjustment(0, AUX3 - NON_AUX_CHANNEL_COUNT, &rateAdjustmentConfig);
|
||||
const timedAdjustmentState_t *adjustmentState = configureStepwiseAdjustment(AUX3 - NON_AUX_CHANNEL_COUNT, ADJUSTMENT_CONFIG_RATE_INDEX);
|
||||
|
||||
// and
|
||||
for (int index = AUX1; index < MAX_SUPPORTED_RC_CHANNEL_COUNT; index++) {
|
||||
|
@ -355,10 +391,6 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
|
|||
// and
|
||||
rcData[AUX3] = PWM_RANGE_MAX;
|
||||
|
||||
// and
|
||||
uint8_t expectedAdjustmentStateMask =
|
||||
(1 << 0);
|
||||
|
||||
// and
|
||||
fixedMillis = 496;
|
||||
|
||||
|
@ -366,10 +398,10 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
|
|||
processRcAdjustments(&controlRateConfig);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(controlRateConfig.rcRates[FD_ROLL], 91);
|
||||
EXPECT_EQ(controlRateConfig.rcRates[FD_PITCH], 91);
|
||||
EXPECT_EQ(CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP), 1);
|
||||
EXPECT_EQ(adjustmentStateMask, expectedAdjustmentStateMask);
|
||||
EXPECT_EQ(91, controlRateConfig.rcRates[FD_ROLL]);
|
||||
EXPECT_EQ(91, controlRateConfig.rcRates[FD_PITCH]);
|
||||
EXPECT_EQ(1, CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP));
|
||||
EXPECT_EQ(false, adjustmentState->ready);
|
||||
|
||||
//
|
||||
// now pretend a short amount of time has passed, but not enough time to allow the value to have been increased
|
||||
|
@ -381,9 +413,9 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
|
|||
// when
|
||||
processRcAdjustments(&controlRateConfig);
|
||||
|
||||
EXPECT_EQ(controlRateConfig.rcRates[FD_ROLL], 91);
|
||||
EXPECT_EQ(controlRateConfig.rcRates[FD_PITCH], 91);
|
||||
EXPECT_EQ(adjustmentStateMask, expectedAdjustmentStateMask);
|
||||
EXPECT_EQ(91, controlRateConfig.rcRates[FD_ROLL]);
|
||||
EXPECT_EQ(91, controlRateConfig.rcRates[FD_PITCH]);
|
||||
EXPECT_EQ(false, adjustmentState->ready);
|
||||
|
||||
|
||||
//
|
||||
|
@ -397,16 +429,12 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
|
|||
// and
|
||||
fixedMillis = 498;
|
||||
|
||||
// and
|
||||
expectedAdjustmentStateMask = adjustmentStateMask &
|
||||
~(1 << 0);
|
||||
|
||||
// when
|
||||
processRcAdjustments(&controlRateConfig);
|
||||
|
||||
EXPECT_EQ(controlRateConfig.rcRates[FD_ROLL], 91);
|
||||
EXPECT_EQ(controlRateConfig.rcRates[FD_PITCH], 91);
|
||||
EXPECT_EQ(adjustmentStateMask, expectedAdjustmentStateMask);
|
||||
EXPECT_EQ(91, controlRateConfig.rcRates[FD_ROLL]);
|
||||
EXPECT_EQ(91, controlRateConfig.rcRates[FD_PITCH]);
|
||||
EXPECT_EQ(true, adjustmentState->ready);
|
||||
|
||||
|
||||
//
|
||||
|
@ -415,10 +443,6 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
|
|||
// given
|
||||
rcData[AUX3] = PWM_RANGE_MAX;
|
||||
|
||||
// and
|
||||
expectedAdjustmentStateMask =
|
||||
(1 << 0);
|
||||
|
||||
// and
|
||||
fixedMillis = 499;
|
||||
|
||||
|
@ -426,10 +450,10 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
|
|||
processRcAdjustments(&controlRateConfig);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(controlRateConfig.rcRates[FD_ROLL], 92);
|
||||
EXPECT_EQ(controlRateConfig.rcRates[FD_PITCH], 92);
|
||||
EXPECT_EQ(CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP), 2);
|
||||
EXPECT_EQ(adjustmentStateMask, expectedAdjustmentStateMask);
|
||||
EXPECT_EQ(92, controlRateConfig.rcRates[FD_ROLL]);
|
||||
EXPECT_EQ(92, controlRateConfig.rcRates[FD_PITCH]);
|
||||
EXPECT_EQ(2, CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP));
|
||||
EXPECT_EQ(false, adjustmentState->ready);
|
||||
|
||||
//
|
||||
// leaving the switch up, after the original timer would have reset the state should now NOT cause
|
||||
|
@ -443,9 +467,9 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
|
|||
processRcAdjustments(&controlRateConfig);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(controlRateConfig.rcRates[FD_ROLL], 92);
|
||||
EXPECT_EQ(controlRateConfig.rcRates[FD_PITCH], 92);
|
||||
EXPECT_EQ(adjustmentStateMask, expectedAdjustmentStateMask);
|
||||
EXPECT_EQ(92, controlRateConfig.rcRates[FD_ROLL]);
|
||||
EXPECT_EQ(92, controlRateConfig.rcRates[FD_PITCH]);
|
||||
EXPECT_EQ(false, adjustmentState->ready);
|
||||
|
||||
//
|
||||
// should still not be able to be increased
|
||||
|
@ -458,9 +482,9 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
|
|||
processRcAdjustments(&controlRateConfig);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(controlRateConfig.rcRates[FD_ROLL], 92);
|
||||
EXPECT_EQ(controlRateConfig.rcRates[FD_PITCH], 92);
|
||||
EXPECT_EQ(adjustmentStateMask, expectedAdjustmentStateMask);
|
||||
EXPECT_EQ(92, controlRateConfig.rcRates[FD_ROLL]);
|
||||
EXPECT_EQ(92, controlRateConfig.rcRates[FD_PITCH]);
|
||||
EXPECT_EQ(false, adjustmentState->ready);
|
||||
|
||||
//
|
||||
// 500ms has now passed since the switch was returned to the middle, now that
|
||||
|
@ -475,23 +499,18 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
|
|||
processRcAdjustments(&controlRateConfig);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(controlRateConfig.rcRates[FD_ROLL], 93);
|
||||
EXPECT_EQ(controlRateConfig.rcRates[FD_PITCH], 93);
|
||||
EXPECT_EQ(CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP), 3);
|
||||
EXPECT_EQ(adjustmentStateMask, expectedAdjustmentStateMask);
|
||||
EXPECT_EQ(93, controlRateConfig.rcRates[FD_ROLL]);
|
||||
EXPECT_EQ(93, controlRateConfig.rcRates[FD_PITCH]);
|
||||
EXPECT_EQ(3, CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP));
|
||||
EXPECT_EQ(false, adjustmentState->ready);
|
||||
}
|
||||
|
||||
static const adjustmentConfig_t rateProfileAdjustmentConfig = {
|
||||
.adjustmentFunction = ADJUSTMENT_RATE_PROFILE,
|
||||
.mode = ADJUSTMENT_MODE_SELECT,
|
||||
.data = { 3 }
|
||||
};
|
||||
#define ADJUSTMENT_RATE_PROFILE_INDEX 12
|
||||
|
||||
TEST_F(RcControlsAdjustmentsTest, processRcRateProfileAdjustments)
|
||||
{
|
||||
// given
|
||||
int adjustmentIndex = 3;
|
||||
configureAdjustment(adjustmentIndex, AUX4 - NON_AUX_CHANNEL_COUNT, &rateProfileAdjustmentConfig);
|
||||
configureContinuosAdjustment(AUX4 - NON_AUX_CHANNEL_COUNT, ADJUSTMENT_RATE_PROFILE_INDEX);
|
||||
|
||||
// and
|
||||
for (int index = AUX1; index < MAX_SUPPORTED_RC_CHANNEL_COUNT; index++) {
|
||||
|
@ -505,54 +524,20 @@ TEST_F(RcControlsAdjustmentsTest, processRcRateProfileAdjustments)
|
|||
// and
|
||||
rcData[AUX4] = PWM_RANGE_MAX;
|
||||
|
||||
// and
|
||||
uint8_t expectedAdjustmentStateMask =
|
||||
(1 << adjustmentIndex);
|
||||
|
||||
// when
|
||||
processRcAdjustments(&controlRateConfig);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP), 1);
|
||||
EXPECT_EQ(CALL_COUNTER(COUNTER_CHANGE_CONTROL_RATE_PROFILE), 1);
|
||||
EXPECT_EQ(adjustmentStateMask, expectedAdjustmentStateMask);
|
||||
EXPECT_EQ(1, CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP));
|
||||
EXPECT_EQ(1, CALL_COUNTER(COUNTER_CHANGE_CONTROL_RATE_PROFILE));
|
||||
}
|
||||
|
||||
static const adjustmentConfig_t pidPitchAndRollPAdjustmentConfig = {
|
||||
.adjustmentFunction = ADJUSTMENT_PITCH_ROLL_P,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { 1 }
|
||||
};
|
||||
|
||||
static const adjustmentConfig_t pidPitchAndRollIAdjustmentConfig = {
|
||||
.adjustmentFunction = ADJUSTMENT_PITCH_ROLL_I,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { 1 }
|
||||
};
|
||||
|
||||
static const adjustmentConfig_t pidPitchAndRollDAdjustmentConfig = {
|
||||
.adjustmentFunction = ADJUSTMENT_PITCH_ROLL_D,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { 1 }
|
||||
};
|
||||
|
||||
static const adjustmentConfig_t pidYawPAdjustmentConfig = {
|
||||
.adjustmentFunction = ADJUSTMENT_YAW_P,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { 1 }
|
||||
};
|
||||
|
||||
static const adjustmentConfig_t pidYawIAdjustmentConfig = {
|
||||
.adjustmentFunction = ADJUSTMENT_YAW_I,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { 1 }
|
||||
};
|
||||
|
||||
static const adjustmentConfig_t pidYawDAdjustmentConfig = {
|
||||
.adjustmentFunction = ADJUSTMENT_YAW_D,
|
||||
.mode = ADJUSTMENT_MODE_STEP,
|
||||
.data = { 1 }
|
||||
};
|
||||
#define ADJUSTMENT_PITCH_ROLL_P_INDEX 6
|
||||
#define ADJUSTMENT_PITCH_ROLL_I_INDEX 7
|
||||
#define ADJUSTMENT_PITCH_ROLL_D_INDEX 8
|
||||
#define ADJUSTMENT_YAW_P_INDEX 9
|
||||
#define ADJUSTMENT_YAW_I_INDEX 10
|
||||
#define ADJUSTMENT_YAW_D_INDEX 11
|
||||
|
||||
TEST_F(RcControlsAdjustmentsTest, processPIDIncreasePidController0)
|
||||
{
|
||||
|
@ -572,12 +557,12 @@ TEST_F(RcControlsAdjustmentsTest, processPIDIncreasePidController0)
|
|||
controlRateConfig_t controlRateConfig;
|
||||
memset(&controlRateConfig, 0, sizeof (controlRateConfig));
|
||||
|
||||
configureAdjustment(0, AUX1 - NON_AUX_CHANNEL_COUNT, &pidPitchAndRollPAdjustmentConfig);
|
||||
configureAdjustment(1, AUX2 - NON_AUX_CHANNEL_COUNT, &pidPitchAndRollIAdjustmentConfig);
|
||||
configureAdjustment(2, AUX3 - NON_AUX_CHANNEL_COUNT, &pidPitchAndRollDAdjustmentConfig);
|
||||
configureAdjustment(3, AUX1 - NON_AUX_CHANNEL_COUNT, &pidYawPAdjustmentConfig);
|
||||
configureAdjustment(4, AUX2 - NON_AUX_CHANNEL_COUNT, &pidYawIAdjustmentConfig);
|
||||
configureAdjustment(5, AUX3 - NON_AUX_CHANNEL_COUNT, &pidYawDAdjustmentConfig);
|
||||
const timedAdjustmentState_t *adjustmentState1 = configureStepwiseAdjustment(AUX1 - NON_AUX_CHANNEL_COUNT, ADJUSTMENT_PITCH_ROLL_P_INDEX);
|
||||
const timedAdjustmentState_t *adjustmentState2 = configureStepwiseAdjustment(AUX2 - NON_AUX_CHANNEL_COUNT, ADJUSTMENT_PITCH_ROLL_I_INDEX);
|
||||
const timedAdjustmentState_t *adjustmentState3 = configureStepwiseAdjustment(AUX3 - NON_AUX_CHANNEL_COUNT, ADJUSTMENT_PITCH_ROLL_D_INDEX);
|
||||
const timedAdjustmentState_t *adjustmentState4 = configureStepwiseAdjustment(AUX1 - NON_AUX_CHANNEL_COUNT, ADJUSTMENT_YAW_P_INDEX);
|
||||
const timedAdjustmentState_t *adjustmentState5 = configureStepwiseAdjustment(AUX2 - NON_AUX_CHANNEL_COUNT, ADJUSTMENT_YAW_I_INDEX);
|
||||
const timedAdjustmentState_t *adjustmentState6 = configureStepwiseAdjustment(AUX3 - NON_AUX_CHANNEL_COUNT, ADJUSTMENT_YAW_D_INDEX);
|
||||
|
||||
// and
|
||||
for (int index = AUX1; index < MAX_SUPPORTED_RC_CHANNEL_COUNT; index++) {
|
||||
|
@ -593,23 +578,19 @@ TEST_F(RcControlsAdjustmentsTest, processPIDIncreasePidController0)
|
|||
rcData[AUX2] = PWM_RANGE_MAX;
|
||||
rcData[AUX3] = PWM_RANGE_MAX;
|
||||
|
||||
// and
|
||||
uint8_t expectedAdjustmentStateMask =
|
||||
(1 << 0) |
|
||||
(1 << 1) |
|
||||
(1 << 2) |
|
||||
(1 << 3) |
|
||||
(1 << 4) |
|
||||
(1 << 5);
|
||||
|
||||
// when
|
||||
currentPidProfile = &pidProfile;
|
||||
rcControlsInit();
|
||||
processRcAdjustments(&controlRateConfig);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP), 6);
|
||||
EXPECT_EQ(adjustmentStateMask, expectedAdjustmentStateMask);
|
||||
EXPECT_EQ(6, CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP));
|
||||
EXPECT_EQ(false, adjustmentState1->ready);
|
||||
EXPECT_EQ(false, adjustmentState2->ready);
|
||||
EXPECT_EQ(false, adjustmentState3->ready);
|
||||
EXPECT_EQ(false, adjustmentState4->ready);
|
||||
EXPECT_EQ(false, adjustmentState5->ready);
|
||||
EXPECT_EQ(false, adjustmentState6->ready);
|
||||
|
||||
// and
|
||||
EXPECT_EQ(1, pidProfile.pid[PID_PITCH].P);
|
||||
|
@ -623,82 +604,6 @@ TEST_F(RcControlsAdjustmentsTest, processPIDIncreasePidController0)
|
|||
EXPECT_EQ(28, pidProfile.pid[PID_YAW].D);
|
||||
}
|
||||
|
||||
#if 0 // only one PID controller
|
||||
|
||||
TEST_F(RcControlsAdjustmentsTest, processPIDIncreasePidController2)
|
||||
{
|
||||
// given
|
||||
pidProfile_t pidProfile;
|
||||
memset(&pidProfile, 0, sizeof (pidProfile));
|
||||
pidProfile.pidController = 2;
|
||||
pidProfile.P_f[PIDPITCH] = 0.0f;
|
||||
pidProfile.P_f[PIDROLL] = 5.0f;
|
||||
pidProfile.P_f[PIDYAW] = 7.0f;
|
||||
pidProfile.I_f[PIDPITCH] = 10.0f;
|
||||
pidProfile.I_f[PIDROLL] = 15.0f;
|
||||
pidProfile.I_f[PIDYAW] = 17.0f;
|
||||
pidProfile.D_f[PIDPITCH] = 20.0f;
|
||||
pidProfile.D_f[PIDROLL] = 25.0f;
|
||||
pidProfile.D_f[PIDYAW] = 27.0f;
|
||||
|
||||
// and
|
||||
controlRateConfig_t controlRateConfig;
|
||||
memset(&controlRateConfig, 0, sizeof (controlRateConfig));
|
||||
|
||||
configureAdjustment(0, AUX1 - NON_AUX_CHANNEL_COUNT, &pidPitchAndRollPAdjustmentConfig);
|
||||
configureAdjustment(1, AUX2 - NON_AUX_CHANNEL_COUNT, &pidPitchAndRollIAdjustmentConfig);
|
||||
configureAdjustment(2, AUX3 - NON_AUX_CHANNEL_COUNT, &pidPitchAndRollDAdjustmentConfig);
|
||||
configureAdjustment(3, AUX1 - NON_AUX_CHANNEL_COUNT, &pidYawPAdjustmentConfig);
|
||||
configureAdjustment(4, AUX2 - NON_AUX_CHANNEL_COUNT, &pidYawIAdjustmentConfig);
|
||||
configureAdjustment(5, AUX3 - NON_AUX_CHANNEL_COUNT, &pidYawDAdjustmentConfig);
|
||||
|
||||
// and
|
||||
for (int index = AUX1; index < MAX_SUPPORTED_RC_CHANNEL_COUNT; index++) {
|
||||
rcData[index] = PWM_RANGE_MIDDLE;
|
||||
}
|
||||
|
||||
// and
|
||||
resetCallCounters();
|
||||
resetMillis();
|
||||
|
||||
// and
|
||||
rcData[AUX1] = PWM_RANGE_MAX;
|
||||
rcData[AUX2] = PWM_RANGE_MAX;
|
||||
rcData[AUX3] = PWM_RANGE_MAX;
|
||||
|
||||
// and
|
||||
uint8_t expectedAdjustmentStateMask =
|
||||
(1 << 0) |
|
||||
(1 << 1) |
|
||||
(1 << 2) |
|
||||
(1 << 3) |
|
||||
(1 << 4) |
|
||||
(1 << 5);
|
||||
|
||||
// when
|
||||
currentPidProfile = &pidProfile;
|
||||
rcControlsInit();
|
||||
processRcAdjustments(&controlRateConfig, &rxConfig);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP), 6);
|
||||
EXPECT_EQ(adjustmentStateMask, expectedAdjustmentStateMask);
|
||||
|
||||
// and
|
||||
EXPECT_EQ(0.01f, pidProfile.P_f[PIDPITCH]);
|
||||
EXPECT_EQ(5.01f, pidProfile.P_f[PIDROLL]);
|
||||
EXPECT_EQ(7.01f, pidProfile.P_f[PIDYAW]);
|
||||
EXPECT_EQ(10.01f, pidProfile.I_f[PIDPITCH]);
|
||||
EXPECT_EQ(15.01f, pidProfile.I_f[PIDROLL]);
|
||||
EXPECT_EQ(17.01f, pidProfile.I_f[PIDYAW]);
|
||||
EXPECT_EQ(20.001f, pidProfile.D_f[PIDPITCH]);
|
||||
EXPECT_EQ(25.001f, pidProfile.D_f[PIDROLL]);
|
||||
EXPECT_EQ(27.001f, pidProfile.D_f[PIDYAW]);
|
||||
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
extern "C" {
|
||||
void setConfigDirty(void) {}
|
||||
void saveConfigAndNotify(void) {}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue