mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 21:05:35 +03:00
some more minor updates from 2.2
added variable for gyro_cmpfm factor (mag) to configurables changed gyro_cmpf factor to 600 (higher gyro influence) got rid of GYRO_INTERLEAVE stuff (didn't work, obsolete) got rid of applyDeadband hacks, invsqrt hacks, and other shit. ifdef'd original baseflight attitude/heading calcs w/new 2.2 routines fixed cockup in altitude calculation w/applyDeadband remaining: GPS git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@304 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
f2c7ad585a
commit
c26603dd72
6 changed files with 3911 additions and 3334 deletions
1
src/mw.h
1
src/mw.h
|
@ -245,6 +245,7 @@ typedef struct master_t {
|
|||
uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device
|
||||
uint16_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen.
|
||||
uint16_t gyro_cmpf_factor; // Set the Gyro Weight for Gyro/Acc complementary filter. Increasing this value would reduce and delay Acc influence on the output of the filter.
|
||||
uint16_t gyro_cmpfm_factor; // Set the Gyro Weight for Gyro/Magnetometer complementary filter. Increasing this value would reduce and delay Magnetometer influence on the output of the filter
|
||||
uint32_t gyro_smoothing_factor; // How much to smoothen with per axis (32bit value with Roll, Pitch, Yaw in bits 24, 16, 8 respectively
|
||||
uint8_t moron_threshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default.
|
||||
uint8_t mpu6050_scale; // es/non-es variance between MPU6050 sensors, half my boards are mpu6000ES, need this to be dynamic. automatically set by mpu6050 driver.
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue