mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 08:45:36 +03:00
Change ACC Trim step to 1 (for stick commands)
This commit is contained in:
parent
1a6fa4ddbd
commit
8ff89b5ed0
1 changed files with 4 additions and 4 deletions
|
@ -316,19 +316,19 @@ void processRcStickPositions()
|
|||
bool shouldApplyRollAndPitchTrimDelta = false;
|
||||
switch (rcSticks) {
|
||||
case THR_HI + YAW_CE + PIT_HI + ROL_CE:
|
||||
accelerometerTrimsDelta.values.pitch = 2;
|
||||
accelerometerTrimsDelta.values.pitch = 1;
|
||||
shouldApplyRollAndPitchTrimDelta = true;
|
||||
break;
|
||||
case THR_HI + YAW_CE + PIT_LO + ROL_CE:
|
||||
accelerometerTrimsDelta.values.pitch = -2;
|
||||
accelerometerTrimsDelta.values.pitch = -1;
|
||||
shouldApplyRollAndPitchTrimDelta = true;
|
||||
break;
|
||||
case THR_HI + YAW_CE + PIT_CE + ROL_HI:
|
||||
accelerometerTrimsDelta.values.roll = 2;
|
||||
accelerometerTrimsDelta.values.roll = 1;
|
||||
shouldApplyRollAndPitchTrimDelta = true;
|
||||
break;
|
||||
case THR_HI + YAW_CE + PIT_CE + ROL_LO:
|
||||
accelerometerTrimsDelta.values.roll = -2;
|
||||
accelerometerTrimsDelta.values.roll = -1;
|
||||
shouldApplyRollAndPitchTrimDelta = true;
|
||||
break;
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue