Merge pull request #4973 from mikeller/added_selectable_raceflight_rates

Added selectable RaceFlight rates.
This commit is contained in:
Michael Keller 2018-01-19 00:56:18 +13:00 committed by GitHub
commit c0b8f6c7dc
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
21 changed files with 260 additions and 135 deletions

View File

@ -1232,14 +1232,16 @@ static bool blackboxWriteSysinfo(void)
BLACKBOX_PRINT_HEADER_LINE("looptime", "%d", gyro.targetLooptime);
BLACKBOX_PRINT_HEADER_LINE("gyro_sync_denom", "%d", gyroConfig()->gyro_sync_denom);
BLACKBOX_PRINT_HEADER_LINE("pid_process_denom", "%d", pidConfig()->pid_process_denom);
BLACKBOX_PRINT_HEADER_LINE("rc_rate", "%d", currentControlRateProfile->rcRate8);
BLACKBOX_PRINT_HEADER_LINE("rc_expo", "%d", currentControlRateProfile->rcExpo8);
BLACKBOX_PRINT_HEADER_LINE("rc_rate_yaw", "%d", currentControlRateProfile->rcYawRate8);
BLACKBOX_PRINT_HEADER_LINE("rc_expo_yaw", "%d", currentControlRateProfile->rcYawExpo8);
BLACKBOX_PRINT_HEADER_LINE("thr_mid", "%d", currentControlRateProfile->thrMid8);
BLACKBOX_PRINT_HEADER_LINE("thr_expo", "%d", currentControlRateProfile->thrExpo8);
BLACKBOX_PRINT_HEADER_LINE("tpa_rate", "%d", currentControlRateProfile->dynThrPID);
BLACKBOX_PRINT_HEADER_LINE("tpa_breakpoint", "%d", currentControlRateProfile->tpa_breakpoint);
BLACKBOX_PRINT_HEADER_LINE("rc_rates", "%d,%d,%d", currentControlRateProfile->rcRates[ROLL],
currentControlRateProfile->rcRates[PITCH],
currentControlRateProfile->rcRates[YAW]);
BLACKBOX_PRINT_HEADER_LINE("rc_expo", "%d,%d,%d", currentControlRateProfile->rcExpo[ROLL],
currentControlRateProfile->rcExpo[PITCH],
currentControlRateProfile->rcExpo[YAW]);
BLACKBOX_PRINT_HEADER_LINE("rates", "%d,%d,%d", currentControlRateProfile->rates[ROLL],
currentControlRateProfile->rates[PITCH],
currentControlRateProfile->rates[YAW]);

View File

@ -203,15 +203,17 @@ static OSD_Entry cmsx_menuRateProfileEntries[] =
{
{ "-- RATE --", OME_Label, NULL, rateProfileIndexString, 0 },
{ "RC RATE", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcRate8, 0, 255, 1, 10 }, 0 },
{ "RC YAW RATE", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcYawRate8, 0, 255, 1, 10 }, 0 },
{ "RC R RATE", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcRates[FD_ROLL], 0, 255, 1, 10 }, 0 },
{ "RC P RATE", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcRates[FD_PITCH], 0, 255, 1, 10 }, 0 },
{ "RC Y RATE", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcRates[FD_YAW], 0, 255, 1, 10 }, 0 },
{ "ROLL SUPER", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rates[0], 0, 100, 1, 10 }, 0 },
{ "PITCH SUPER", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rates[1], 0, 100, 1, 10 }, 0 },
{ "YAW SUPER", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rates[2], 0, 100, 1, 10 }, 0 },
{ "ROLL SUPER", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rates[FD_ROLL], 0, 100, 1, 10 }, 0 },
{ "PITCH SUPER", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rates[FD_PITCH], 0, 100, 1, 10 }, 0 },
{ "YAW SUPER", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rates[FD_YAW], 0, 100, 1, 10 }, 0 },
{ "RC EXPO", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcExpo8, 0, 100, 1, 10 }, 0 },
{ "RC YAW EXP", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcYawExpo8, 0, 100, 1, 10 }, 0 },
{ "RC R EXPO", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcExpo[FD_ROLL], 0, 100, 1, 10 }, 0 },
{ "RC P EXPO", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcExpo[FD_PITCH], 0, 100, 1, 10 }, 0 },
{ "RC Y EXPO", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcExpo[FD_YAW], 0, 100, 1, 10 }, 0 },
{ "THR MID", OME_UINT8, NULL, &(OSD_UINT8_t) { &rateProfile.thrMid8, 0, 100, 1}, 0 },
{ "THR EXPO", OME_UINT8, NULL, &(OSD_UINT8_t) { &rateProfile.thrExpo8, 0, 100, 1}, 0 },

View File

@ -137,7 +137,7 @@ void resetConfigs(void)
void activateConfig(void)
{
#ifndef USE_OSD_SLAVE
generateThrottleCurve();
initRcProcessing();
resetAdjustmentStates();

View File

@ -33,21 +33,23 @@
controlRateConfig_t *currentControlRateProfile;
PG_REGISTER_ARRAY_WITH_RESET_FN(controlRateConfig_t, CONTROL_RATE_PROFILE_COUNT, controlRateProfiles, PG_CONTROL_RATE_PROFILES, 0);
PG_REGISTER_ARRAY_WITH_RESET_FN(controlRateConfig_t, CONTROL_RATE_PROFILE_COUNT, controlRateProfiles, PG_CONTROL_RATE_PROFILES, 1);
void pgResetFn_controlRateProfiles(controlRateConfig_t *controlRateConfig)
{
for (int i = 0; i < CONTROL_RATE_PROFILE_COUNT; i++) {
RESET_CONFIG(controlRateConfig_t, &controlRateConfig[i],
.rcRate8 = 100,
.rcYawRate8 = 100,
.rcExpo8 = 0,
.thrMid8 = 50,
.thrExpo8 = 0,
.dynThrPID = 10,
.rcYawExpo8 = 0,
.tpa_breakpoint = 1650,
.rates_type = RATES_TYPE_BETAFLIGHT,
.rcRates[FD_ROLL] = 100,
.rcRates[FD_PITCH] = 100,
.rcRates[FD_YAW] = 100,
.rcExpo[FD_ROLL] = 0,
.rcExpo[FD_PITCH] = 0,
.rcExpo[FD_YAW] = 0,
.rates[FD_ROLL] = 70,
.rates[FD_PITCH] = 70,
.rates[FD_YAW] = 70
@ -69,7 +71,7 @@ void changeControlRateProfile(uint8_t controlRateProfileIndex)
controlRateProfileIndex = CONTROL_RATE_PROFILE_COUNT - 1;
}
setControlRateProfile(controlRateProfileIndex);
generateThrottleCurve();
initRcProcessing();
}
void copyControlRateProfile(const uint8_t dstControlRateProfileIndex, const uint8_t srcControlRateProfileIndex) {

View File

@ -23,15 +23,19 @@
#define CONTROL_RATE_PROFILE_COUNT 3
typedef enum {
RATES_TYPE_BETAFLIGHT = 0,
RATES_TYPE_RACEFLIGHT,
} ratesType_e;
typedef struct controlRateConfig_s {
uint8_t rcRate8;
uint8_t rcYawRate8;
uint8_t rcExpo8;
uint8_t thrMid8;
uint8_t thrExpo8;
uint8_t rates_type;
uint8_t rcRates[3];
uint8_t rcExpo[3];
uint8_t rates[3];
uint8_t dynThrPID;
uint8_t rcYawExpo8;
uint16_t tpa_breakpoint; // Breakpoint where TPA is activated
} controlRateConfig_t;

View File

@ -46,10 +46,12 @@
#include "sensors/battery.h"
typedef float (applyRatesFn)(int axis, float rcCommandf, const float rcCommandfAbs);
static float setpointRate[3], rcDeflection[3], rcDeflectionAbs[3];
static float throttlePIDAttenuation;
static bool reverseMotors = false;
static applyRatesFn *applyRates;
float getSetpointRate(int axis)
{
@ -74,20 +76,6 @@ float getThrottlePIDAttenuation(void)
#define THROTTLE_LOOKUP_LENGTH 12
static int16_t lookupThrottleRC[THROTTLE_LOOKUP_LENGTH]; // lookup table for expo & mid THROTTLE
void generateThrottleCurve(void)
{
for (int i = 0; i < THROTTLE_LOOKUP_LENGTH; i++) {
const int16_t tmp = 10 * i - currentControlRateProfile->thrMid8;
uint8_t y = 1;
if (tmp > 0)
y = 100 - currentControlRateProfile->thrMid8;
if (tmp < 0)
y = currentControlRateProfile->thrMid8;
lookupThrottleRC[i] = 10 * currentControlRateProfile->thrMid8 + tmp * (100 - currentControlRateProfile->thrExpo8 + (int32_t) currentControlRateProfile->thrExpo8 * (tmp * tmp) / (y * y)) / 10;
lookupThrottleRC[i] = PWM_RANGE_MIN + (PWM_RANGE_MAX - PWM_RANGE_MIN) * lookupThrottleRC[i] / 1000; // [MINTHROTTLE;MAXTHROTTLE]
}
}
static int16_t rcLookupThrottle(int32_t tmp)
{
const int32_t tmp2 = tmp / 100;
@ -98,37 +86,44 @@ static int16_t rcLookupThrottle(int32_t tmp)
#define SETPOINT_RATE_LIMIT 1998.0f
#define RC_RATE_INCREMENTAL 14.54f
static void calculateSetpointRate(int axis)
float applyBetaflightRates(int axis, float rcCommandf, const float rcCommandfAbs)
{
uint8_t rcExpo;
float rcRate;
if (axis != YAW) {
rcExpo = currentControlRateProfile->rcExpo8;
rcRate = currentControlRateProfile->rcRate8 / 100.0f;
} else {
rcExpo = currentControlRateProfile->rcYawExpo8;
rcRate = currentControlRateProfile->rcYawRate8 / 100.0f;
}
if (rcRate > 2.0f) {
rcRate += RC_RATE_INCREMENTAL * (rcRate - 2.0f);
if (currentControlRateProfile->rcExpo[axis]) {
const float expof = currentControlRateProfile->rcExpo[axis] / 100.0f;
rcCommandf = rcCommandf * power3(rcCommandfAbs) * expof + rcCommandf * (1 - expof);
}
float angleRate = 200.0f * currentControlRateProfile->rcRates[axis] * rcCommandf;
if (currentControlRateProfile->rates[axis]) {
const float rcSuperfactor = 1.0f / (constrainf(1.0f - (rcCommandfAbs * (currentControlRateProfile->rates[axis] / 100.0f)), 0.01f, 1.00f));
angleRate *= rcSuperfactor;
}
return angleRate;
}
float applyRaceFlightRates(int axis, float rcCommandf, const float rcCommandfAbs)
{
UNUSED(rcCommandfAbs);
// -1.0 to 1.0 ranged and curved
rcCommandf = ((1.0f + 0.01f * currentControlRateProfile->rcExpo[axis] * (rcCommandf * rcCommandf - 1.0f)) * rcCommandf);
// convert to -2000 to 2000 range using acro+ modifier
float angleRate = 10.0f * currentControlRateProfile->rcRates[axis] * rcCommandf;
angleRate = angleRate * (1 + (float)currentControlRateProfile->rates[axis] * 0.01f);
return angleRate;
}
static void calculateSetpointRate(int axis)
{
// scale rcCommandf to range [-1.0, 1.0]
float rcCommandf = rcCommand[axis] / 500.0f;
rcDeflection[axis] = rcCommandf;
const float rcCommandfAbs = ABS(rcCommandf);
rcDeflectionAbs[axis] = rcCommandfAbs;
if (rcExpo) {
const float expof = rcExpo / 100.0f;
rcCommandf = rcCommandf * power3(rcCommandfAbs) * expof + rcCommandf * (1-expof);
}
float angleRate = 200.0f * rcRate * rcCommandf;
if (currentControlRateProfile->rates[axis]) {
const float rcSuperfactor = 1.0f / (constrainf(1.0f - (rcCommandfAbs * (currentControlRateProfile->rates[axis] / 100.0f)), 0.01f, 1.00f));
angleRate *= rcSuperfactor;
}
float angleRate = applyRates(axis, rcCommandf, rcCommandfAbs);
DEBUG_SET(DEBUG_ANGLERATE, axis, angleRate);
@ -249,7 +244,14 @@ void processRcCommand(void)
readyToCalculateRateAxisCnt = FD_YAW;
}
#if defined(SITL)
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunsafe-loop-optimizations"
#endif
for (int axis = 0; axis <= readyToCalculateRateAxisCnt; axis++) {
#if defined(SITL)
#pragma GCC diagnostic pop
#endif
calculateSetpointRate(axis);
}
@ -369,3 +371,28 @@ bool isMotorsReversed(void)
{
return reverseMotors;
}
void initRcProcessing(void)
{
for (int i = 0; i < THROTTLE_LOOKUP_LENGTH; i++) {
const int16_t tmp = 10 * i - currentControlRateProfile->thrMid8;
uint8_t y = 1;
if (tmp > 0)
y = 100 - currentControlRateProfile->thrMid8;
if (tmp < 0)
y = currentControlRateProfile->thrMid8;
lookupThrottleRC[i] = 10 * currentControlRateProfile->thrMid8 + tmp * (100 - currentControlRateProfile->thrExpo8 + (int32_t) currentControlRateProfile->thrExpo8 * (tmp * tmp) / (y * y)) / 10;
lookupThrottleRC[i] = PWM_RANGE_MIN + (PWM_RANGE_MAX - PWM_RANGE_MIN) * lookupThrottleRC[i] / 1000; // [MINTHROTTLE;MAXTHROTTLE]
}
switch (currentControlRateProfile->rates_type) {
case RATES_TYPE_BETAFLIGHT:
applyRates = applyBetaflightRates;
break;
case RATES_TYPE_RACEFLIGHT:
applyRates = applyRaceFlightRates;
break;
}
}

View File

@ -23,6 +23,5 @@ float getRcDeflectionAbs(int axis);
float getThrottlePIDAttenuation(void);
void updateRcCommands(void);
void resetYawAxis(void);
void generateThrottleCurve(void);
void initRcProcessing(void);
bool isMotorsReversed(void);

View File

@ -256,24 +256,44 @@ static int applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t a
int newValue;
switch (adjustmentFunction) {
case ADJUSTMENT_RC_RATE:
newValue = constrain((int)controlRateConfig->rcRate8 + delta, 0, 250); // FIXME magic numbers repeated in cli.c
controlRateConfig->rcRate8 = newValue;
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_RC_RATE, newValue);
case ADJUSTMENT_ROLL_RC_RATE:
newValue = constrain((int)controlRateConfig->rcRates[FD_ROLL] + delta, 0, CONTROL_RATE_CONFIG_RC_RATES_MAX);
controlRateConfig->rcRates[FD_ROLL] = newValue;
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_ROLL_RC_RATE, newValue);
if (adjustmentFunction == ADJUSTMENT_ROLL_RC_RATE) {
break;
}
// fall through for combined ADJUSTMENT_RC_EXPO
FALLTHROUGH;
case ADJUSTMENT_PITCH_RC_RATE:
newValue = constrain((int)controlRateConfig->rcRates[FD_PITCH] + delta, 0, CONTROL_RATE_CONFIG_RC_RATES_MAX);
controlRateConfig->rcRates[FD_PITCH] = newValue;
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_PITCH_RC_RATE, newValue);
break;
case ADJUSTMENT_RC_EXPO:
newValue = constrain((int)controlRateConfig->rcExpo8 + delta, 0, 100); // FIXME magic numbers repeated in cli.c
controlRateConfig->rcExpo8 = newValue;
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_RC_EXPO, newValue);
case ADJUSTMENT_ROLL_RC_EXPO:
newValue = constrain((int)controlRateConfig->rcExpo[FD_ROLL] + delta, 0, CONTROL_RATE_CONFIG_RC_EXPO_MAX);
controlRateConfig->rcExpo[FD_ROLL] = newValue;
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_ROLL_RC_EXPO, newValue);
if (adjustmentFunction == ADJUSTMENT_ROLL_RC_EXPO) {
break;
}
// fall through for combined ADJUSTMENT_RC_EXPO
FALLTHROUGH;
case ADJUSTMENT_PITCH_RC_EXPO:
newValue = constrain((int)controlRateConfig->rcExpo[FD_PITCH] + delta, 0, CONTROL_RATE_CONFIG_RC_EXPO_MAX);
controlRateConfig->rcExpo[FD_PITCH] = newValue;
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_PITCH_RC_EXPO, newValue);
break;
case ADJUSTMENT_THROTTLE_EXPO:
newValue = constrain((int)controlRateConfig->thrExpo8 + delta, 0, 100); // FIXME magic numbers repeated in cli.c
controlRateConfig->thrExpo8 = newValue;
generateThrottleCurve();
initRcProcessing();
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_THROTTLE_EXPO, newValue);
break;
case ADJUSTMENT_PITCH_ROLL_RATE:
case ADJUSTMENT_PITCH_RATE:
newValue = constrain((int)controlRateConfig->rates[FD_PITCH] + delta, 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX);
newValue = constrain((int)controlRateConfig->rates[FD_PITCH] + delta, 0, CONTROL_RATE_CONFIG_RATE_MAX);
controlRateConfig->rates[FD_PITCH] = newValue;
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_PITCH_RATE, newValue);
if (adjustmentFunction == ADJUSTMENT_PITCH_RATE) {
@ -282,12 +302,12 @@ static int applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t a
// fall through for combined ADJUSTMENT_PITCH_ROLL_RATE
FALLTHROUGH;
case ADJUSTMENT_ROLL_RATE:
newValue = constrain((int)controlRateConfig->rates[FD_ROLL] + delta, 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX);
newValue = constrain((int)controlRateConfig->rates[FD_ROLL] + delta, 0, CONTROL_RATE_CONFIG_RATE_MAX);
controlRateConfig->rates[FD_ROLL] = newValue;
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_ROLL_RATE, newValue);
break;
case ADJUSTMENT_YAW_RATE:
newValue = constrain((int)controlRateConfig->rates[FD_YAW] + delta, 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX);
newValue = constrain((int)controlRateConfig->rates[FD_YAW] + delta, 0, CONTROL_RATE_CONFIG_RATE_MAX);
controlRateConfig->rates[FD_YAW] = newValue;
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_YAW_RATE, newValue);
break;
@ -353,8 +373,8 @@ static int applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t a
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_YAW_D, newValue);
break;
case ADJUSTMENT_RC_RATE_YAW:
newValue = constrain((int)controlRateConfig->rcYawRate8 + delta, 0, 300); // FIXME magic numbers repeated in cli.c
controlRateConfig->rcYawRate8 = newValue;
newValue = constrain((int)controlRateConfig->rcRates[FD_YAW] + delta, 0, CONTROL_RATE_CONFIG_RC_RATES_MAX);
controlRateConfig->rcRates[FD_YAW] = newValue;
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_RC_RATE_YAW, newValue);
break;
case ADJUSTMENT_D_SETPOINT:

View File

@ -47,6 +47,10 @@ typedef enum {
ADJUSTMENT_D_SETPOINT,
ADJUSTMENT_D_SETPOINT_TRANSITION,
ADJUSTMENT_HORIZON_STRENGTH,
ADJUSTMENT_ROLL_RC_RATE,
ADJUSTMENT_PITCH_RC_RATE,
ADJUSTMENT_ROLL_RC_EXPO,
ADJUSTMENT_PITCH_RC_EXPO,
ADJUSTMENT_FUNCTION_COUNT
} adjustmentFunction_e;

View File

@ -68,11 +68,12 @@ typedef enum {
#define THR_CE (3 << (2 * THROTTLE))
#define THR_HI (2 << (2 * THROTTLE))
// Roll/pitch rates are a proportion used for mixing, so it tops out at 1.0:
#define CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX 100
#define CONTROL_RATE_CONFIG_RC_EXPO_MAX 100
/* Meaningful yaw rates are effectively unbounded because they are treated as a rotation rate multiplier: */
#define CONTROL_RATE_CONFIG_YAW_RATE_MAX 255
#define CONTROL_RATE_CONFIG_RC_RATES_MAX 255
// (Super) rates are constrained to [0, 100] for Betaflight rates, so values higher than 100 won't make a difference. Range extended for RaceFlight rates.
#define CONTROL_RATE_CONFIG_RATE_MAX 255
#define CONTROL_RATE_CONFIG_TPA_MAX 100

View File

@ -880,8 +880,8 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
break;
case MSP_RC_TUNING:
sbufWriteU8(dst, currentControlRateProfile->rcRate8);
sbufWriteU8(dst, currentControlRateProfile->rcExpo8);
sbufWriteU8(dst, currentControlRateProfile->rcRates[FD_ROLL]);
sbufWriteU8(dst, currentControlRateProfile->rcExpo[FD_ROLL]);
for (int i = 0 ; i < 3; i++) {
sbufWriteU8(dst, currentControlRateProfile->rates[i]); // R,P,Y see flight_dynamics_index_t
}
@ -889,8 +889,10 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
sbufWriteU8(dst, currentControlRateProfile->thrMid8);
sbufWriteU8(dst, currentControlRateProfile->thrExpo8);
sbufWriteU16(dst, currentControlRateProfile->tpa_breakpoint);
sbufWriteU8(dst, currentControlRateProfile->rcYawExpo8);
sbufWriteU8(dst, currentControlRateProfile->rcYawRate8);
sbufWriteU8(dst, currentControlRateProfile->rcExpo[FD_YAW]);
sbufWriteU8(dst, currentControlRateProfile->rcRates[FD_YAW]);
sbufWriteU8(dst, currentControlRateProfile->rcRates[FD_PITCH]);
sbufWriteU8(dst, currentControlRateProfile->rcExpo[FD_PITCH]);
break;
case MSP_PID:
@ -1473,24 +1475,45 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
case MSP_SET_RC_TUNING:
if (sbufBytesRemaining(src) >= 10) {
currentControlRateProfile->rcRate8 = sbufReadU8(src);
currentControlRateProfile->rcExpo8 = sbufReadU8(src);
for (int i = 0; i < 3; i++) {
value = sbufReadU8(src);
currentControlRateProfile->rates[i] = MIN(value, i == FD_YAW ? CONTROL_RATE_CONFIG_YAW_RATE_MAX : CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX);
value = sbufReadU8(src);
if (currentControlRateProfile->rcRates[FD_PITCH] == currentControlRateProfile->rcRates[FD_ROLL]) {
currentControlRateProfile->rcRates[FD_PITCH] = value;
}
currentControlRateProfile->rcRates[FD_ROLL] = value;
value = sbufReadU8(src);
if (currentControlRateProfile->rcExpo[FD_PITCH] == currentControlRateProfile->rcExpo[FD_ROLL]) {
currentControlRateProfile->rcExpo[FD_PITCH] = value;
}
currentControlRateProfile->rcExpo[FD_ROLL] = value;
for (int i = 0; i < 3; i++) {
currentControlRateProfile->rates[i] = sbufReadU8(src);
}
value = sbufReadU8(src);
currentControlRateProfile->dynThrPID = MIN(value, CONTROL_RATE_CONFIG_TPA_MAX);
currentControlRateProfile->thrMid8 = sbufReadU8(src);
currentControlRateProfile->thrExpo8 = sbufReadU8(src);
currentControlRateProfile->tpa_breakpoint = sbufReadU16(src);
if (sbufBytesRemaining(src) >= 1) {
currentControlRateProfile->rcYawExpo8 = sbufReadU8(src);
currentControlRateProfile->rcExpo[FD_YAW] = sbufReadU8(src);
}
if (sbufBytesRemaining(src) >= 1) {
currentControlRateProfile->rcYawRate8 = sbufReadU8(src);
currentControlRateProfile->rcRates[FD_YAW] = sbufReadU8(src);
}
generateThrottleCurve();
if (sbufBytesRemaining(src) >= 1) {
currentControlRateProfile->rcRates[FD_PITCH] = sbufReadU8(src);
}
if (sbufBytesRemaining(src) >= 1) {
currentControlRateProfile->rcExpo[FD_PITCH] = sbufReadU8(src);
}
initRcProcessing();
} else {
return MSP_RESULT_ERROR;
}

View File

@ -284,6 +284,10 @@ static const char * const lookupTableGyroOverflowCheck[] = {
};
#endif
static const char * const lookupTableRatesType[] = {
"BETAFLIGHT", "RACEFLIGHT"
};
const lookupTableEntry_t lookupTables[] = {
{ lookupTableOffOn, sizeof(lookupTableOffOn) / sizeof(char *) },
{ lookupTableUnit, sizeof(lookupTableUnit) / sizeof(char *) },
@ -340,6 +344,7 @@ const lookupTableEntry_t lookupTables[] = {
#ifdef USE_GYRO_OVERFLOW_CHECK
{ lookupTableGyroOverflowCheck, sizeof(lookupTableGyroOverflowCheck) / sizeof(char *) },
#endif
{ lookupTableRatesType, sizeof(lookupTableRatesType) / sizeof(char *) },
};
const clivalue_t valueTable[] = {
@ -549,15 +554,18 @@ const clivalue_t valueTable[] = {
#endif
// PG_CONTROLRATE_PROFILES
{ "rc_rate", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 255 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcRate8) },
{ "rc_rate_yaw", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 255 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcYawRate8) },
{ "rc_expo", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 100 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcExpo8) },
{ "rc_expo_yaw", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 100 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcYawExpo8) },
{ "thr_mid", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 100 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, thrMid8) },
{ "thr_expo", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 100 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, thrExpo8) },
{ "roll_srate", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rates[FD_ROLL]) },
{ "pitch_srate", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rates[FD_PITCH]) },
{ "yaw_srate", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rates[FD_YAW]) },
{ "rates_type", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RATES_TYPE }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rates_type) },
{ "roll_rc_rate", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, CONTROL_RATE_CONFIG_RC_RATES_MAX }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcRates[FD_ROLL]) },
{ "pitch_rc_rate", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, CONTROL_RATE_CONFIG_RC_RATES_MAX }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcRates[FD_PITCH]) },
{ "yaw_rc_rate", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, CONTROL_RATE_CONFIG_RC_RATES_MAX }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcRates[FD_YAW]) },
{ "roll_expo", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, CONTROL_RATE_CONFIG_RC_EXPO_MAX }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcExpo[FD_ROLL]) },
{ "pitch_expo", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, CONTROL_RATE_CONFIG_RC_EXPO_MAX }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcExpo[FD_PITCH]) },
{ "yaw_expo", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, CONTROL_RATE_CONFIG_RC_EXPO_MAX }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcExpo[FD_YAW]) },
{ "roll_srate", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, CONTROL_RATE_CONFIG_RATE_MAX }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rates[FD_ROLL]) },
{ "pitch_srate", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, CONTROL_RATE_CONFIG_RATE_MAX }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rates[FD_PITCH]) },
{ "yaw_srate", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, CONTROL_RATE_CONFIG_RATE_MAX }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rates[FD_YAW]) },
{ "tpa_rate", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, CONTROL_RATE_CONFIG_TPA_MAX}, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, dynThrPID) },
{ "tpa_breakpoint", VAR_UINT16 | PROFILE_RATE_VALUE, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, tpa_breakpoint) },

View File

@ -78,6 +78,7 @@ typedef enum {
#ifdef USE_GYRO_OVERFLOW_CHECK
TABLE_GYRO_OVERFLOW_CHECK,
#endif
TABLE_RATES_TYPE,
LOOKUP_TABLE_COUNT
} lookupTableIndex_e;

View File

@ -325,9 +325,19 @@ static void showProfilePage(void)
i2c_OLED_send_string(bus, lineBuffer);
const controlRateConfig_t *controlRateConfig = controlRateProfiles(currentRateProfileIndex);
tfp_sprintf(lineBuffer, "RCE: %d, RCR: %d",
controlRateConfig->rcExpo8,
controlRateConfig->rcRate8
tfp_sprintf(lineBuffer, "RRr:%d PRR:%d YRR:%d",
controlRateConfig->rcRates[FD_ROLL],
controlRateConfig->rcRates[FD_PITCH],
controlRateConfig->rcRates[FD_YAW]
);
padLineBuffer();
i2c_OLED_set_line(bus, rowIndex++);
i2c_OLED_send_string(bus, lineBuffer);
tfp_sprintf(lineBuffer, "RE:%d PE:%d YE:%d",
controlRateConfig->rcExpo[FD_ROLL],
controlRateConfig->rcExpo[FD_PITCH],
controlRateConfig->rcExpo[FD_YAW]
);
padLineBuffer();
i2c_OLED_set_line(bus, rowIndex++);

View File

@ -130,9 +130,11 @@ void targetConfiguration(void)
controlRateConfig_t *controlRateConfig = controlRateProfilesMutable(rateProfileIndex);
/* RC Rates */
controlRateConfig->rcRate8 = 100;
controlRateConfig->rcYawRate8 = 100;
controlRateConfig->rcExpo8 = 0;
controlRateConfig->rcRates[FD_ROLL] = 100;
controlRateConfig->rcRates[FD_PITCH] = 100;
controlRateConfig->rcRates[FD_YAW] = 100;
controlRateConfig->rcExpo[FD_ROLL] = 0;
controlRateConfig->rcExpo[FD_PITCH] = 0;
/* Super Expo Rates */
controlRateConfig->rates[FD_ROLL] = 80;

View File

@ -85,9 +85,10 @@ void targetConfiguration(void)
for (uint8_t rateProfileIndex = 0; rateProfileIndex < CONTROL_RATE_PROFILE_COUNT; rateProfileIndex++) {
controlRateConfig_t *controlRateConfig = controlRateProfilesMutable(rateProfileIndex);
controlRateConfig->rcYawRate8 = 120;
controlRateConfig->rcExpo8 = 15;
controlRateConfig->rcYawExpo8 = 15;
controlRateConfig->rcRates[FD_YAW] = 120;
controlRateConfig->rcExpo[FD_ROLL] = 15;
controlRateConfig->rcExpo[FD_PITCH] = 15;
controlRateConfig->rcExpo[FD_YAW] = 15;
controlRateConfig->rates[FD_ROLL] = 85;
controlRateConfig->rates[FD_PITCH] = 85;
}

View File

@ -332,8 +332,8 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
bstWrite16(getTaskDeltaTime(TASK_GYROPID));
break;
case BST_RC_TUNING:
bstWrite8(currentControlRateProfile->rcRate8);
bstWrite8(currentControlRateProfile->rcExpo8);
bstWrite8(currentControlRateProfile->rcRates[FD_ROLL]);
bstWrite8(currentControlRateProfile->rcExpo[FD_ROLL]);
for (i = 0 ; i < 3; i++) {
bstWrite8(currentControlRateProfile->rates[i]); // R,P,Y see flight_dynamics_index_t
}
@ -341,8 +341,8 @@ static bool bstSlaveProcessFeedbackCommand(uint8_t bstRequest)
bstWrite8(currentControlRateProfile->thrMid8);
bstWrite8(currentControlRateProfile->thrExpo8);
bstWrite16(currentControlRateProfile->tpa_breakpoint);
bstWrite8(currentControlRateProfile->rcYawExpo8);
bstWrite8(currentControlRateProfile->rcYawRate8);
bstWrite8(currentControlRateProfile->rcExpo[FD_YAW]);
bstWrite8(currentControlRateProfile->rcRates[FD_YAW]);
break;
case BST_PID:
for (i = 0; i < PID_ITEM_COUNT; i++) {

View File

@ -80,10 +80,12 @@ void targetConfiguration(void)
for (uint8_t rateProfileIndex = 0; rateProfileIndex < CONTROL_RATE_PROFILE_COUNT; rateProfileIndex++) {
controlRateConfig_t *controlRateConfig = controlRateProfilesMutable(rateProfileIndex);
controlRateConfig->rcRate8 = 100;
controlRateConfig->rcYawRate8 = 100;
controlRateConfig->rcExpo8 = 15;
controlRateConfig->rcYawExpo8 = 15;
controlRateConfig->rcRates[FD_ROLL] = 100;
controlRateConfig->rcRates[FD_PITCH] = 100;
controlRateConfig->rcRates[FD_YAW] = 100;
controlRateConfig->rcExpo[FD_ROLL] = 15;
controlRateConfig->rcExpo[FD_PITCH] = 15;
controlRateConfig->rcExpo[FD_YAW] = 15;
controlRateConfig->rates[PID_ROLL] = 80;
controlRateConfig->rates[PID_PITCH] = 80;
controlRateConfig->rates[PID_YAW] = 80;

View File

@ -92,7 +92,8 @@ void targetConfiguration(void)
for (uint8_t rateProfileIndex = 0; rateProfileIndex < CONTROL_RATE_PROFILE_COUNT; rateProfileIndex++) {
controlRateConfig_t *controlRateConfig = controlRateProfilesMutable(rateProfileIndex);
controlRateConfig->rcRate8 = 70;
controlRateConfig->rcRates[FD_ROLL] = 70;
controlRateConfig->rcRates[FD_PITCH] = 70;
}
}
#endif

View File

@ -85,9 +85,11 @@ void targetConfiguration(void)
for (uint8_t rateProfileIndex = 0; rateProfileIndex < CONTROL_RATE_PROFILE_COUNT; rateProfileIndex++) {
controlRateConfig_t *controlRateConfig = controlRateProfilesMutable(rateProfileIndex);
controlRateConfig->rcRate8 = 100;
controlRateConfig->rcYawRate8 = 110;
controlRateConfig->rcExpo8 = 0;
controlRateConfig->rcRates[FD_ROLL] = 100;
controlRateConfig->rcRates[FD_PITCH] = 100;
controlRateConfig->rcRate[FD_YAW] = 110;
controlRateConfig->rcExpo[FD_ROLL] = 0;
controlRateConfig->rcExpo[FD_PITCH] = 0;
controlRateConfig->rates[FD_ROLL] = 77;
controlRateConfig->rates[FD_PITCH] = 77;
controlRateConfig->rates[FD_YAW] = 80;

View File

@ -241,13 +241,15 @@ extern "C" {
class RcControlsAdjustmentsTest : public ::testing::Test {
protected:
controlRateConfig_t controlRateConfig = {
.rcRate8 = 90,
.rcExpo8 = 0,
.rcRates[FD_ROLL] = 90,
.rcRates[FD_PITCH] = 90,
.rcExpo[FD_ROLL] = 0,
.rcExpo[FD_PITCH] = 0,
.thrMid8 = 0,
.thrExpo8 = 0,
.rates = {0, 0, 0},
.dynThrPID = 0,
.rcYawExpo8 = 0,
.rcExpo[FD_YAW] = 0,
.tpa_breakpoint = 0
};
@ -260,11 +262,13 @@ protected:
rxConfigMutable()->maxcheck = DEFAULT_MAX_CHECK;
rxConfigMutable()->midrc = 1500;
controlRateConfig.rcRate8 = 90;
controlRateConfig.rcExpo8 = 0;
controlRateConfig.rcRates[FD_ROLL] = 90;
controlRateConfig.rcRates[FD_PITCH] = 90;
controlRateConfig.rcExpo[FD_ROLL] = 0;
controlRateConfig.rcExpo[FD_PITCH] = 0;
controlRateConfig.thrMid8 = 0;
controlRateConfig.thrExpo8 = 0;
controlRateConfig.rcYawExpo8 = 0;
controlRateConfig.rcExpo[FD_YAW] = 0;
controlRateConfig.rates[0] = 0;
controlRateConfig.rates[1] = 0;
controlRateConfig.rates[2] = 0;
@ -292,7 +296,8 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsSticksInMiddle)
processRcAdjustments(&controlRateConfig);
// then
EXPECT_EQ(controlRateConfig.rcRate8, 90);
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);
}
@ -301,13 +306,15 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
{
// given
controlRateConfig_t controlRateConfig = {
.rcRate8 = 90,
.rcExpo8 = 0,
.rcRates[FD_ROLL] = 90,
.rcRates[FD_PITCH] = 90,
.rcExpo[FD_ROLL] = 0,
.rcExpo[FD_PITCH] = 0,
.thrMid8 = 0,
.thrExpo8 = 0,
.rates = {0,0,0},
.dynThrPID = 0,
.rcYawExpo8 = 0,
.rcExpo[FD_YAW] = 0,
.tpa_breakpoint = 0
};
@ -345,7 +352,8 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
processRcAdjustments(&controlRateConfig);
// then
EXPECT_EQ(controlRateConfig.rcRate8, 91);
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);
@ -359,7 +367,8 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
// when
processRcAdjustments(&controlRateConfig);
EXPECT_EQ(controlRateConfig.rcRate8, 91);
EXPECT_EQ(controlRateConfig.rcRates[FD_ROLL], 91);
EXPECT_EQ(controlRateConfig.rcRates[FD_PITCH], 91);
EXPECT_EQ(adjustmentStateMask, expectedAdjustmentStateMask);
@ -381,7 +390,8 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
// when
processRcAdjustments(&controlRateConfig);
EXPECT_EQ(controlRateConfig.rcRate8, 91);
EXPECT_EQ(controlRateConfig.rcRates[FD_ROLL], 91);
EXPECT_EQ(controlRateConfig.rcRates[FD_PITCH], 91);
EXPECT_EQ(adjustmentStateMask, expectedAdjustmentStateMask);
@ -402,7 +412,8 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
processRcAdjustments(&controlRateConfig);
// then
EXPECT_EQ(controlRateConfig.rcRate8, 92);
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);
@ -418,7 +429,8 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
processRcAdjustments(&controlRateConfig);
// then
EXPECT_EQ(controlRateConfig.rcRate8, 92);
EXPECT_EQ(controlRateConfig.rcRates[FD_ROLL], 92);
EXPECT_EQ(controlRateConfig.rcRates[FD_PITCH], 92);
EXPECT_EQ(adjustmentStateMask, expectedAdjustmentStateMask);
//
@ -432,7 +444,8 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
processRcAdjustments(&controlRateConfig);
// then
EXPECT_EQ(controlRateConfig.rcRate8, 92);
EXPECT_EQ(controlRateConfig.rcRates[FD_ROLL], 92);
EXPECT_EQ(controlRateConfig.rcRates[FD_PITCH], 92);
EXPECT_EQ(adjustmentStateMask, expectedAdjustmentStateMask);
//
@ -448,7 +461,8 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
processRcAdjustments(&controlRateConfig);
// then
EXPECT_EQ(controlRateConfig.rcRate8, 93);
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);
}
@ -673,7 +687,7 @@ TEST_F(RcControlsAdjustmentsTest, processPIDIncreasePidController2)
extern "C" {
void saveConfigAndNotify(void) {}
void generateThrottleCurve(void) {}
void initRcProcessing(void) {}
void changePidProfile(uint8_t) {}
void pidInitConfig(const pidProfile_t *) {}
void accSetCalibrationCycles(uint16_t) {}