Subversion Repositories FlightCtrl

Compare Revisions

Ignore whitespace Rev 2188 → Rev 2189

/branches/dongfang_FC_rewrite/analog.c
2,117 → 2,87
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <stdlib.h>
#include <stdio.h>
 
#include "analog.h"
#include "attitude.h"
#include "sensors.h"
#include "printf_P.h"
#include "mk3mag.h"
 
// for Delay functions
// for Delay functions used in calibration.
#include "timer0.h"
 
// For reading and writing acc. meter offsets.
#include "eeprom.h"
#include "debug.h"
 
// For debugOut
#include "output.h"
 
// set ADC enable & ADC Start Conversion & ADC Interrupt Enable bit
#define startADC() (ADCSRA |= (1<<ADEN)|(1<<ADSC)|(1<<ADIE))
 
// TODO: Off to PROGMEM .
const char* recal = ", recalibration needed.";
 
/*
* For each A/D conversion cycle, each analog channel is sampled a number of times
* (see array channelsForStates), and the results for each channel are summed.
* Here are those for the gyros and the acc. meters. They are not zero-offset.
* They are exported in the analog.h file - but please do not use them! The only
* reason for the export is that the ENC-03_FC1.3 modules needs them for calibrating
* the offsets with the DAC.
* Gyro and accelerometer values for attitude computation.
* Unfiltered (this is unnecessary as noise should get absorbed in DCM).
* Normalized to rad/s.
* Data flow: ADCs (1 iteration) --> samplingADCData --offsetting--> gyro_attitude_tmp
* --rotation-->
* [filtering] --> gyro_attitude.
* Altimeter is also considered part of the "long" attitude loop.
*/
volatile uint16_t sensorInputs[8];
int16_t acc[3];
int16_t filteredAcc[3] = { 0,0,0 };
Vector3f gyro_attitude;
Vector3f accel;
 
/*
* These 4 exported variables are zero-offset. The "PID" ones are used
* in the attitude control as rotation rates. The "ATT" ones are for
* integration to angles.
* This stuff is for the aircraft control thread. It runs in unprocessed integers.
* (well some sort of scaling will be required).
* Data flow: ADCs (1 iteration) -> samplingADCData -> [offsetting and rotation] ->
* [filtering] --> gyro_control
*/
int16_t gyro_PID[2];
int16_t gyro_ATT[2];
int16_t gyro_control[3];
int16_t gyroD[2];
int16_t gyroDWindow[2][GYRO_D_WINDOW_LENGTH];
uint8_t gyroDWindowIdx = 0;
int16_t yawGyro;
int16_t magneticHeading;
uint8_t gyroDWindowIdx;
 
/*
* Air pressure. TODO: Might as well convert to floats / well known units.
*/
int32_t groundPressure;
int16_t dHeight;
 
uint32_t gyroActivity;
 
/*
* Offset values. These are the raw gyro and acc. meter sums when the copter is
* standing still. They are used for adjusting the gyro and acc. meter values
* to be centered on zero.
*/
 
sensorOffset_t gyroOffset;
sensorOffset_t accOffset;
sensorOffset_t accelOffset;
sensorOffset_t gyroAmplifierOffset;
 
/*
* In the MK coordinate system, nose-down is positive and left-roll is positive.
* If a sensor is used in an orientation where one but not both of the axes has
* an opposite sign, PR_ORIENTATION_REVERSED is set to 1 (true).
* Transform:
* pitch <- pp*pitch + pr*roll
* roll <- rp*pitch + rr*roll
* Not reversed, GYRO_QUADRANT:
* 0: pp=1, pr=0, rp=0, rr=1 // 0 degrees
* 1: pp=1, pr=-1,rp=1, rr=1 // +45 degrees
* 2: pp=0, pr=-1,rp=1, rr=0 // +90 degrees
* 3: pp=-1,pr=-1,rp=1, rr=1 // +135 degrees
* 4: pp=-1,pr=0, rp=0, rr=-1 // +180 degrees
* 5: pp=-1,pr=1, rp=-1,rr=-1 // +225 degrees
* 6: pp=0, pr=1, rp=-1,rr=0 // +270 degrees
* 7: pp=1, pr=1, rp=-1,rr=1 // +315 degrees
* Reversed, GYRO_QUADRANT:
* 0: pp=-1,pr=0, rp=0, rr=1 // 0 degrees with pitch reversed
* 1: pp=-1,pr=-1,rp=-1,rr=1 // +45 degrees with pitch reversed
* 2: pp=0, pr=-1,rp=-1,rr=0 // +90 degrees with pitch reversed
* 3: pp=1, pr=-1,rp=-1,rr=1 // +135 degrees with pitch reversed
* 4: pp=1, pr=0, rp=0, rr=-1 // +180 degrees with pitch reversed
* 5: pp=1, pr=1, rp=1, rr=-1 // +225 degrees with pitch reversed
* 6: pp=0, pr=1, rp=1, rr=0 // +270 degrees with pitch reversed
* 7: pp=-1,pr=1, rp=1, rr=1 // +315 degrees with pitch reversed
* Redo this to that quadrant 0 is normal with an FC2.x.
*/
 
void rotate(int16_t* result, uint8_t quadrant, uint8_t reverse) {
static const int8_t rotationTab[] = {1,1,0,-1,-1,-1,0,1};
// Pitch to Pitch part
int8_t xx = reverse ? rotationTab[(quadrant+4)%8] : rotationTab[quadrant];
// Roll to Pitch part
int8_t xy = rotationTab[(quadrant+2)%8];
// Pitch to Roll part
int8_t yx = reverse ? rotationTab[(quadrant+2)%8] : rotationTab[(quadrant+6)%8];
// Roll to Roll part
int8_t yy = rotationTab[quadrant];
static const int8_t rotationTab[] = { 1, 1, 0, -1, -1, -1, 0, 1 };
// Pitch to Pitch part
int8_t xx = reverse ? rotationTab[(quadrant + 4) & 7] : rotationTab[quadrant]; // 1
// Roll to Pitch part
int8_t xy = rotationTab[(quadrant + 2) & 7]; // -1
// Pitch to Roll part
int8_t yx = reverse ? rotationTab[(quadrant + 2) & 7] : rotationTab[(quadrant + 6) & 7]; // -1
// Roll to Roll part
int8_t yy = rotationTab[quadrant]; // -1
 
int16_t xIn = result[0];
result[0] = xx*xIn + xy*result[1];
result[1] = yx*xIn + yy*result[1];
if (quadrant & 1) {
// A rotation was used above, where the factors were too large by sqrt(2).
// So, we multiply by 2^n/sqt(2) and right shift n bits, as to divide by sqrt(2).
// A suitable value for n: Sample is 11 bits. After transformation it is the sum
// of 2 11 bit numbers, so 12 bits. We have 4 bits left...
result[0] = (result[0]*11) >> 4;
result[1] = (result[1]*11) >> 4;
}
int16_t xIn = result[0];
int32_t tmp0, tmp1;
 
tmp0 = xx * xIn + xy * result[1];
tmp1 = yx * xIn + yy * result[1];
 
if (quadrant & 1) {
tmp0 = (tmp0 * 181L) >> 8;
tmp1 = (tmp1 * 181L) >> 8;
}
 
result[0] = (int16_t) tmp0;
result[1] = (int16_t) tmp1;
}
 
/*
121,7 → 91,6
volatile uint8_t rangewidth = 105;
 
// Direct from sensor, irrespective of range.
// volatile uint16_t rawAirPressure;
 
// Value of 2 samples, with range.
uint16_t simpleAirPressure;
143,7 → 112,7
int32_t airPressureSum;
 
// The number of samples summed into airPressureSum so far.
uint8_t pressureMeasurementCount;
uint8_t pressureSumCount;
 
/*
* Battery voltage, in units of: 1k/11k / 3V * 1024 = 31.03 per volt.
155,53 → 124,75
/*
* Control and status.
*/
volatile uint8_t analogDataReady = 1;
volatile uint16_t samplingADCData[8];
volatile uint16_t attitudeADCData[8];
 
/*
* Experiment: Measuring vibration-induced sensor noise.
*/
uint16_t gyroNoisePeak[3];
uint16_t accNoisePeak[3];
volatile uint8_t analog_controlDataStatus = CONTROL_SENSOR_DATA_READY;
volatile uint8_t analog_attitudeDataStatus = ATTITUDE_SENSOR_NO_DATA;
// Number of ADC iterations done for current attitude loop.
volatile uint8_t attitudeSumCount;
 
volatile uint8_t adState;
volatile uint8_t ADCSampleCount;
volatile uint8_t adChannel;
 
// ADC channels
#define AD_GYRO_YAW 0
#define AD_GYRO_ROLL 1
#define AD_GYRO_PITCH 2
#define AD_AIRPRESSURE 3
#define AD_UBAT 4
#define AD_ACC_Z 5
#define AD_ACC_ROLL 6
#define AD_ACC_PITCH 7
 
/*
* Table of AD converter inputs for each state.
* The number of samples summed for each channel is equal to
* the number of times the channel appears in the array.
* The max. number of samples that can be taken in 2 ms is:
* 20e6 / 128 / 13 / (1/2e-3) = 24. Since the main control
* loop needs a little time between reading AD values and
* re-enabling ADC, the real limit is (how much?) lower.
* The acc. sensor is sampled even if not used - or installed
* at all. The cost is not significant.
*/
const uint8_t channelsForStates[] PROGMEM = {
AD_GYRO_X,
AD_GYRO_Y,
AD_GYRO_Z,
 
const uint8_t channelsForStates[] PROGMEM = {
AD_GYRO_PITCH, AD_GYRO_ROLL, AD_GYRO_YAW,
AD_ACC_PITCH, AD_ACC_ROLL, AD_AIRPRESSURE,
AD_ACCEL_X,
AD_ACCEL_Y,
 
AD_GYRO_PITCH, AD_GYRO_ROLL, AD_ACC_Z, // at 8, measure Z acc.
AD_GYRO_PITCH, AD_GYRO_ROLL, AD_GYRO_YAW, // at 11, finish yaw gyro
AD_ACC_PITCH, // at 12, finish pitch axis acc.
AD_ACC_ROLL, // at 13, finish roll axis acc.
AD_AIRPRESSURE, // at 14, finish air pressure.
AD_GYRO_PITCH, // at 15, finish pitch gyro
AD_GYRO_ROLL, // at 16, finish roll gyro
AD_UBAT // at 17, measure battery.
AD_GYRO_X,
AD_GYRO_Y,
//AD_GYRO_Z,
 
AD_ACCEL_Z,
AD_AIRPRESSURE,
 
AD_GYRO_X,
AD_GYRO_Y,
AD_GYRO_Z,
 
AD_ACCEL_X,
AD_ACCEL_Y,
 
AD_GYRO_X,
AD_GYRO_Y,
//AD_GYRO_Z,
 
//AD_ACCEL_Z,
//AD_AIRPRESSURE,
 
AD_GYRO_X,
AD_GYRO_Y,
AD_GYRO_Z,
 
AD_ACCEL_X,
AD_ACCEL_Y,
 
AD_GYRO_X,
AD_GYRO_Y,
//AD_GYRO_Z,
 
AD_ACCEL_Z,
AD_AIRPRESSURE,
 
AD_GYRO_Y,
AD_GYRO_X,
AD_GYRO_Z,
 
AD_ACCEL_X,
AD_ACCEL_Y,
 
AD_GYRO_X,
AD_GYRO_Y,
// AD_GYRO_Z,
 
//AD_ACCEL_Z,
//AD_AIRPRESSURE,
AD_UBAT
};
 
// Feature removed. Could be reintroduced later - but should work for all gyro types then.
208,57 → 199,69
// uint8_t GyroDefectPitch = 0, GyroDefectRoll = 0, GyroDefectYaw = 0;
 
void analog_init(void) {
uint8_t sreg = SREG;
// disable all interrupts before reconfiguration
cli();
uint8_t sreg = SREG;
// disable all interrupts before reconfiguration
cli();
 
//ADC0 ... ADC7 is connected to PortA pin 0 ... 7
DDRA = 0x00;
PORTA = 0x00;
// Digital Input Disable Register 0
// Disable digital input buffer for analog adc_channel pins
DIDR0 = 0xFF;
// external reference, adjust data to the right
ADMUX &= ~((1<<REFS1)|(1<<REFS0)|(1<<ADLAR));
// set muxer to ADC adc_channel 0 (0 to 7 is a valid choice)
ADMUX = (ADMUX & 0xE0);
//Set ADC Control and Status Register A
//Auto Trigger Enable, Prescaler Select Bits to Division Factor 128, i.e. ADC clock = SYSCKL/128 = 156.25 kHz
ADCSRA = (1<<ADPS2)|(1<<ADPS1)|(1<<ADPS0);
//Set ADC Control and Status Register B
//Trigger Source to Free Running Mode
ADCSRB &= ~((1<<ADTS2)|(1<<ADTS1)|(1<<ADTS0));
//ADC0 ... ADC7 is connected to PortA pin 0 ... 7
DDRA = 0x00;
PORTA = 0x00;
// Digital Input Disable Register 0
// Disable digital input buffer for analog adc_channel pins
DIDR0 = 0xFF;
// external reference, adjust data to the right
ADMUX &= ~((1 << REFS1) | (1 << REFS0) | (1 << ADLAR));
// set muxer to ADC adc_channel 0 (0 to 7 is a valid choice)
ADMUX = (ADMUX & 0xE0);
//Set ADC Control and Status Register A
//Auto Trigger Enable, Prescaler Select Bits to Division Factor 128, i.e. ADC clock = SYSCKL/128 = 156.25 kHz
ADCSRA = (1 << ADPS2) | (1 << ADPS1) | (1 << ADPS0);
//Set ADC Control and Status Register B
//Trigger Source to Free Running Mode
ADCSRB &= ~((1 << ADTS2) | (1 << ADTS1) | (1 << ADTS0));
 
for (uint8_t i=0; i<MAX_AIRPRESSURE_WINDOW_LENGTH; i++) {
airPressureWindow[i] = 0;
}
for (uint8_t i = 0; i < MAX_AIRPRESSURE_WINDOW_LENGTH; i++) {
airPressureWindow[i] = 0;
}
 
windowedAirPressure = 0;
 
startAnalogConversionCycle();
startADCCycle();
 
// restore global interrupt flags
SREG = sreg;
// restore global interrupt flags
SREG = sreg;
}
 
uint16_t rawGyroValue(uint8_t axis) {
return sensorInputs[AD_GYRO_PITCH-axis];
// Convert axis number (X, Y, Z to ADC channel mapping (1, 2, 0)
uint16_t gyroValue(uint8_t axis, volatile uint16_t dataArray[]) {
switch (axis) {
case X:
return dataArray[AD_GYRO_X];
case Y:
return dataArray[AD_GYRO_Y];
case Z:
return dataArray[AD_GYRO_Z];
default:
return 0; // should never happen.
}
}
 
uint16_t rawAccValue(uint8_t axis) {
return sensorInputs[AD_ACC_PITCH-axis];
uint16_t gyroValueForFC13DACCalibration(uint8_t axis) {
return gyroValue(axis, samplingADCData);
}
 
void measureNoise(const int16_t sensor,
volatile uint16_t* const noiseMeasurement, const uint8_t damping) {
if (sensor > (int16_t) (*noiseMeasurement)) {
*noiseMeasurement = sensor;
} else if (-sensor > (int16_t) (*noiseMeasurement)) {
*noiseMeasurement = -sensor;
} else if (*noiseMeasurement > damping) {
*noiseMeasurement -= damping;
} else {
*noiseMeasurement = 0;
}
// Convert axis number (X, Y, Z to ADC channel mapping (6, 7, 5)
uint16_t accValue(uint8_t axis, volatile uint16_t dataArray[]) {
switch (axis) {
case X:
return dataArray[AD_ACCEL_X];
case Y:
return dataArray[AD_ACCEL_Y];
case Z:
return dataArray[AD_ACCEL_Z];
default:
return 0; // should never happen.
}
}
 
/*
266,345 → 269,391
* Max: About 106 * 240 + 2047 = 27487; it is OK with just a 16 bit type.
*/
uint16_t getSimplePressure(int advalue) {
uint16_t result = (uint16_t) OCR0A * (uint16_t) rangewidth + advalue;
result += (acc[Z] * (staticParams.airpressureAccZCorrection-128)) >> 10;
return result;
uint16_t result = (uint16_t) OCR0A * /*(uint16_t)*/ rangewidth + advalue;
result += (/*accel.z*/0 * (staticParams.airpressureAccZCorrection - 128)) >> 10;
return result;
}
 
void startAnalogConversionCycle(void) {
analogDataReady = 0;
 
// Stop the sampling. Cycle is over.
for (uint8_t i = 0; i < 8; i++) {
sensorInputs[i] = 0;
}
adState = 0;
adChannel = AD_GYRO_PITCH;
ADMUX = (ADMUX & 0xE0) | adChannel;
startADC();
void startADCCycle(void) {
for (uint8_t i=0; i<8; i++) {
samplingADCData[i] = 0;
}
ADCSampleCount = 0;
adChannel = AD_GYRO_X;
ADMUX = (ADMUX & 0xE0) | adChannel;
analog_controlDataStatus = CONTROL_SENSOR_SAMPLING_DATA;
J4HIGH;
startADC();
}
 
/*****************************************************
* Interrupt Service Routine for ADC
* Runs at 312.5 kHz or 3.2 �s. When all states are
* processed further conversions are stopped.
* Runs at 12 kHz. When all states are processed
* further conversions are stopped.
*****************************************************/
ISR(ADC_vect) {
sensorInputs[adChannel] += ADC;
// set up for next state.
adState++;
if (adState < sizeof(channelsForStates)) {
adChannel = pgm_read_byte(&channelsForStates[adState]);
// set adc muxer to next adChannel
ADMUX = (ADMUX & 0xE0) | adChannel;
// after full cycle stop further interrupts
startADC();
} else {
analogDataReady = 1;
// do not restart ADC converter.
}
ISR( ADC_vect) {
samplingADCData[adChannel] += ADC;
// set up for next state.
ADCSampleCount++;
if (ADCSampleCount < sizeof(channelsForStates)) {
adChannel = pgm_read_byte(&channelsForStates[ADCSampleCount]);
// set adc muxer to next adChannel
ADMUX = (ADMUX & 0xE0) | adChannel;
// after full cycle stop further interrupts
startADC();
} else {
J4LOW;
analog_controlDataStatus = CONTROL_SENSOR_DATA_READY;
// do not restart ADC converter.
}
}
 
void measureGyroActivity(int16_t newValue) {
gyroActivity += newValue * newValue;
// abs(newValue); // (uint32_t)((int32_t)newValue * newValue);
/*
* Used in calibration only!
* Wait the specified number of millis, and then run a full sensor ADC cycle.
*/
void waitADCCycle(uint16_t delay) {
delay_ms(delay);
startADCCycle();
while(analog_controlDataStatus != CONTROL_SENSOR_DATA_READY)
;
}
 
#define GADAMPING 6
void dampenGyroActivity(void) {
static uint8_t cnt = 0;
void analog_updateControlData(void) {
/*
* 1) Near-saturation boost (dont bother with Z)
* 2) Offset
* 3) Rotation
* 4) Filter
* 5) Extract gyroD (should this be without near-saturation boost really? Ignore issue)
*/
 
if (++cnt >= IMUConfig.gyroActivityDamping) {
cnt = 0;
gyroActivity *= (uint32_t)((1L<<GADAMPING)-1);
gyroActivity >>= GADAMPING;
}
int16_t tempOffsetGyro[2];
int16_t tempGyro;
for (uint8_t axis=X; axis<=Y; axis++) {
tempGyro = gyroValue(axis, samplingADCData);
//debugOut.analog[3 + axis] = tempGyro;
//debugOut.analog[3 + 2] = gyroValue(Z, samplingADCData);
 
/*
if (gyroActivity >= 10) gyroActivity -= 10;
else if (gyroActivity <=- 10) gyroActivity += 10;
*/
}
/*
* Process the gyro data for the PID controller.
*/
// 1) Extrapolate: Near the ends of the range, we boost the input significantly. This simulates a
// gyro with a wider range, and helps counter saturation at full control.
// There is hardly any reason to bother extrapolating yaw.
 
void analog_updateGyros(void) {
// for various filters...
int16_t tempOffsetGyro[2], tempGyro;
debugOut.digital[0] &= ~DEBUG_SENSORLIMIT;
for (uint8_t axis=0; axis<2; axis++) {
tempGyro = rawGyroValue(axis);
/*
* Process the gyro data for the PID controller.
*/
// 1) Extrapolate: Near the ends of the range, we boost the input significantly. This simulates a
// gyro with a wider range, and helps counter saturation at full control.
if (staticParams.bitConfig & CFG_GYRO_SATURATION_PREVENTION) {
if (tempGyro < SENSOR_MIN_PITCHROLL) {
debugOut.digital[0] |= DEBUG_SENSORLIMIT;
tempGyro = tempGyro * EXTRAPOLATION_SLOPE - EXTRAPOLATION_LIMIT;
} else if (tempGyro > SENSOR_MAX_PITCHROLL) {
debugOut.digital[0] |= DEBUG_SENSORLIMIT;
tempGyro = (tempGyro - SENSOR_MAX_PITCHROLL) * EXTRAPOLATION_SLOPE + SENSOR_MAX_PITCHROLL;
}
if (staticParams.bitConfig & CFG_GYRO_SATURATION_PREVENTION) {
if (tempGyro < SENSOR_MIN_XY) {
debugOut.digital[0] |= DEBUG_SENSORLIMIT;
tempGyro = tempGyro * EXTRAPOLATION_SLOPE - EXTRAPOLATION_LIMIT;
} else if (tempGyro > SENSOR_MAX_XY) {
debugOut.digital[0] |= DEBUG_SENSORLIMIT;
tempGyro = (tempGyro - SENSOR_MAX_XY) * EXTRAPOLATION_SLOPE + SENSOR_MAX_XY;
}
}
 
// 2) Apply offset (rotation will take care of signs).
tempOffsetGyro[axis] = tempGyro - gyroOffset.offsets[axis];
}
 
// 2) Apply sign and offset, scale before filtering.
tempOffsetGyro[axis] = (tempGyro - gyroOffset.offsets[axis]) * GYRO_FACTOR_PITCHROLL;
}
// 2.1: Transform axes.
rotate(tempOffsetGyro, IMUConfig.gyroQuadrant, IMUConfig.imuReversedFlags & IMU_REVERSE_GYRO_XY);
 
// 2.1: Transform axes.
rotate(tempOffsetGyro, IMUConfig.gyroQuadrant, IMUConfig.imuReversedFlags & IMU_REVERSE_GYRO_PR);
for (uint8_t axis=X; axis<=Y; axis++) {
// Filter. There is no filter for Z and no need for one.
tempGyro = (gyro_control[axis] * (IMUConfig.gyroPIDFilterConstant - 1) + tempOffsetGyro[axis]) / IMUConfig.gyroPIDFilterConstant;
// 5) Differential measurement.
int16_t diff = tempGyro - gyro_control[axis];
gyroD[axis] -= gyroDWindow[axis][gyroDWindowIdx];
gyroD[axis] += diff;
gyroDWindow[axis][gyroDWindowIdx] = diff;
 
for (uint8_t axis=0; axis<2; axis++) {
// 3) Filter.
tempOffsetGyro[axis] = (gyro_PID[axis] * (IMUConfig.gyroPIDFilterConstant - 1) + tempOffsetGyro[axis]) / IMUConfig.gyroPIDFilterConstant;
// 6) Done.
gyro_control[axis] = tempGyro;
}
 
// 4) Measure noise.
measureNoise(tempOffsetGyro[axis], &gyroNoisePeak[axis], GYRO_NOISE_MEASUREMENT_DAMPING);
if (++gyroDWindowIdx >= IMUConfig.gyroDWindowLength) {
gyroDWindowIdx = 0;
}
if (IMUConfig.imuReversedFlags & IMU_REVERSE_GYRO_Z)
tempGyro = gyroOffset.offsets[Z] - gyroValue(Z, samplingADCData);
else
tempGyro = gyroValue(Z, samplingADCData) - gyroOffset.offsets[Z];
 
// 5) Differential measurement.
// gyroD[axis] = (gyroD[axis] * (staticParams.gyroDFilterConstant - 1) + (tempOffsetGyro[axis] - gyro_PID[axis])) / staticParams.gyroDFilterConstant;
int16_t diff = tempOffsetGyro[axis] - gyro_PID[axis];
gyroD[axis] -= gyroDWindow[axis][gyroDWindowIdx];
gyroD[axis] += diff;
gyroDWindow[axis][gyroDWindowIdx] = diff;
gyro_control[Z] = tempGyro;
startADCCycle();
}
 
// 6) Done.
gyro_PID[axis] = tempOffsetGyro[axis];
/*
* The uint16s can take a max. of 1<<16-10) = 64 samples summed.
* Assuming a max oversampling count of 8 for the control loop, this is 8 control loop iterations
* summed. After 8 are reached, we just throw away all further data. This (that the attitude loop
* is more than 8 times slower than the control loop) should not happen anyway so there is no waste.
*/
#define MAX_OVEROVERSAMPLING_COUNT 8
 
// Prepare tempOffsetGyro for next calculation below...
tempOffsetGyro[axis] = (rawGyroValue(axis) - gyroOffset.offsets[axis]) * GYRO_FACTOR_PITCHROLL;
}
void analog_sumAttitudeData(void) {
// From when this procedure completes, there is attitude data available.
if (analog_attitudeDataStatus == ATTITUDE_SENSOR_NO_DATA)
analog_attitudeDataStatus = ATTITUDE_SENSOR_DATA_READY;
 
/*
* Now process the data for attitude angles.
*/
rotate(tempOffsetGyro, IMUConfig.gyroQuadrant, IMUConfig.imuReversedFlags & IMU_REVERSE_GYRO_PR);
 
dampenGyroActivity();
gyro_ATT[PITCH] = tempOffsetGyro[PITCH];
gyro_ATT[ROLL] = tempOffsetGyro[ROLL];
if (analog_attitudeDataStatus == ATTITUDE_SENSOR_DATA_READY && attitudeSumCount < MAX_OVEROVERSAMPLING_COUNT) {
for (uint8_t i = 0; i < 8; i++) {
attitudeADCData[i] += samplingADCData[i];
}
attitudeSumCount++;
debugOut.analog[24] = attitudeSumCount;
}
}
 
/*
measureGyroActivity(tempOffsetGyro[PITCH]);
measureGyroActivity(tempOffsetGyro[ROLL]);
*/
measureGyroActivity(gyroD[PITCH]);
measureGyroActivity(gyroD[ROLL]);
void clearAttitudeData(void) {
for (uint8_t i = 0; i < 8; i++) {
attitudeADCData[i] = 0;
}
attitudeSumCount = 0;
analog_attitudeDataStatus = ATTITUDE_SENSOR_NO_DATA;
}
 
// We measure activity of yaw by plain gyro value and not d/dt, because:
// - There is no drift correction anyway
// - Effect of steady circular flight would vanish (it should have effect).
// int16_t diff = yawGyro;
// Yaw gyro.
if (IMUConfig.imuReversedFlags & IMU_REVERSE_GYRO_YAW)
yawGyro = gyroOffset.offsets[YAW] - sensorInputs[AD_GYRO_YAW];
else
yawGyro = sensorInputs[AD_GYRO_YAW] - gyroOffset.offsets[YAW];
void updateAttitudeVectors(void) {
/*
int16_t gyro_attitude_tmp[3];
Vector3f gyro_attitude;
Vector3f accel;
*/
 
// diff -= yawGyro;
// gyroD[YAW] -= gyroDWindow[YAW][gyroDWindowIdx];
// gyroD[YAW] += diff;
// gyroDWindow[YAW][gyroDWindowIdx] = diff;
int16_t tmpSensor[3];
 
// gyroActivity += (uint32_t)(abs(yawGyro)* IMUConfig.yawRateFactor);
measureGyroActivity(yawGyro);
// prevent gyro_attitude_tmp and attitudeSumCount from being updated.
// TODO: This only prevents interrupts from starting. Well its good enough really?
analog_attitudeDataStatus = ATTITUDE_SENSOR_READING_DATA;
 
if (++gyroDWindowIdx >= IMUConfig.gyroDWindowLength) {
gyroDWindowIdx = 0;
}
}
tmpSensor[X] = gyroValue(X, attitudeADCData) - gyroOffset.offsets[X] * attitudeSumCount;
tmpSensor[Y] = gyroValue(Y, attitudeADCData) - gyroOffset.offsets[Y] * attitudeSumCount;
 
void analog_updateAccelerometers(void) {
// Pitch and roll axis accelerations.
for (uint8_t axis=0; axis<2; axis++) {
acc[axis] = rawAccValue(axis) - accOffset.offsets[axis];
}
rotate(tmpSensor, IMUConfig.gyroQuadrant, IMUConfig.imuReversedFlags & IMU_REVERSE_GYRO_XY);
 
rotate(acc, IMUConfig.accQuadrant, IMUConfig.imuReversedFlags & IMU_REVERSE_ACC_XY);
for(uint8_t axis=0; axis<3; axis++) {
filteredAcc[axis] = (filteredAcc[axis] * (IMUConfig.accFilterConstant - 1) + acc[axis]) / IMUConfig.accFilterConstant;
measureNoise(acc[axis], &accNoisePeak[axis], 1);
}
if (IMUConfig.imuReversedFlags & IMU_REVERSE_GYRO_Z)
tmpSensor[Z] = gyroOffset.offsets[Z] * attitudeSumCount - gyroValue(Z, attitudeADCData);
else
tmpSensor[Z] = gyroValue(Z, attitudeADCData) - gyroOffset.offsets[Z] * attitudeSumCount;
 
// Z acc.
if (IMUConfig.imuReversedFlags & 8)
acc[Z] = accOffset.offsets[Z] - sensorInputs[AD_ACC_Z];
else
acc[Z] = sensorInputs[AD_ACC_Z] - accOffset.offsets[Z];
gyro_attitude.x = ((float) tmpSensor[X]) / (GYRO_RATE_FACTOR_XY * attitudeSumCount);
gyro_attitude.y = ((float) tmpSensor[Y]) / (GYRO_RATE_FACTOR_XY * attitudeSumCount);
gyro_attitude.z = ((float) tmpSensor[Z]) / (GYRO_RATE_FACTOR_Z * attitudeSumCount);
 
// debugOut.analog[29] = acc[Z];
// Done with gyros. Now accelerometer:
tmpSensor[X] = accValue(X, attitudeADCData) - accelOffset.offsets[X] * attitudeSumCount;
tmpSensor[Y] = accValue(Y, attitudeADCData) - accelOffset.offsets[Y] * attitudeSumCount;
 
rotate(tmpSensor, IMUConfig.accQuadrant, IMUConfig.imuReversedFlags & IMU_REVERSE_ACCEL_XY);
 
// Z acc.
if (IMUConfig.imuReversedFlags & IMU_REVERSE_ACCEL_Z)
tmpSensor[Z] = accelOffset.offsets[Z] * attitudeSumCount - accValue(Z, attitudeADCData);
else
tmpSensor[Z] = accValue(Z, attitudeADCData) - accelOffset.offsets[Z] * attitudeSumCount;
 
// Blarh!!! We just skip acc filtering. There are trillions of samples already.
accel.x = (float)tmpSensor[X] / (ACCEL_FACTOR_XY * attitudeSumCount); // (accel.x + (float)tmpSensor[X] / (ACCEL_FACTOR_XY * attitudeSumCount)) / 2.0;
accel.y = (float)tmpSensor[Y] / (ACCEL_FACTOR_XY * attitudeSumCount); // (accel.y + (float)tmpSensor[Y] / (ACCEL_FACTOR_XY * attitudeSumCount)) / 2.0;
accel.z = (float)tmpSensor[Z] / (ACCEL_FACTOR_Z * attitudeSumCount); // (accel.z + (float)tmpSensor[Z] / (ACCEL_FACTOR_Z * attitudeSumCount)) / 2.0;
 
for (uint8_t i=0; i<3; i++) {
debugOut.analog[3 + i] = (int16_t)(gyro_attitude[i] * 100);
debugOut.analog[6 + i] = (int16_t)(accel[i] * 100);
}
}
 
void analog_updateAirPressure(void) {
static uint16_t pressureAutorangingWait = 25;
uint16_t rawAirPressure;
int16_t newrange;
// air pressure
if (pressureAutorangingWait) {
//A range switch was done recently. Wait for steadying.
pressureAutorangingWait--;
} else {
rawAirPressure = sensorInputs[AD_AIRPRESSURE];
if (rawAirPressure < MIN_RAWPRESSURE) {
// value is too low, so decrease voltage on the op amp minus input, making the value higher.
newrange = OCR0A - (MAX_RAWPRESSURE - MIN_RAWPRESSURE) / (rangewidth * 4); // 4; // (MAX_RAWPRESSURE - rawAirPressure) / (rangewidth * 2) + 1;
if (newrange > MIN_RANGES_EXTRAPOLATION) {
pressureAutorangingWait = (OCR0A - newrange) * AUTORANGE_WAIT_FACTOR; // = OCRA0 - OCRA0 +
OCR0A = newrange;
} else {
if (OCR0A) {
OCR0A--;
pressureAutorangingWait = AUTORANGE_WAIT_FACTOR;
}
}
} else if (rawAirPressure > MAX_RAWPRESSURE) {
// value is too high, so increase voltage on the op amp minus input, making the value lower.
// If near the end, make a limited increase
newrange = OCR0A + (MAX_RAWPRESSURE - MIN_RAWPRESSURE) / (rangewidth * 4); // 4; // (rawAirPressure - MIN_RAWPRESSURE) / (rangewidth * 2) - 1;
if (newrange < MAX_RANGES_EXTRAPOLATION) {
pressureAutorangingWait = (newrange - OCR0A) * AUTORANGE_WAIT_FACTOR;
OCR0A = newrange;
} else {
if (OCR0A < 254) {
OCR0A++;
pressureAutorangingWait = AUTORANGE_WAIT_FACTOR;
}
}
}
// Even if the sample is off-range, use it.
simpleAirPressure = getSimplePressure(rawAirPressure);
if (simpleAirPressure < MIN_RANGES_EXTRAPOLATION * rangewidth) {
// Danger: pressure near lower end of range. If the measurement saturates, the
// copter may climb uncontrolledly... Simulate a drastic reduction in pressure.
debugOut.digital[1] |= DEBUG_SENSORLIMIT;
airPressureSum += (int16_t) MIN_RANGES_EXTRAPOLATION * rangewidth
+ (simpleAirPressure - (int16_t) MIN_RANGES_EXTRAPOLATION
* rangewidth) * PRESSURE_EXTRAPOLATION_COEFF;
} else if (simpleAirPressure > MAX_RANGES_EXTRAPOLATION * rangewidth) {
// Danger: pressure near upper end of range. If the measurement saturates, the
// copter may descend uncontrolledly... Simulate a drastic increase in pressure.
debugOut.digital[1] |= DEBUG_SENSORLIMIT;
airPressureSum += (int16_t) MAX_RANGES_EXTRAPOLATION * rangewidth
+ (simpleAirPressure - (int16_t) MAX_RANGES_EXTRAPOLATION
* rangewidth) * PRESSURE_EXTRAPOLATION_COEFF;
static uint16_t pressureAutorangingWait = 25;
uint16_t rawAirPressure;
int16_t newrange;
// air pressure
if (pressureAutorangingWait) {
//A range switch was done recently. Wait for steadying.
pressureAutorangingWait--;
} else {
// normal case.
// If AIRPRESSURE_OVERSAMPLING is an odd number we only want to add half the double sample.
// The 2 cases above (end of range) are ignored for this.
debugOut.digital[1] &= ~DEBUG_SENSORLIMIT;
airPressureSum += simpleAirPressure;
}
// 2 samples were added.
pressureMeasurementCount += 2;
// Assumption here: AIRPRESSURE_OVERSAMPLING is even (well we all know it's 14 haha...)
if (pressureMeasurementCount == AIRPRESSURE_OVERSAMPLING) {
rawAirPressure = attitudeADCData[AD_AIRPRESSURE] / attitudeSumCount;
if (rawAirPressure < MIN_RAWPRESSURE) {
// value is too low, so decrease voltage on the op amp minus input, making the value higher.
newrange = OCR0A - (MAX_RAWPRESSURE - MIN_RAWPRESSURE) / (rangewidth * 4);
if (newrange > MIN_RANGES_EXTRAPOLATION) {
pressureAutorangingWait = (OCR0A - newrange) * AUTORANGE_WAIT_FACTOR; // = OCRA0 - OCRA0 +
OCR0A = newrange;
} else {
if (OCR0A) {
OCR0A--;
pressureAutorangingWait = AUTORANGE_WAIT_FACTOR;
}
}
} else if (rawAirPressure > MAX_RAWPRESSURE) {
// value is too high, so increase voltage on the op amp minus input, making the value lower.
// If near the end, make a limited increase
newrange = OCR0A + (MAX_RAWPRESSURE - MIN_RAWPRESSURE) / (rangewidth * 4);
if (newrange < MAX_RANGES_EXTRAPOLATION) {
pressureAutorangingWait = (newrange - OCR0A) * AUTORANGE_WAIT_FACTOR;
OCR0A = newrange;
} else {
if (OCR0A < 254) {
OCR0A++;
pressureAutorangingWait = AUTORANGE_WAIT_FACTOR;
}
}
}
 
// The best oversampling count is 14.5. We add a quarter of the double ADC value to get the final half.
airPressureSum += simpleAirPressure >> 2;
// Even if the sample is off-range, use it.
simpleAirPressure = getSimplePressure(rawAirPressure);
if (simpleAirPressure < (uint16_t)(MIN_RANGES_EXTRAPOLATION * rangewidth)) {
// Danger: pressure near lower end of range. If the measurement saturates, the
// copter may climb uncontrolledly... Simulate a drastic reduction in pressure.
debugOut.digital[1] |= DEBUG_SENSORLIMIT;
airPressureSum += (int16_t) MIN_RANGES_EXTRAPOLATION * rangewidth
+ (simpleAirPressure - (int16_t) MIN_RANGES_EXTRAPOLATION
* rangewidth) * PRESSURE_EXTRAPOLATION_COEFF;
} else if (simpleAirPressure > (uint16_t)(MAX_RANGES_EXTRAPOLATION * rangewidth)) {
// Danger: pressure near upper end of range. If the measurement saturates, the
// copter may descend uncontrolledly... Simulate a drastic increase in pressure.
debugOut.digital[1] |= DEBUG_SENSORLIMIT;
airPressureSum += (int16_t) MAX_RANGES_EXTRAPOLATION * rangewidth
+ (simpleAirPressure - (int16_t) MAX_RANGES_EXTRAPOLATION
* rangewidth) * PRESSURE_EXTRAPOLATION_COEFF;
} else {
// normal case.
// If AIRPRESSURE_OVERSAMPLING is an odd number we only want to add half the double sample.
// The 2 cases above (end of range) are ignored for this.
debugOut.digital[1] &= ~DEBUG_SENSORLIMIT;
airPressureSum += simpleAirPressure;
}
 
uint32_t lastFilteredAirPressure = filteredAirPressure;
// 2 samples were added.
pressureSumCount += 2;
// Assumption here: AIRPRESSURE_OVERSAMPLING is even (well we all know it's 28...)
if (pressureSumCount == AIRPRESSURE_OVERSAMPLING) {
 
if (!staticParams.airpressureWindowLength) {
filteredAirPressure = (filteredAirPressure * (staticParams.airpressureFilterConstant - 1)
+ airPressureSum + staticParams.airpressureFilterConstant / 2) / staticParams.airpressureFilterConstant;
} else {
// use windowed.
windowedAirPressure += simpleAirPressure;
windowedAirPressure -= airPressureWindow[windowPtr];
airPressureWindow[windowPtr++] = simpleAirPressure;
if (windowPtr >= staticParams.airpressureWindowLength) windowPtr = 0;
filteredAirPressure = windowedAirPressure / staticParams.airpressureWindowLength;
}
// The best oversampling count is 14.5. We add a quarter of the double ADC value to get the final half.
airPressureSum += simpleAirPressure >> 2;
 
// positive diff of pressure
int16_t diff = filteredAirPressure - lastFilteredAirPressure;
// is a negative diff of height.
dHeight -= diff;
// remove old sample (fifo) from window.
dHeight += dAirPressureWindow[dWindowPtr];
dAirPressureWindow[dWindowPtr++] = diff;
if (dWindowPtr >= staticParams.airpressureDWindowLength) dWindowPtr = 0;
pressureMeasurementCount = airPressureSum = 0;
uint32_t lastFilteredAirPressure = filteredAirPressure;
 
if (!staticParams.airpressureWindowLength) {
filteredAirPressure = (filteredAirPressure
* (staticParams.airpressureFilterConstant - 1)
+ airPressureSum
+ staticParams.airpressureFilterConstant / 2)
/ staticParams.airpressureFilterConstant;
} else {
// use windowed.
windowedAirPressure += simpleAirPressure;
windowedAirPressure -= airPressureWindow[windowPtr];
airPressureWindow[windowPtr++] = simpleAirPressure;
if (windowPtr >= staticParams.airpressureWindowLength)
windowPtr = 0;
filteredAirPressure = windowedAirPressure / staticParams.airpressureWindowLength;
}
 
// positive diff of pressure
int16_t diff = filteredAirPressure - lastFilteredAirPressure;
// is a negative diff of height.
dHeight -= diff;
// remove old sample (fifo) from window.
dHeight += dAirPressureWindow[dWindowPtr];
dAirPressureWindow[dWindowPtr++] = diff;
if (dWindowPtr >= staticParams.airpressureDWindowLength)
dWindowPtr = 0;
pressureSumCount = airPressureSum = 0;
}
}
}
debugOut.analog[25] = simpleAirPressure;
debugOut.analog[26] = OCR0A;
debugOut.analog[27] = filteredAirPressure;
}
 
void analog_updateBatteryVoltage(void) {
// Battery. The measured value is: (V * 1k/11k)/3v * 1024 = 31.03 counts per volt (max. measurable is 33v).
// This is divided by 3 --> 10.34 counts per volt.
UBat = (3 * UBat + sensorInputs[AD_UBAT] / 3) / 4;
// Battery. The measured value is: (V * 1k/11k)/3v * 1024 = 31.03 counts per volt (max. measurable is 33v).
// This is divided by 3 --> 10.34 counts per volt.
UBat = (3 * UBat + attitudeADCData[AD_UBAT] / 3) / 4;
}
 
void analog_update(void) {
analog_updateGyros();
analog_updateAccelerometers();
analog_updateAirPressure();
analog_updateBatteryVoltage();
#ifdef USE_MK3MAG
magneticHeading = volatileMagneticHeading;
#endif
void analog_updateAttitudeData(void) {
updateAttitudeVectors();
 
// TODO: These are waaaay off by now.
analog_updateAirPressure();
analog_updateBatteryVoltage();
 
clearAttitudeData();
}
 
void analog_setNeutral() {
gyro_init();
if (gyroOffset_readFromEEProm()) {
printf("gyro offsets invalid%s",recal);
gyroOffset.offsets[PITCH] = gyroOffset.offsets[ROLL] = 512 * GYRO_OVERSAMPLING_PITCHROLL;
gyroOffset.offsets[YAW] = 512 * GYRO_OVERSAMPLING_YAW;
}
if (accOffset_readFromEEProm()) {
printf("acc. meter offsets invalid%s",recal);
accOffset.offsets[PITCH] = accOffset.offsets[ROLL] = 512 * ACC_OVERSAMPLING_XY;
accOffset.offsets[Z] = 717 * ACC_OVERSAMPLING_Z;
}
gyro_init();
 
// Noise is relative to offset. So, reset noise measurements when changing offsets.
for (uint8_t i=PITCH; i<=ROLL; i++) {
gyroNoisePeak[i] = 0;
gyroD[i] = 0;
for (uint8_t j=0; j<GYRO_D_WINDOW_LENGTH; j++) {
gyroDWindow[i][j] = 0;
}
}
// Setting offset values has an influence in the analog.c ISR
// Therefore run measurement for 100ms to achive stable readings
delay_ms_with_adc_measurement(100, 0);
if (gyroOffset_readFromEEProm()) {
printf("gyro offsets invalid%s", recal);
gyroOffset.offsets[X] = gyroOffset.offsets[Y] = 512 * GYRO_OVERSAMPLING_XY;
gyroOffset.offsets[Z] = 512 * GYRO_OVERSAMPLING_Z;
// This will get the DACs for FC1.3 to offset to a reasonable value.
gyro_calibrate();
}
 
gyroActivity = 0;
if (accelOffset_readFromEEProm()) {
printf("acc. meter offsets invalid%s", recal);
accelOffset.offsets[X] = accelOffset.offsets[Y] = 512 * ACCEL_OVERSAMPLING_XY;
accelOffset.offsets[Z] = 512 * ACCEL_OVERSAMPLING_Z;
if (IMUConfig.imuReversedFlags & IMU_REVERSE_ACCEL_Z) {
accelOffset.offsets[Z] -= ACCEL_G_FACTOR_Z;
} else {
accelOffset.offsets[Z] += ACCEL_G_FACTOR_Z;
}
}
 
// Noise is relative to offset. So, reset noise measurements when changing offsets.
for (uint8_t i=X; i<=Y; i++) {
// gyroNoisePeak[i] = 0;
gyroD[i] = 0;
for (uint8_t j=0; j<GYRO_D_WINDOW_LENGTH; j++) {
gyroDWindow[i][j] = 0;
}
}
// Setting offset values has an influence in the analog.c ISR
// Therefore run measurement for 100ms to achive stable readings
waitADCCycle(100);
}
 
void analog_calibrateGyros(void) {
#define GYRO_OFFSET_CYCLES 32
uint8_t i, axis;
int32_t offsets[3] = { 0, 0, 0 };
gyro_calibrate();
// determine gyro bias by averaging (requires that the copter does not rotate around any axis!)
for (i = 0; i < GYRO_OFFSET_CYCLES; i++) {
delay_ms_with_adc_measurement(10, 1);
for (axis = PITCH; axis <= YAW; axis++) {
offsets[axis] += rawGyroValue(axis);
#define GYRO_OFFSET_CYCLES 100
uint8_t i, axis;
int32_t offsets[3] = { 0, 0, 0 };
 
flightControlStatus = BLOCKED_FOR_CALIBRATION;
delay_ms(10);
 
gyro_calibrate();
 
// determine gyro bias by averaging (requires that the copter does not rotate around any axis!)
for (i = 0; i < GYRO_OFFSET_CYCLES; i++) {
waitADCCycle(5);
for (axis=X; axis<=Z; axis++) {
offsets[axis] += gyroValue(axis, samplingADCData);
}
}
}
for (axis = PITCH; axis <= YAW; axis++) {
gyroOffset.offsets[axis] = (offsets[axis] + GYRO_OFFSET_CYCLES / 2) / GYRO_OFFSET_CYCLES;
 
int16_t min = (512-200) * (axis==YAW) ? GYRO_OVERSAMPLING_YAW : GYRO_OVERSAMPLING_PITCHROLL;
int16_t max = (512+200) * (axis==YAW) ? GYRO_OVERSAMPLING_YAW : GYRO_OVERSAMPLING_PITCHROLL;
if(gyroOffset.offsets[axis] < min || gyroOffset.offsets[axis] > max)
versionInfo.hardwareErrors[0] |= FC_ERROR0_GYRO_PITCH << axis;
}
for (axis=X; axis<=Z; axis++) {
gyroOffset.offsets[axis] = (offsets[axis] + GYRO_OFFSET_CYCLES/2) / GYRO_OFFSET_CYCLES;
int16_t min = (512 - 200) * (axis==Z) ? GYRO_OVERSAMPLING_Z : GYRO_OVERSAMPLING_XY;
int16_t max = (512 + 200) * (axis==Z) ? GYRO_OVERSAMPLING_Z : GYRO_OVERSAMPLING_XY;
if (gyroOffset.offsets[axis] < min || gyroOffset.offsets[axis] > max)
versionInfo.hardwareErrors[0] |= FC_ERROR0_GYRO_X << axis;
}
 
gyroOffset_writeToEEProm();
startAnalogConversionCycle();
gyroOffset_writeToEEProm();
//startADCCycle();
}
 
/*
615,59 → 664,62
* directly from here, though.
*/
void analog_calibrateAcc(void) {
#define ACC_OFFSET_CYCLES 32
uint8_t i, axis;
int32_t offsets[3] = { 0, 0, 0 };
#define ACCEL_OFFSET_CYCLES 100
uint8_t i, axis;
int32_t offsets[3] = { 0, 0, 0 };
 
for (i = 0; i < ACC_OFFSET_CYCLES; i++) {
delay_ms_with_adc_measurement(10, 1);
for (axis = PITCH; axis <= YAW; axis++) {
offsets[axis] += rawAccValue(axis);
flightControlStatus = BLOCKED_FOR_CALIBRATION;
delay_ms(10);
 
for (i = 0; i < ACCEL_OFFSET_CYCLES; i++) {
waitADCCycle(5);
for (axis=X; axis<=Z; axis++) {
offsets[axis] += accValue(axis, samplingADCData);
}
}
}
 
for (axis = PITCH; axis <= YAW; axis++) {
accOffset.offsets[axis] = (offsets[axis] + ACC_OFFSET_CYCLES / 2) / ACC_OFFSET_CYCLES;
int16_t min,max;
if (axis==Z) {
if (IMUConfig.imuReversedFlags & IMU_REVERSE_ACC_Z) {
// TODO: This assumes a sensitivity of +/- 2g.
min = (256-200) * ACC_OVERSAMPLING_Z;
max = (256+200) * ACC_OVERSAMPLING_Z;
} else {
// TODO: This assumes a sensitivity of +/- 2g.
min = (768-200) * ACC_OVERSAMPLING_Z;
max = (768+200) * ACC_OVERSAMPLING_Z;
}
for (axis=X; axis<=Z; axis++) {
accelOffset.offsets[axis] = (offsets[axis] + ACCEL_OFFSET_CYCLES / 2) / ACCEL_OFFSET_CYCLES;
int16_t min, max;
if (axis == Z) {
if (IMUConfig.imuReversedFlags & IMU_REVERSE_ACCEL_Z) {
// TODO: This assumes a sensitivity of +/- 2g.
min = (256 - 200) * ACCEL_OVERSAMPLING_Z;
max = (256 + 200) * ACCEL_OVERSAMPLING_Z;
} else {
// TODO: This assumes a sensitivity of +/- 2g.
min = (768 - 200) * ACCEL_OVERSAMPLING_Z;
max = (768 + 200) * ACCEL_OVERSAMPLING_Z;
}
} else {
min = (512 - 200) * ACCEL_OVERSAMPLING_XY;
max = (512 + 200) * ACCEL_OVERSAMPLING_XY;
}
if (gyroOffset.offsets[axis] < min || gyroOffset.offsets[axis] > max) {
versionInfo.hardwareErrors[0] |= FC_ERROR0_ACCEL_X << axis;
}
}
 
if (IMUConfig.imuReversedFlags & IMU_REVERSE_ACCEL_Z) {
accelOffset.offsets[Z] -= ACCEL_G_FACTOR_Z;
} else {
min = (512-200) * ACC_OVERSAMPLING_XY;
max = (512+200) * ACC_OVERSAMPLING_XY;
accelOffset.offsets[Z] += ACCEL_G_FACTOR_Z;
}
if(gyroOffset.offsets[axis] < min || gyroOffset.offsets[axis] > max) {
versionInfo.hardwareErrors[0] |= FC_ERROR0_ACC_X << axis;
}
}
 
accOffset_writeToEEProm();
startAnalogConversionCycle();
accelOffset_writeToEEProm();
// startADCCycle();
}
 
void analog_setGround() {
groundPressure = filteredAirPressure;
groundPressure = filteredAirPressure;
}
 
int32_t analog_getHeight(void) {
return groundPressure - filteredAirPressure;
int32_t height = groundPressure - filteredAirPressure;
debugOut.analog[28] = height;
return height;
}
 
int16_t analog_getDHeight(void) {
/*
int16_t result = 0;
for (int i=0; i<staticParams.airpressureDWindowLength; i++) {
result -= dAirPressureWindow[i]; // minus pressure is plus height.
}
// dHeight = -dPressure, so here it is the old pressure minus the current, not opposite.
return result;
*/
return dHeight;
return dHeight;
}