1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 16:55:36 +03:00

added ability to swap sensor axises dynamically. still needs a sane way to configire in CLI, though.

adjusted all drivers for the new align stuff.
commented out default config setting values to zero - memset already did that.


git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@227 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
timecop@gmail.com 2012-10-07 18:03:42 +00:00
parent 193902079c
commit 021b486916
8 changed files with 3184 additions and 3144 deletions

View file

@ -113,6 +113,12 @@ typedef struct mixer_t {
const motorMixer_t *motor;
} mixer_t;
enum {
ALIGN_GYRO = 0,
ALIGN_ACCEL = 1,
ALIGN_MAG = 2
};
typedef struct config_t {
uint8_t version;
uint16_t size;
@ -141,11 +147,12 @@ typedef struct config_t {
int16_t angleTrim[2]; // accelerometer trim
// sensor-related stuff
int8_t align[3][3]; // acc, gyro, mag alignment (ex: with sensor output of X, Y, Z, align of 1 -3 2 would return X, -Z, Y)
uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device
uint8_t acc_lpf_factor; // Set the Low Pass Filter factor for ACC. Increasing this value would reduce ACC noise (visible in GUI), but would increase ACC lag time. Zero = no filter
uint8_t acc_lpf_for_velocity; // ACC lowpass for AccZ height hold
uint8_t accz_deadband; // ??
uint16_t gyro_lpf; // mpuX050 LPF setting
uint16_t gyro_lpf; // mpuX050 LPF setting (TODO make it work on L3GD as well)
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.
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 mpu6050_scale; // seems es/non-es variance between MPU6050 sensors, half my boards are mpu6000ES, need this to be dynamic. fucking invenshit won't release chip IDs so I can't autodetect it.