Whitespace/compiler warnings cleanups by Dominic Clifton;

Slight tweak of new althold defaults
NOT-flight-tested .hex committing so people can commence with althold testing.

git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@391 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
timecop@gmail.com 2013-08-31 01:40:13 +00:00
parent 77a241bd5f
commit 509e349e69
11 changed files with 3312 additions and 3231 deletions

File diff suppressed because it is too large Load Diff

View File

@ -192,6 +192,7 @@ typedef struct baro_t
// OLIMEXINO
#include "drv_adc.h"
#include "drv_i2c.h"
#include "drv_spi.h"
#include "drv_adxl345.h"
#include "drv_mpu3050.h"
#include "drv_mpu6050.h"

View File

@ -33,7 +33,7 @@ static float _atof(const char *p);
static char *ftoa(float x, char *floatString);
// sync this with MultiType enum from mw.h
const char * const mixerNames[] = {
static const char * const mixerNames[] = {
"TRI", "QUADP", "QUADX", "BI",
"GIMBAL", "Y6", "HEX6",
"FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX",
@ -41,7 +41,7 @@ const char * const mixerNames[] = {
};
// sync this with AvailableFeatures enum from board.h
const char * const featureNames[] = {
static const char * const featureNames[] = {
"PPM", "VBAT", "INFLIGHT_ACC_CAL", "SPEKTRUM", "MOTOR_STOP",
"SERVO_TILT", "GYRO_SMOOTHING", "LED_RING", "GPS",
"FAILSAFE", "SONAR", "TELEMETRY", "POWERMETER", "VARIO", "3D",
@ -49,17 +49,17 @@ const char * const featureNames[] = {
};
// sync this with AvailableSensors enum from board.h
const char * const sensorNames[] = {
static const char * const sensorNames[] = {
"ACC", "BARO", "MAG", "SONAR", "GPS", NULL
};
const char * const accNames[] = {
static const char * const accNames[] = {
"", "ADXL345", "MPU6050", "MMA845x", NULL
};
typedef struct {
char *name;
char *param;
const char *name;
const char *param;
void (*func)(char *cmdline);
} clicmd_t;
@ -80,7 +80,7 @@ const clicmd_t cmdTable[] = {
{ "status", "show system status", cliStatus },
{ "version", "", cliVersion },
};
#define CMD_COUNT (sizeof(cmdTable) / sizeof(cmdTable[0]))
#define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t))
typedef enum {
VAR_UINT8,
@ -140,6 +140,7 @@ const clivalue_t valueTable[] = {
{ "deadband", VAR_UINT8, &cfg.deadband, 0, 32 },
{ "yawdeadband", VAR_UINT8, &cfg.yawdeadband, 0, 100 },
{ "alt_hold_throttle_neutral", VAR_UINT8, &cfg.alt_hold_throttle_neutral, 1, 250 },
{ "alt_hold_fast_change", VAR_UINT8, &cfg.alt_hold_fast_change, 0, 1 },
{ "throttle_angle_correction", VAR_UINT8, &cfg.throttle_angle_correction, 0, 100 },
{ "rc_rate", VAR_UINT8, &cfg.rcRate8, 0, 250 },
{ "rc_expo", VAR_UINT8, &cfg.rcExpo8, 0, 100 },
@ -216,7 +217,7 @@ const clivalue_t valueTable[] = {
{ "d_level", VAR_UINT8, &cfg.D8[PIDLEVEL], 0, 200 },
};
#define VALUE_COUNT (sizeof(valueTable) / sizeof(valueTable[0]))
#define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
static void cliSetVar(const clivalue_t *var, const int32_t value);
static void cliPrintVar(const clivalue_t *var, uint32_t full);
@ -241,7 +242,7 @@ static void cliWrite(uint8_t ch);
static char *i2a(unsigned i, char *a, unsigned r)
{
if (i / r > 0)
if (i / r > 0)
a = i2a(i / r, a, r);
*a = "0123456789ABCDEFGHIJKLMNOPQRSTUVWXYZ"[i % r];
return a + 1;
@ -254,10 +255,10 @@ char *itoa(int i, char *a, int r)
if (i < 0) {
*a = '-';
*i2a(-(unsigned)i, a + 1, r) = 0;
} else
} else
*i2a(i, a, r) = 0;
return a;
}
}
#endif
@ -536,7 +537,6 @@ static void cliDefaults(char *cmdline)
static void cliDump(char *cmdline)
{
int i;
char buf[16];
float thr, roll, pitch, yaw;
@ -561,16 +561,16 @@ static void cliDump(char *cmdline)
pitch = mcfg.customMixer[i].pitch;
yaw = mcfg.customMixer[i].yaw;
printf("cmix %d", i + 1);
if (thr < 0)
if (thr < 0)
printf(" ");
printf("%s", ftoa(thr, buf));
if (roll < 0)
if (roll < 0)
printf(" ");
printf("%s", ftoa(roll, buf));
if (pitch < 0)
if (pitch < 0)
printf(" ");
printf("%s", ftoa(pitch, buf));
if (yaw < 0)
if (yaw < 0)
printf(" ");
printf("%s\r\n", ftoa(yaw, buf));
}
@ -692,7 +692,7 @@ static void cliMap(char *cmdline)
if (len == 8) {
// uppercase it
for (i = 0; i < 8; i++)
cmdline[i] = toupper(cmdline[i]);
cmdline[i] = toupper((unsigned char)cmdline[i]);
for (i = 0; i < 8; i++) {
if (strchr(rcChannelLetters, cmdline[i]) && !strchr(cmdline + i + 1, cmdline[i]))
continue;
@ -862,7 +862,7 @@ static void cliSet(char *cmdline)
cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
cliPrint("\r\n");
}
} else if ((eqptr = strstr(cmdline, "="))) {
} else if ((eqptr = strstr(cmdline, "=")) != NULL) {
// has equal, set var
eqptr++;
len--;

View File

@ -255,7 +255,7 @@ static void resetConf(void)
cfg.baro_tab_size = 21;
cfg.baro_noise_lpf = 0.6f;
cfg.baro_cf_vel = 0.995f;
cfg.baro_cf_alt = 0.900f;
cfg.baro_cf_alt = 0.950f;
cfg.acc_unarmedcal = 1;
// Radio

View File

@ -47,7 +47,7 @@ typedef struct {
#define E_SENSOR_NOT_DETECTED (char) 0
#define BMP085_PROM_START__ADDR 0xaa
#define BMP085_PROM_DATA__LEN 22
#define BMP085_T_MEASURE 0x2E // temperature measurent
#define BMP085_T_MEASURE 0x2E // temperature measurent
#define BMP085_P_MEASURE 0x34 // pressure measurement
#define BMP085_CTRL_MEAS_REG 0xF4
#define BMP085_ADC_OUT_MSB_REG 0xF6
@ -110,7 +110,9 @@ bool bmp085Detect(baro_t *baro)
gpio.pin = Pin_14;
gpio.mode = Mode_IN_FLOATING;
gpioInit(GPIOC, &gpio);
#ifdef BARO
BARO_ON;
#endif
// EXTI interrupt for barometer EOC
GPIO_EXTILineConfig(GPIO_PortSourceGPIOC, GPIO_PinSource14);
@ -148,7 +150,9 @@ bool bmp085Detect(baro_t *baro)
baro->calculate = bmp085_calculate;
return true;
}
#ifdef BARO
BARO_OFF;
#endif
return false;
}
@ -188,11 +192,11 @@ static int32_t bmp085_get_pressure(uint32_t up)
x2 = (bmp085.cal_param.b1 * ((b6 * b6) >> 12) ) >> 16;
x3 = ((x1 + x2) + 2) >> 2;
b4 = (bmp085.cal_param.ac4 * (uint32_t) (x3 + 32768)) >> 15;
b7 = ((uint32_t)(up - b3) * (50000 >> bmp085.oversampling_setting));
if (b7 < 0x80000000) {
pressure = (b7 << 1) / b4;
} else {
} else {
pressure = (b7 / b4) << 1;
}
@ -214,16 +218,11 @@ static void bmp085_start_ut(void)
static void bmp085_get_ut(void)
{
uint8_t data[2];
uint16_t timeout = 10000;
// wait in case of cockup
if (!convDone)
convOverrun++;
#if 0
while (!convDone && timeout-- > 0) {
__NOP();
}
#endif
i2cRead(BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 2, data);
bmp085_ut = (data[0] << 8) | data[1];
}
@ -244,16 +243,11 @@ static void bmp085_start_up(void)
static void bmp085_get_up(void)
{
uint8_t data[3];
uint16_t timeout = 10000;
// wait in case of cockup
if (!convDone)
convOverrun++;
#if 0
while (!convDone && timeout-- > 0) {
__NOP();
}
#endif
i2cRead(BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 3, data);
bmp085_up = (((uint32_t) data[0] << 16) | ((uint32_t) data[1] << 8) | (uint32_t) data[2]) >> (8 - bmp085.oversampling_setting);
}

View File

@ -47,31 +47,31 @@ static volatile uint8_t* read_p;
static void i2c_er_handler(void)
{
volatile uint32_t SR1Register, SR2Register;
/* Read the I2C1 status register */
volatile uint32_t SR1Register;
// Read the I2C1 status register
SR1Register = I2Cx->SR1;
if (SR1Register & 0x0F00) { //an error
error = true;
// I2C1error.error = ((SR1Register & 0x0F00) >> 8); //save error
// I2C1error.job = job; //the task
}
/* If AF, BERR or ARLO, abandon the current job and commence new if there are jobs */
// If AF, BERR or ARLO, abandon the current job and commence new if there are jobs
if (SR1Register & 0x0700) {
SR2Register = I2Cx->SR2; //read second status register to clear ADDR if it is set (note that BTF will not be set after a NACK)
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); //disable the RXNE/TXE interrupt - prevent the ISR tailchaining onto the ER (hopefully)
if (!(SR1Register & 0x0200) && !(I2Cx->CR1 & 0x0200)) { //if we dont have an ARLO error, ensure sending of a stop
if (I2Cx->CR1 & 0x0100) { //We are currently trying to send a start, this is very bad as start,stop will hang the peripheral
while (I2Cx->CR1 & 0x0100); //wait for any start to finish sending
I2C_GenerateSTOP(I2Cx, ENABLE); //send stop to finalise bus transaction
while (I2Cx->CR1 & 0x0200); //wait for stop to finish sending
i2cInit(I2Cx); //reset and configure the hardware
(void)I2Cx->SR2; // read second status register to clear ADDR if it is set (note that BTF will not be set after a NACK)
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable the RXNE/TXE interrupt - prevent the ISR tailchaining onto the ER (hopefully)
if (!(SR1Register & 0x0200) && !(I2Cx->CR1 & 0x0200)) { // if we dont have an ARLO error, ensure sending of a stop
if (I2Cx->CR1 & 0x0100) { // We are currently trying to send a start, this is very bad as start,stop will hang the peripheral
while (I2Cx->CR1 & 0x0100); // wait for any start to finish sending
I2C_GenerateSTOP(I2Cx, ENABLE); // send stop to finalise bus transaction
while (I2Cx->CR1 & 0x0200); // wait for stop to finish sending
i2cInit(I2Cx); // reset and configure the hardware
} else {
I2C_GenerateSTOP(I2Cx, ENABLE); //stop to free up the bus
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); //Disable EVT and ERR interrupts while bus inactive
I2C_GenerateSTOP(I2Cx, ENABLE); // stop to free up the bus
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts while bus inactive
}
}
}
I2Cx->SR1 &= ~0x0F00; //reset all the error bits to clear the interrupt
I2Cx->SR1 &= ~0x0F00; // reset all the error bits to clear the interrupt
busy = 0;
}
@ -167,18 +167,17 @@ void i2c_ev_handler(void)
index = -1; //send a subaddress
}
} else if (SReg_1 & 0x0002) { //we just sent the address - EV6 in ref manual
//Read SR1,2 to clear ADDR
volatile uint8_t a;
// Read SR1,2 to clear ADDR
__DMB(); // memory fence to control hardware
if (bytes == 1 && reading && subaddress_sent) { //we are receiving 1 byte - EV6_3
I2C_AcknowledgeConfig(I2Cx, DISABLE); //turn off ACK
if (bytes == 1 && reading && subaddress_sent) { // we are receiving 1 byte - EV6_3
I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
__DMB();
a = I2Cx->SR2; //clear ADDR after ACK is turned off
I2C_GenerateSTOP(I2Cx, ENABLE); //program the stop
(void)I2Cx->SR2; // clear ADDR after ACK is turned off
I2C_GenerateSTOP(I2Cx, ENABLE); // program the stop
final_stop = 1;
I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE); //allow us to have an EV7
} else { //EV6 and EV6_1
a = I2Cx->SR2; //clear the ADDR here
I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE); // allow us to have an EV7
} else { // EV6 and EV6_1
(void)I2Cx->SR2; // clear the ADDR here
__DMB();
if (bytes == 2 && reading && subaddress_sent) { //rx 2 bytes - EV6_1
I2C_AcknowledgeConfig(I2Cx, DISABLE); //turn off ACK
@ -220,7 +219,7 @@ void i2c_ev_handler(void)
}
}
//we must wait for the start to clear, otherwise we get constant BTF
while (I2Cx->CR1 & 0x0100) { ; }
while (I2Cx->CR1 & 0x0100) { ; }
} else if (SReg_1 & 0x0040) { //Byte received - EV7
read_p[index++] = I2C_ReceiveData(I2Cx);
if (bytes == (index + 3))

View File

@ -490,7 +490,7 @@ const uint8_t dmp_updates[29][9] = {
{0x01, 0xEC, 0x04, 0x00, 0x00, 0x40, 0x00}, //D_1_236 inv_apply_endian_accel
{0x03, 0x7F, 0x06, 0x0C, 0xC9, 0x2C, 0x97, 0x97, 0x97}, //FCFG_2 inv_set_mpu_sensors
{0x04, 0x02, 0x03, 0x0D, 0x35, 0x5D}, //CFG_MOTION_BIAS inv_turn_on_bias_from_no_motion
{0x04, 0x09, 0x04, 0x87, 0x2D, 0x35, 0x3D}, //FCFG_5 inv_set_bias_update
{0x04, 0x09, 0x04, 0x87, 0x2D, 0x35, 0x3D}, //FCFG_5 inv_set_bias_update
{0x00, 0xA3, 0x01, 0x00}, //D_0_163 inv_set_dead_zone
//SET INT_ENABLE at i=22
{0x07, 0x86, 0x01, 0xFE}, //CFG_6 inv_set_fifo_interupt
@ -560,13 +560,13 @@ void mpu6050DmpLoop(void)
if (dmp_firstPacket) {
delay(1);
mpu6050DmpBankSelect(0x00);
mpu6050DmpBankSelect(0x00); // bank
i2cWrite(MPU6050_ADDRESS, MPU_RA_MEM_START_ADDR, 0x60);
i2cWriteBuffer(MPU6050_ADDRESS, MPU_RA_MEM_R_W, 4, "\x04\x00\x00\x00"); // data
mpu6050DmpBankSelect(0x01);
i2cWrite(MPU6050_ADDRESS, MPU_RA_MEM_START_ADDR, 0x62);
i2cRead(MPU6050_ADDRESS, DMP_MEM_R_W, 2, buf);
dmp_firstPacket = false;
@ -593,20 +593,20 @@ static void mpu6050DmpProcessQuat(void)
quatl2 = dmp_quatTake32(dmp_received_packet, 2);
quatl3 = dmp_quatTake32(dmp_received_packet, 3);
if (quatl0 > 32767)
if (quatl0 > 32767)
quatl0 -= 65536;
if (quatl1 > 32767)
if (quatl1 > 32767)
quatl1 -= 65536;
if (quatl2 > 32767)
if (quatl2 > 32767)
quatl2 -= 65536;
if (quatl3 > 32767)
if (quatl3 > 32767)
quatl3 -= 65536;
quat0 = ((float) quatl0) / 16384.0f;
quat1 = ((float) quatl1) / 16384.0f;
quat2 = ((float) quatl2) / 16384.0f;
quat3 = ((float) quatl3) / 16384.0f;
dmpdata[0] = atan2f(2 * ((quat0 * quat1) + (quat2 * quat3)), 1.0 - (2 * ((quat1 * quat1) + (quat2 * quat2)))) * (180.0f / M_PI);
dmpdata[1] = asinf(2 * ((quat0 * quat2) - (quat3 * quat1))) * (180.0f / M_PI);
angle[0] = dmpdata[0] * 10;
@ -620,7 +620,7 @@ static void mpu6050DmpProcessQuat(void)
void mpu6050DmpResetFifo(void)
{
uint8_t ctrl;
i2cRead(MPU6050_ADDRESS, MPU_RA_USER_CTRL, 1, &ctrl);
ctrl |= 0x04;
i2cWrite(MPU6050_ADDRESS, MPU_RA_USER_CTRL, ctrl);
@ -632,7 +632,7 @@ static void mpu6050DmpGetPacket(void)
dmp_fifoCountL2 = dmp_fifoCountL - 32;
dmp_longPacket = true;
}
if (dmp_longPacket) {
i2cRead(MPU6050_ADDRESS, MPU_RA_FIFO_R_W, 32, dmp_received_packet);
i2cRead(MPU6050_ADDRESS, MPU_RA_FIFO_R_W, dmp_fifoCountL, dmp_received_packet + 32);
@ -652,7 +652,7 @@ static bool mpu6050DmpFifoReady(void)
dmp_fifoCountL = buf[1];
dmpFifoLevel = buf[0] << 8 | buf[1];
if (dmp_fifoCountL == 42 || dmp_fifoCountL == 44)
return true;
else {
@ -769,7 +769,7 @@ static void mpu6050DmpMemInit(void)
delay(2);
i2cRead(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_2, 1, &temp);
i2cWrite(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_2, 0x00);
i2cWrite(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_2, 0x00);
i2cRead(MPU6050_ADDRESS, MPU_RA_ACCEL_CONFIG, 1, &temp);
i2cWrite(MPU6050_ADDRESS, MPU_RA_ACCEL_CONFIG, 0x00); // full scale range +/- 2g

View File

@ -330,7 +330,7 @@ void GPS_NewData(uint16_t c)
GPS_distance_cm_bearing(&GPS_coord[LAT], &GPS_coord[LON], &GPS_home[LAT], &GPS_home[LON], &dist, &dir);
GPS_distanceToHome = dist / 100;
GPS_directionToHome = dir / 100;
if (!f.GPS_FIX_HOME) { // If we don't have home set, do not display anything
GPS_distanceToHome = 0;
GPS_directionToHome = 0;
@ -713,7 +713,7 @@ uint32_t GPS_coord_to_degrees(char* s)
int i;
// scan for decimal point or end of field
for (p = s; isdigit(*p); p++)
for (p = s; isdigit((unsigned char)*p); p++)
;
q = s;
@ -736,7 +736,7 @@ uint32_t GPS_coord_to_degrees(char* s)
q = p + 1;
for (i = 0; i < 4; i++) {
frac_min *= 10;
if (isdigit(*q))
if (isdigit((unsigned char)*q))
frac_min += *q++ - '0';
}
}
@ -1002,8 +1002,6 @@ static bool _new_position;
// do we have new speed information?
static bool _new_speed;
static uint8_t _disable_counter;
// Receive buffer
static union {
ubx_nav_posllh posllh;

View File

@ -372,7 +372,6 @@ int getEstimatedAltitude(void)
int32_t baroVel;
int32_t vel_tmp;
int32_t BaroAlt_tmp;
float vel_calc;
static float vel = 0.0f;
static float accAlt = 0.0f;
static int32_t lastBaroAlt;
@ -396,8 +395,7 @@ int getEstimatedAltitude(void)
BaroAlt = BaroAlt * cfg.baro_noise_lpf + BaroAlt_tmp * (1.0f - cfg.baro_noise_lpf); // additional LPF to reduce baro noise
// Integrator - velocity, cm/sec
vel_calc = (float) accSum[2] * accVelScale * (float) accTimeSum / (float) accSumCount;
vel += vel_calc;
vel += (float)accSum[2] * accVelScale * (float)accTimeSum / (float)accSumCount;
// Integrator - Altitude in cm
accAlt += vel * ((float) accTimeSum * 0.0000005f); // integrate velocity to get distance (x= a/2 * t^2)

View File

@ -6,7 +6,6 @@ int16_t motor[MAX_MOTORS];
int16_t servo[8] = { 1500, 1500, 1500, 1500, 1500, 1500, 1500, 1500 };
static motorMixer_t currentMixer[MAX_MOTORS];
static servoParam_t currentServo[MAX_SERVOS];
static const motorMixer_t mixerTri[] = {
{ 1.0f, 0.0f, 1.333333f, 0.0f }, // REAR

View File

@ -18,7 +18,7 @@ int16_t telemTemperature1; // gyro sensor temperature
int16_t failsafeCnt = 0;
int16_t failsafeEvents = 0;
int16_t rcData[8] = { 1502, 1502, 1502, 1502, 1502, 1502, 1502, 1502 }; // interval [1000;2000]
int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+500] for ROLL/PITCH/YAW
int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+500] for ROLL/PITCH/YAW
int16_t lookupPitchRollRC[6]; // lookup table for expo & RC rate PITCH+ROLL
int16_t lookupThrottleRC[11]; // lookup table for expo & mid THROTTLE
uint16_t rssi; // range: [0;1023]
@ -275,7 +275,7 @@ static void mwDisarm(void)
static void mwVario(void)
{
}
static int32_t errorGyroI[3] = { 0, 0, 0 };
@ -285,7 +285,7 @@ static void pidMultiWii(void)
{
int axis, prop;
int32_t error, errorAngle;
int32_t PTerm, ITerm, PTermACC, ITermACC = 0, PTermGYRO = 0, ITermGYRO = 0, DTerm;
int32_t PTerm, ITerm, PTermACC = 0, ITermACC = 0, PTermGYRO = 0, ITermGYRO = 0, DTerm;
static int16_t lastGyro[3] = { 0, 0, 0 };
static int32_t delta1[3], delta2[3];
int32_t deltaSum;
@ -310,7 +310,7 @@ static void pidMultiWii(void)
PTermGYRO = rcCommand[axis];
errorGyroI[axis] = constrain(errorGyroI[axis] + error, -16000, +16000); // WindUp
if (abs(gyroData[axis]) > 640)
if (abs(gyroData[axis]) > 640)
errorGyroI[axis] = 0;
ITermGYRO = (errorGyroI[axis] / 125 * cfg.I8[axis]) >> 6;
}
@ -404,7 +404,7 @@ static void pidRewrite(void)
delta1[axis] = delta;
DTerm = (deltaSum * cfg.D8[axis]) >> 8;
// -----calculate total PID output
// -----calculate total PID output
axisPID[axis] = PTerm + ITerm + DTerm;
}
}
@ -429,7 +429,9 @@ void loop(void)
uint8_t stTmp = 0;
int i;
static uint32_t rcTime = 0;
#ifdef BARO
static int16_t initialThrottleHold;
#endif
static uint32_t loopTime;
uint16_t auxState = 0;
static uint8_t GPSNavReset = 1;
@ -621,7 +623,7 @@ void loop(void)
if (rcOptions[BOXHORIZON]) {
f.ANGLE_MODE = 0;
if (!f.HORIZON_MODE) {
errorAngleI[ROLL] = 0;
errorAngleI[ROLL] = 0;
errorAngleI[PITCH] = 0;
f.HORIZON_MODE = 1;
}