Subversion Repositories FlightCtrl

Compare Revisions

Ignore whitespace Rev 1963 → Rev 1964

/branches/dongfang_FC_rewrite/analog.c
56,6 → 56,7
#include "analog.h"
#include "attitude.h"
#include "sensors.h"
#include "printf_P.h"
 
// for Delay functions
#include "timer0.h"
470,11 → 471,16
 
void analog_setNeutral() {
if (gyroOffset_readFromEEProm()) {
printf("gyro offsets invalid, you must recalibrate.");
gyroOffset.offsets[PITCH] = gyroOffset.offsets[ROLL] = 512 * GYRO_SUMMATION_FACTOR_PITCHROLL;
gyroOffset.offsets[YAW] = 512 * GYRO_SUMMATION_FACTOR_YAW;
}
debugOut.analog[6] = gyroOffset.offsets[PITCH];
debugOut.analog[7] = gyroOffset.offsets[ROLL];
 
if (accOffset_readFromEEProm()) {
printf("acc. meter offsets invalid, you must recalibrate.");
accOffset.offsets[PITCH] = accOffset.offsets[ROLL] = 512 * ACC_SUMMATION_FACTOR_PITCHROLL;
accOffset.offsets[Z] = 512 * ACC_SUMMATION_FACTOR_Z;
}