mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-14 03:49:58 +03:00
rc_rate setting removed
This commit is contained in:
parent
7eb2419ef9
commit
0f19dcc70f
9 changed files with 9 additions and 32 deletions
|
@ -187,7 +187,6 @@ Re-apply any new defaults as desired.
|
|||
| `yaw_motor_direction` | | -1 | 1 | 1 | Profile | INT8 |
|
||||
| `tri_unarmed_servo` | On tricopter mix only, if this is set to 1, servo will always be correcting regardless of armed state. to disable this, set it to 0. | OFF | ON | ON | Profile | INT8 |
|
||||
| `default_rate_profile` | Default = profile number | 0 | 2 | | Profile | UINT8 |
|
||||
| `rc_rate` | | 0 | 250 | 90 | Rate Profile | UINT8 |
|
||||
| `rc_expo` | | 0 | 100 | 65 | Rate Profile | UINT8 |
|
||||
| `rc_yaw_expo` | | 0 | 100 | 0 | Rate Profile | UINT8 |
|
||||
| `thr_mid` | | 0 | 100 | 50 | Rate Profile | UINT8 |
|
||||
|
|
|
@ -31,7 +31,7 @@ Three rate profiles are supported.
|
|||
Rate profiles can be selected while flying using the inflight adjustments feature.
|
||||
|
||||
Each normal profile has a setting called 'default_rate_profile`. When a profile is activated the
|
||||
corresponding rate profile is also activated.
|
||||
corresponding rate profile is also activated.
|
||||
|
||||
Profile 0 has a default rate profile of 0.
|
||||
Profile 1 has a default rate profile of 1.
|
||||
|
@ -54,7 +54,6 @@ e.g
|
|||
# rateprofile
|
||||
rateprofile 0
|
||||
|
||||
set rc_rate = 90
|
||||
set rc_expo = 65
|
||||
set thr_mid = 50
|
||||
set thr_expo = 0
|
||||
|
|
|
@ -685,7 +685,7 @@ static void writeInterframe(void)
|
|||
arraySubInt32(deltas, blackboxCurrent->axisPID_P, blackboxLast->axisPID_P, XYZ_AXIS_COUNT);
|
||||
blackboxWriteSignedVBArray(deltas, XYZ_AXIS_COUNT);
|
||||
|
||||
/*
|
||||
/*
|
||||
* The PID I field changes very slowly, most of the time +-2, so use an encoding
|
||||
* that can pack all three fields into one byte in that situation.
|
||||
*/
|
||||
|
@ -920,7 +920,7 @@ void startBlackbox(void)
|
|||
* cache those now.
|
||||
*/
|
||||
blackboxBuildConditionCache();
|
||||
|
||||
|
||||
blackboxModeActivationConditionPresent = isModeActivationConditionPresent(currentProfile->modeActivationConditions, BOXBLACKBOX);
|
||||
|
||||
blackboxIteration = 0;
|
||||
|
@ -1228,7 +1228,7 @@ static bool blackboxWriteSysinfo()
|
|||
blackboxPrintfHeaderLine("P interval:%d/%d", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
|
||||
break;
|
||||
case 4:
|
||||
blackboxPrintfHeaderLine("rcRate:%d", masterConfig.controlRateProfiles[masterConfig.current_profile_index].rcRate8);
|
||||
blackboxPrintfHeaderLine("rcRate:%d", 100); //For compatibility reasons write rc_rate 100
|
||||
break;
|
||||
case 5:
|
||||
blackboxPrintfHeaderLine("minthrottle:%d", masterConfig.escAndServoConfig.minthrottle);
|
||||
|
@ -1323,7 +1323,7 @@ static void blackboxCheckAndLogArmingBeep()
|
|||
}
|
||||
}
|
||||
|
||||
/*
|
||||
/*
|
||||
* Use the user's num/denom settings to decide if the P-frame of the given index should be logged, allowing the user to control
|
||||
* the portion of logged loop iterations.
|
||||
*/
|
||||
|
@ -1367,7 +1367,7 @@ static void blackboxLogIteration()
|
|||
writeIntraframe();
|
||||
} else {
|
||||
blackboxCheckAndLogArmingBeep();
|
||||
|
||||
|
||||
if (blackboxShouldLogPFrame(blackboxPFrameIndex)) {
|
||||
/*
|
||||
* We assume that slow frames are only interesting in that they aid the interpretation of the main data stream.
|
||||
|
@ -1499,7 +1499,7 @@ void handleBlackbox(void)
|
|||
|
||||
blackboxLogEvent(FLIGHT_LOG_EVENT_LOGGING_RESUME, (flightLogEventData_t *) &resume);
|
||||
blackboxSetState(BLACKBOX_STATE_RUNNING);
|
||||
|
||||
|
||||
blackboxLogIteration();
|
||||
}
|
||||
|
||||
|
|
|
@ -353,7 +353,6 @@ void resetSerialConfig(serialConfig_t *serialConfig)
|
|||
}
|
||||
|
||||
static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) {
|
||||
controlRateConfig->rcRate8 = 90;
|
||||
controlRateConfig->rcExpo8 = 70;
|
||||
controlRateConfig->thrMid8 = 50;
|
||||
controlRateConfig->thrExpo8 = 0;
|
||||
|
@ -628,7 +627,6 @@ static void resetConf(void)
|
|||
currentProfile->pidProfile.P8[PITCH] = 36;
|
||||
masterConfig.failsafeConfig.failsafe_delay = 2;
|
||||
masterConfig.failsafeConfig.failsafe_off_delay = 0;
|
||||
currentControlRateProfile->rcRate8 = 130;
|
||||
currentControlRateProfile->rates[FD_PITCH] = CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_DEFAULT;
|
||||
currentControlRateProfile->rates[FD_ROLL] = CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_DEFAULT;
|
||||
currentControlRateProfile->rates[FD_YAW] = CONTROL_RATE_CONFIG_YAW_RATE_DEFAULT;
|
||||
|
|
|
@ -456,12 +456,6 @@ void applyStepAdjustment(controlRateConfig_t *controlRateConfig, uint8_t adjustm
|
|||
beeperConfirmationBeeps(1);
|
||||
}
|
||||
switch(adjustmentFunction) {
|
||||
case ADJUSTMENT_RC_RATE:
|
||||
newValue = constrain((int)controlRateConfig->rcRate8 + delta, 0, 250); // FIXME magic numbers repeated in serial_cli.c
|
||||
controlRateConfig->rcRate8 = newValue;
|
||||
generateRcCurves(controlRateConfig);
|
||||
blackboxLogInflightAdjustmentEvent(ADJUSTMENT_RC_RATE, newValue);
|
||||
break;
|
||||
case ADJUSTMENT_RC_EXPO:
|
||||
newValue = constrain((int)controlRateConfig->rcExpo8 + delta, 0, 100); // FIXME magic numbers repeated in serial_cli.c
|
||||
controlRateConfig->rcExpo8 = newValue;
|
||||
|
|
|
@ -138,7 +138,6 @@ typedef struct modeActivationCondition_s {
|
|||
#define IS_RANGE_USABLE(range) ((range)->startStep < (range)->endStep)
|
||||
|
||||
typedef struct controlRateConfig_s {
|
||||
uint8_t rcRate8;
|
||||
uint8_t rcExpo8;
|
||||
uint8_t thrMid8;
|
||||
uint8_t thrExpo8;
|
||||
|
|
|
@ -670,7 +670,6 @@ const clivalue_t valueTable[] = {
|
|||
#endif
|
||||
|
||||
{ "default_rate_profile", VAR_UINT8 | PROFILE_VALUE , &masterConfig.profile[0].defaultRateProfileIndex, .config.minmax = { 0, MAX_CONTROL_RATE_PROFILE_COUNT - 1 }, 0 },
|
||||
{ "rc_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcRate8, .config.minmax = { 0, 250 }, 0 },
|
||||
{ "rc_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcExpo8, .config.minmax = { 0, 100 }, 0 },
|
||||
{ "rc_yaw_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcYawExpo8, .config.minmax = { 0, 100 }, 0 },
|
||||
{ "thr_mid", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].thrMid8, .config.minmax = { 0, 100 }, 0 },
|
||||
|
|
|
@ -732,7 +732,7 @@ static bool processOutCommand(uint8_t cmdMSP)
|
|||
break;
|
||||
case MSP_RC_TUNING:
|
||||
headSerialReply(11);
|
||||
serialize8(currentControlRateProfile->rcRate8);
|
||||
serialize8(100); //rcRate8 kept for compatibity reasons, this setting is no longer used
|
||||
serialize8(currentControlRateProfile->rcExpo8);
|
||||
for (i = 0 ; i < 3; i++) {
|
||||
serialize8(currentControlRateProfile->rates[i]); // R,P,Y see flight_dynamics_index_t
|
||||
|
@ -1215,7 +1215,7 @@ static bool processInCommand(void)
|
|||
|
||||
case MSP_SET_RC_TUNING:
|
||||
if (currentPort->dataSize >= 10) {
|
||||
currentControlRateProfile->rcRate8 = read8();
|
||||
read8(); //Read rcRate8, kept for protocol compatibility reasons
|
||||
currentControlRateProfile->rcExpo8 = read8();
|
||||
for (i = 0; i < 3; i++) {
|
||||
rate = read8();
|
||||
|
|
|
@ -237,7 +237,6 @@ static const adjustmentConfig_t rateAdjustmentConfig = {
|
|||
class RcControlsAdjustmentsTest : public ::testing::Test {
|
||||
protected:
|
||||
controlRateConfig_t controlRateConfig = {
|
||||
.rcRate8 = 90,
|
||||
.rcExpo8 = 0,
|
||||
.thrMid8 = 0,
|
||||
.thrExpo8 = 0,
|
||||
|
@ -256,7 +255,6 @@ protected:
|
|||
rxConfig.maxcheck = DEFAULT_MAX_CHECK;
|
||||
rxConfig.midrc = 1500;
|
||||
|
||||
controlRateConfig.rcRate8 = 90;
|
||||
controlRateConfig.rcExpo8 = 0;
|
||||
controlRateConfig.thrMid8 = 0;
|
||||
controlRateConfig.thrExpo8 = 0;
|
||||
|
@ -289,7 +287,6 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsSticksInMiddle)
|
|||
processRcAdjustments(&controlRateConfig, &rxConfig);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(controlRateConfig.rcRate8, 90);
|
||||
EXPECT_EQ(CALL_COUNTER(COUNTER_GENERATE_PITCH_ROLL_CURVE), 0);
|
||||
EXPECT_EQ(CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP), 0);
|
||||
EXPECT_EQ(adjustmentStateMask, 0);
|
||||
|
@ -299,7 +296,6 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
|
|||
{
|
||||
// given
|
||||
controlRateConfig_t controlRateConfig = {
|
||||
.rcRate8 = 90,
|
||||
.rcExpo8 = 0,
|
||||
.thrMid8 = 0,
|
||||
.thrExpo8 = 0,
|
||||
|
@ -344,7 +340,6 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
|
|||
processRcAdjustments(&controlRateConfig, &rxConfig);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(controlRateConfig.rcRate8, 91);
|
||||
EXPECT_EQ(CALL_COUNTER(COUNTER_GENERATE_PITCH_ROLL_CURVE), 1);
|
||||
EXPECT_EQ(CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP), 1);
|
||||
EXPECT_EQ(adjustmentStateMask, expectedAdjustmentStateMask);
|
||||
|
@ -360,7 +355,6 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
|
|||
// when
|
||||
processRcAdjustments(&controlRateConfig, &rxConfig);
|
||||
|
||||
EXPECT_EQ(controlRateConfig.rcRate8, 91);
|
||||
EXPECT_EQ(adjustmentStateMask, expectedAdjustmentStateMask);
|
||||
|
||||
|
||||
|
@ -382,7 +376,6 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
|
|||
// when
|
||||
processRcAdjustments(&controlRateConfig, &rxConfig);
|
||||
|
||||
EXPECT_EQ(controlRateConfig.rcRate8, 91);
|
||||
EXPECT_EQ(adjustmentStateMask, expectedAdjustmentStateMask);
|
||||
|
||||
|
||||
|
@ -403,7 +396,6 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
|
|||
processRcAdjustments(&controlRateConfig, &rxConfig);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(controlRateConfig.rcRate8, 92);
|
||||
EXPECT_EQ(CALL_COUNTER(COUNTER_GENERATE_PITCH_ROLL_CURVE), 2);
|
||||
EXPECT_EQ(CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP), 2);
|
||||
EXPECT_EQ(adjustmentStateMask, expectedAdjustmentStateMask);
|
||||
|
@ -420,7 +412,6 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
|
|||
processRcAdjustments(&controlRateConfig, &rxConfig);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(controlRateConfig.rcRate8, 92);
|
||||
EXPECT_EQ(adjustmentStateMask, expectedAdjustmentStateMask);
|
||||
|
||||
//
|
||||
|
@ -434,7 +425,6 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
|
|||
processRcAdjustments(&controlRateConfig, &rxConfig);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(controlRateConfig.rcRate8, 92);
|
||||
EXPECT_EQ(adjustmentStateMask, expectedAdjustmentStateMask);
|
||||
|
||||
//
|
||||
|
@ -450,7 +440,6 @@ TEST_F(RcControlsAdjustmentsTest, processRcAdjustmentsWithRcRateFunctionSwitchUp
|
|||
processRcAdjustments(&controlRateConfig, &rxConfig);
|
||||
|
||||
// then
|
||||
EXPECT_EQ(controlRateConfig.rcRate8, 93);
|
||||
EXPECT_EQ(CALL_COUNTER(COUNTER_GENERATE_PITCH_ROLL_CURVE), 3);
|
||||
EXPECT_EQ(CALL_COUNTER(COUNTER_QUEUE_CONFIRMATION_BEEP), 3);
|
||||
EXPECT_EQ(adjustmentStateMask, expectedAdjustmentStateMask);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue