mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-17 13:25:30 +03:00
update some comment typos in sensors/acceleration.c
This commit is contained in:
parent
a2a9443045
commit
a92b148557
1 changed files with 4 additions and 5 deletions
|
@ -130,8 +130,8 @@ void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTri
|
||||||
if (InflightcalibratingA == 1) {
|
if (InflightcalibratingA == 1) {
|
||||||
AccInflightCalibrationActive = false;
|
AccInflightCalibrationActive = false;
|
||||||
AccInflightCalibrationMeasurementDone = true;
|
AccInflightCalibrationMeasurementDone = true;
|
||||||
queueConfirmationBeep(2); // beeper to indicatiing the end of calibration
|
queueConfirmationBeep(2); // beeper to indicating the end of calibration
|
||||||
// recover saved values to maintain current flight behavior until new values are transferred
|
// recover saved values to maintain current flight behaviour until new values are transferred
|
||||||
accelerationTrims->raw[FD_ROLL] = accZero_saved[FD_ROLL];
|
accelerationTrims->raw[FD_ROLL] = accZero_saved[FD_ROLL];
|
||||||
accelerationTrims->raw[FD_PITCH] = accZero_saved[FD_PITCH];
|
accelerationTrims->raw[FD_PITCH] = accZero_saved[FD_PITCH];
|
||||||
accelerationTrims->raw[FD_YAW] = accZero_saved[FD_YAW];
|
accelerationTrims->raw[FD_YAW] = accZero_saved[FD_YAW];
|
||||||
|
@ -141,17 +141,16 @@ void performInflightAccelerationCalibration(rollAndPitchTrims_t *rollAndPitchTri
|
||||||
InflightcalibratingA--;
|
InflightcalibratingA--;
|
||||||
}
|
}
|
||||||
// Calculate average, shift Z down by acc_1G and store values in EEPROM at end of calibration
|
// Calculate average, shift Z down by acc_1G and store values in EEPROM at end of calibration
|
||||||
if (AccInflightCalibrationSavetoEEProm) { // the copter is landed, disarmed and the combo has been done again
|
if (AccInflightCalibrationSavetoEEProm) { // the aircraft is landed, disarmed and the combo has been done again
|
||||||
AccInflightCalibrationSavetoEEProm = false;
|
AccInflightCalibrationSavetoEEProm = false;
|
||||||
accelerationTrims->raw[FD_ROLL] = b[FD_ROLL] / 50;
|
accelerationTrims->raw[FD_ROLL] = b[FD_ROLL] / 50;
|
||||||
accelerationTrims->raw[FD_PITCH] = b[FD_PITCH] / 50;
|
accelerationTrims->raw[FD_PITCH] = b[FD_PITCH] / 50;
|
||||||
accelerationTrims->raw[FD_YAW] = b[FD_YAW] / 50 - acc_1G; // for nunchuk 200=1G
|
accelerationTrims->raw[FD_YAW] = b[FD_YAW] / 50 - acc_1G; // for nunchuck 200=1G
|
||||||
|
|
||||||
resetRollAndPitchTrims(rollAndPitchTrims);
|
resetRollAndPitchTrims(rollAndPitchTrims);
|
||||||
|
|
||||||
saveConfigAndNotify();
|
saveConfigAndNotify();
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void applyAccelerationTrims(flightDynamicsTrims_t *accelerationTrims)
|
void applyAccelerationTrims(flightDynamicsTrims_t *accelerationTrims)
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue