mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-20 06:45:16 +03:00
Decouple sensor alignment from all acc/gyro/mag drivers.
This resulted in the removal of duplicate logic, duplicate code and the removal of a temporary buffer per-driver. The NAZE specific sensor alignment is now contained within the core code instead of in the drivers. The sensor alignment is determines by the sensor initialisation code. The alignment of sensor readings is now performed once and only by the appropriate sensor code, see usages of alignSensors(). The acc/gyro/compass driver code is now more reusable since it has no dependencies on the main code.
This commit is contained in:
parent
0f3e4add48
commit
297609d4c3
18 changed files with 124 additions and 185 deletions
|
@ -8,6 +8,7 @@
|
|||
|
||||
acc_t acc; // acc access functions
|
||||
uint8_t accHardware = ACC_DEFAULT; // which accel chip is used/detected
|
||||
sensor_align_e accAlign = 0;
|
||||
|
||||
uint16_t calibratingA = 0; // the calibration is done is the main loop. Calibrating decreases at each cycle down to 0, then we enter in a normal mode.
|
||||
|
||||
|
@ -106,6 +107,8 @@ void ACC_Common(void)
|
|||
void ACC_getADC(void)
|
||||
{
|
||||
acc.read(accADC);
|
||||
alignSensors(accADC, accADC, accAlign);
|
||||
|
||||
ACC_Common();
|
||||
}
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue