Subversion Repositories FlightCtrl

Compare Revisions

Ignore whitespace Rev 2095 → Rev 2096

/branches/dongfang_FC_fixedwing/analog.c
1,22 → 1,28
#include <avr/io.h>
#include <avr/interrupt.h>
#include <avr/pgmspace.h>
#include <stdlib.h>
 
#include "analog.h"
#include "attitude.h"
#include "sensors.h"
#include "printf_P.h"
#include "mk3mag.h"
 
// for Delay functions
#include "timer0.h"
 
// For DebugOut
#include "uart0.h"
 
// For reading and writing acc. meter offsets.
#include "eeprom.h"
 
// For DebugOut.Digital
// For debugOut
#include "output.h"
 
// set ADC enable & ADC Start Conversion & ADC Interrupt Enable bit
#define startADC() (ADCSRA |= (1<<ADEN)|(1<<ADSC)|(1<<ADIE))
 
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.
25,9 → 31,9
* reason for the export is that the ENC-03_FC1.3 modules needs them for calibrating
* the offsets with the DAC.
*/
volatile int16_t rawGyroSum[3];
volatile int16_t acc[3];
volatile int16_t filteredAcc[2] = { 0,0 };
volatile uint16_t sensorInputs[8];
int16_t acc[3];
int16_t filteredAcc[3] = { 0,0,0 };
 
/*
* These 4 exported variables are zero-offset. The "PID" ones are used
34,41 → 40,110
* in the attitude control as rotation rates. The "ATT" ones are for
* integration to angles.
*/
volatile int16_t gyro_PID[2];
volatile int16_t gyro_ATT[2];
volatile int16_t gyroD[3];
volatile int16_t yawGyro;
int16_t gyro_PID[2];
int16_t gyro_ATT[2];
int16_t gyroD[2];
int16_t gyroDWindow[2][GYRO_D_WINDOW_LENGTH];
uint8_t gyroDWindowIdx = 0;
int16_t yawGyro;
int16_t magneticHeading;
 
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.
*/
volatile int16_t gyroOffset[3] = { 512 * GYRO_SUMMATION_FACTOR_PITCHROLL, 512
* GYRO_SUMMATION_FACTOR_PITCHROLL, 512 * GYRO_SUMMATION_FACTOR_YAW };
 
volatile int16_t accOffset[3] = { 512 * ACC_SUMMATION_FACTOR_PITCHROLL, 512
* ACC_SUMMATION_FACTOR_PITCHROLL, 512 * ACC_SUMMATION_FACTOR_Z };
sensorOffset_t gyroOffset;
sensorOffset_t accOffset;
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
*/
 
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];
 
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;
}
}
 
/*
* Air pressure
*/
volatile uint8_t rangewidth = 106;
volatile uint8_t rangewidth = 105;
 
// Direct from sensor, irrespective of range.
// volatile uint16_t rawAirPressure;
 
// Value of 2 samples, with range.
volatile uint16_t simpleAirPressure;
uint16_t simpleAirPressure;
 
// Value of AIRPRESSURE_SUMMATION_FACTOR samples, with range, filtered.
volatile int32_t filteredAirPressure;
// Value of AIRPRESSURE_OVERSAMPLING samples, with range, filtered.
int32_t filteredAirPressure;
 
#define MAX_D_AIRPRESSURE_WINDOW_LENGTH 32
//int32_t lastFilteredAirPressure;
int16_t dAirPressureWindow[MAX_D_AIRPRESSURE_WINDOW_LENGTH];
uint8_t dWindowPtr = 0;
 
#define MAX_AIRPRESSURE_WINDOW_LENGTH 32
int16_t airPressureWindow[MAX_AIRPRESSURE_WINDOW_LENGTH];
int32_t windowedAirPressure;
uint8_t windowPtr = 0;
 
// Partial sum of AIRPRESSURE_SUMMATION_FACTOR samples.
volatile int32_t airPressureSum;
int32_t airPressureSum;
 
// The number of samples summed into airPressureSum so far.
volatile uint8_t pressureMeasurementCount;
uint8_t pressureMeasurementCount;
 
/*
* Battery voltage, in units of: 1k/11k / 3V * 1024 = 31.03 per volt.
75,20 → 150,22
* That is divided by 3 below, for a final 10.34 per volt.
* So the initial value of 100 is for 9.7 volts.
*/
volatile int16_t UBat = 100;
int16_t UBat = 100;
 
/*
* Control and status.
*/
volatile uint16_t ADCycleCount = 0;
volatile uint8_t analogDataReady = 1;
 
/*
* Experiment: Measuring vibration-induced sensor noise.
*/
volatile uint16_t gyroNoisePeak[2];
volatile uint16_t accNoisePeak[2];
uint16_t gyroNoisePeak[3];
uint16_t accNoisePeak[3];
 
volatile uint8_t adState;
volatile uint8_t adChannel;
 
// ADC channels
#define AD_GYRO_YAW 0
#define AD_GYRO_ROLL 1
142,22 → 219,35
// 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));
ADMUX &= ~((1<<REFS1)|(1<<REFS0)|(1<<ADLAR));
// set muxer to ADC adc_channel 0 (0 to 7 is a valid choice)
ADMUX = (ADMUX & 0xE0) | AD_GYRO_PITCH;
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 = (0 << ADEN) | (0 << ADSC) | (0 << ADATE) | (1 << ADPS2) | (1
<< ADPS1) | (1 << ADPS0) | (0 << ADIE);
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));
// Start AD conversion
analog_start();
ADCSRB &= ~((1<<ADTS2)|(1<<ADTS1)|(1<<ADTS0));
 
for (uint8_t i=0; i<MAX_AIRPRESSURE_WINDOW_LENGTH; i++) {
airPressureWindow[i] = 0;
}
windowedAirPressure = 0;
 
startAnalogConversionCycle();
 
// restore global interrupt flags
SREG = sreg;
}
 
uint16_t rawGyroValue(uint8_t axis) {
return sensorInputs[AD_GYRO_PITCH-axis];
}
 
uint16_t rawAccValue(uint8_t axis) {
return sensorInputs[AD_ACC_PITCH-axis];
}
 
void measureNoise(const int16_t sensor,
volatile uint16_t* const noiseMeasurement, const uint8_t damping) {
if (sensor > (int16_t) (*noiseMeasurement)) {
176,280 → 266,348
* Max: About 106 * 240 + 2047 = 27487; it is OK with just a 16 bit type.
*/
uint16_t getSimplePressure(int advalue) {
return (uint16_t) OCR0A * (uint16_t) rangewidth + advalue;
uint16_t result = (uint16_t) OCR0A * (uint16_t) rangewidth + advalue;
result += (acc[Z] * (staticParams.airpressureAccZCorrection-128)) >> 10;
return result;
}
 
/*
* 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).
*/
void transformPRGyro(int16_t* result) {
static const uint8_t tab[] = {1,1,0,0-1,-1,-1,0,1};
// Pitch to Pitch part
int8_t pp = PR_GYROS_ORIENTATION_REVERSED ? tab[(GYRO_QUADRANT+4)%8] : tab[GYRO_QUADRANT];
// Pitch to Roll part
int8_t pr = tab[(GYRO_QUADRANT+2)%8];
// Roll to Roll part
int8_t rp = PR_GYROS_ORIENTATION_REVERSED ? tab[(GYRO_QUADRANT+2)%8] : tab[(GYRO_QUADRANT+6)%8];
// Roll to Roll part
int8_t rr = tab[GYRO_QUADRANT];
int16_t pitchIn = result[PITCH];
result[PITCH] = pp*result[PITCH] + pr*result[ROLL];
result[ROLL] = rp*pitchIn + rr*result[ROLL];
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();
}
 
/*****************************************************
* Interrupt Service Routine for ADC
* Runs at 312.5 kHz or 3.2 us. When all states are
* processed the interrupt is disabled and further
* AD conversions are stopped.
* Runs at 312.5 kHz or 3.2 �s. When all states are
* processed further conversions are stopped.
*****************************************************/
ISR(ADC_vect) {
static uint8_t ad_channel = AD_GYRO_PITCH, state = 0;
static uint16_t sensorInputs[8] = { 0, 0, 0, 0, 0, 0, 0, 0 };
static uint16_t pressureAutorangingWait = 25;
uint16_t rawAirPressure;
uint8_t i, axis;
int16_t newrange;
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.
}
}
 
// for various filters...
int16_t tempOffsetGyro[2];
void measureGyroActivity(int16_t newValue) {
gyroActivity += (uint32_t)((int32_t)newValue * newValue);
}
 
sensorInputs[ad_channel] += ADC;
#define GADAMPING 6
void dampenGyroActivity(void) {
static uint8_t cnt = 0;
if (++cnt >= IMUConfig.gyroActivityDamping) {
cnt = 0;
gyroActivity *= (uint32_t)((1L<<GADAMPING)-1);
gyroActivity >>= GADAMPING;
}
}
/*
void dampenGyroActivity(void) {
if (gyroActivity >= 2000) {
gyroActivity -= 2000;
}
}
*/
 
/*
* Actually we don't need this "switch". We could do all the sampling into the
* sensorInputs array first, and all the processing after the last sample.
*/
switch (state++) {
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;
}
}
 
case 8: // Z acc
if (Z_ACC_REVERSED)
acc[Z] = accOffset[Z] - sensorInputs[AD_ACC_Z];
else
acc[Z] = sensorInputs[AD_ACC_Z] - accOffset[Z];
// 2) Apply sign and offset, scale before filtering.
tempOffsetGyro[axis] = (tempGyro - gyroOffset.offsets[axis]) * GYRO_FACTOR_PITCHROLL;
}
 
/*
stronglyFilteredAcc[Z] =
(stronglyFilteredAcc[Z] * 99 + acc[Z] * 10) / 100;
*/
// 2.1: Transform axes.
rotate(tempOffsetGyro, IMUConfig.gyroQuadrant, IMUConfig.imuReversedFlags & IMU_REVERSE_GYRO_PR);
 
break;
for (uint8_t axis=0; axis<2; axis++) {
// 3) Filter.
tempOffsetGyro[axis] = (gyro_PID[axis] * (IMUConfig.gyroPIDFilterConstant - 1) + tempOffsetGyro[axis]) / IMUConfig.gyroPIDFilterConstant;
 
case 11: // yaw gyro
rawGyroSum[YAW] = sensorInputs[AD_GYRO_YAW];
if (YAW_GYRO_REVERSED)
tempOffsetGyro[0] = gyroOffset[YAW] - sensorInputs[AD_GYRO_YAW];
else
tempOffsetGyro[0] = sensorInputs[AD_GYRO_YAW] - gyroOffset[YAW];
gyroD[YAW] = (gyroD[YAW] * (staticParams.DGyroFilter - 1) + (tempOffsetGyro[0] - yawGyro)) / staticParams.DGyroFilter;
yawGyro = tempOffsetGyro[0];
break;
case 13: // roll axis acc.
// 4) Measure noise.
measureNoise(tempOffsetGyro[axis], &gyroNoisePeak[axis], GYRO_NOISE_MEASUREMENT_DAMPING);
 
// We have no sensor installed...
acc[PITCH] = acc[ROLL] = 0;
// 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;
 
for (axis=0; axis<2; axis++) {
filteredAcc[axis] =
(filteredAcc[axis] * (staticParams.accFilter - 1) + acc[axis]) / staticParams.accFilter;
measureNoise(acc[axis], &accNoisePeak[axis], 1);
}
break;
// 6) Done.
gyro_PID[axis] = tempOffsetGyro[axis];
 
case 14: // air pressure
if (pressureAutorangingWait) {
//A range switch was done recently. Wait for steadying.
pressureAutorangingWait--;
DebugOut.Analog[27] = (uint16_t) OCR0A;
DebugOut.Analog[31] = simpleAirPressure;
break;
}
// Prepare tempOffsetGyro for next calculation below...
tempOffsetGyro[axis] = (rawGyroValue(axis) - gyroOffset.offsets[axis]) * GYRO_FACTOR_PITCHROLL;
}
 
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;
}
}
}
/*
* Now process the data for attitude angles.
*/
rotate(tempOffsetGyro, IMUConfig.gyroQuadrant, IMUConfig.imuReversedFlags & IMU_REVERSE_GYRO_PR);
 
// Even if the sample is off-range, use it.
simpleAirPressure = getSimplePressure(rawAirPressure);
DebugOut.Analog[27] = (uint16_t) OCR0A;
DebugOut.Analog[31] = simpleAirPressure;
dampenGyroActivity();
gyro_ATT[PITCH] = tempOffsetGyro[PITCH];
gyro_ATT[ROLL] = tempOffsetGyro[ROLL];
 
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;
} else {
// normal case.
// If AIRPRESSURE_SUMMATION_FACTOR 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;
if (pressureMeasurementCount == AIRPRESSURE_SUMMATION_FACTOR - 1)
airPressureSum += simpleAirPressure / 2;
else
airPressureSum += simpleAirPressure;
}
/*
measureGyroActivity(tempOffsetGyro[PITCH]);
measureGyroActivity(tempOffsetGyro[ROLL]);
*/
measureGyroActivity(gyroD[PITCH]);
measureGyroActivity(gyroD[ROLL]);
 
// 2 samples were added.
pressureMeasurementCount += 2;
if (pressureMeasurementCount >= AIRPRESSURE_SUMMATION_FACTOR) {
filteredAirPressure = (filteredAirPressure * (AIRPRESSURE_FILTER - 1)
+ airPressureSum + AIRPRESSURE_FILTER / 2) / AIRPRESSURE_FILTER;
pressureMeasurementCount = airPressureSum = 0;
}
// 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];
 
break;
// diff -= yawGyro;
// gyroD[YAW] -= gyroDWindow[YAW][gyroDWindowIdx];
// gyroD[YAW] += diff;
// gyroDWindow[YAW][gyroDWindowIdx] = diff;
 
case 16: // pitch and roll gyro.
for (axis=0; axis<2; axis++) {
tempOffsetGyro[axis] = rawGyroSum[axis] = sensorInputs[AD_GYRO_PITCH - axis];
// 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.
// gyroActivity += (uint32_t)(abs(yawGyro)* IMUConfig.yawRateFactor);
measureGyroActivity(yawGyro);
 
if (staticParams.GlobalConfig & CFG_ROTARY_RATE_LIMITER) {
if (tempOffsetGyro[axis] < SENSOR_MIN_PITCHROLL) {
DebugOut.Digital[0] |= DEBUG_SENSORLIMIT;
tempOffsetGyro[axis] = tempOffsetGyro[axis] * EXTRAPOLATION_SLOPE - EXTRAPOLATION_LIMIT;
} else if (tempOffsetGyro[axis] > SENSOR_MAX_PITCHROLL) {
DebugOut.Digital[0] |= DEBUG_SENSORLIMIT;
tempOffsetGyro[axis] = (tempOffsetGyro[axis] - SENSOR_MAX_PITCHROLL) * EXTRAPOLATION_SLOPE + SENSOR_MAX_PITCHROLL;
} else {
DebugOut.Digital[0] &= ~DEBUG_SENSORLIMIT;
}
}
if (++gyroDWindowIdx >= IMUConfig.gyroDWindowLength) {
gyroDWindowIdx = 0;
}
}
 
// 2) Apply sign and offset, scale before filtering.
tempOffsetGyro[axis] = (tempOffsetGyro[axis] - gyroOffset[axis]) * GYRO_FACTOR_PITCHROLL;
}
void analog_updateAccelerometers(void) {
// Pitch and roll axis accelerations.
for (uint8_t axis=0; axis<2; axis++) {
acc[axis] = rawAccValue(axis) - accOffset.offsets[axis];
}
 
// 2.1: Transform axis if configured to.
transformPRGyro(tempOffsetGyro);
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);
}
 
// 3) Scale and filter.
for (axis=0; axis<2; axis++) {
tempOffsetGyro[axis] = (gyro_PID[axis] * (staticParams.PIDGyroFilter - 1) + tempOffsetGyro[axis]) / staticParams.PIDGyroFilter;
// 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];
 
// 4) Measure noise.
measureNoise(tempOffsetGyro[axis], &gyroNoisePeak[axis], GYRO_NOISE_MEASUREMENT_DAMPING);
// debugOut.analog[29] = acc[Z];
}
 
// 5) Differential measurement.
gyroD[axis] = (gyroD[axis] * (staticParams.DGyroFilter - 1) + (tempOffsetGyro[axis] - gyro_PID[axis])) / staticParams.DGyroFilter;
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);
debugOut.analog[6] = rawAirPressure;
debugOut.analog[7] = simpleAirPressure;
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;
} 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) {
 
// 6) Done.
gyro_PID[axis] = tempOffsetGyro[axis];
}
// The best oversampling count is 14.5. We add a quarter of the double ADC value to get the final half.
airPressureSum += simpleAirPressure >> 2;
 
/*
* Now process the data for attitude angles.
*/
for (axis=0; axis<2; axis++) {
tempOffsetGyro[axis] = (rawGyroSum[axis] - gyroOffset[axis]) * GYRO_FACTOR_PITCHROLL;
}
uint32_t lastFilteredAirPressure = filteredAirPressure;
 
transformPRGyro(tempOffsetGyro);
// 2) Filter. This should really be quite unnecessary. The integration should gobble up any noise anyway and the values are not used for anything else.
gyro_ATT[PITCH] = (gyro_ATT[PITCH] * (staticParams.attitudeGyroFilter - 1) + tempOffsetGyro[PITCH]) / staticParams.attitudeGyroFilter;
gyro_ATT[ROLL] = (gyro_ATT[ROLL] * (staticParams.attitudeGyroFilter - 1) + tempOffsetGyro[ROLL]) / staticParams.attitudeGyroFilter;
break;
case 17:
// 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;
DebugOut.Analog[20] = UBat;
analogDataReady = 1; // mark
ADCycleCount++;
// Stop the sampling. Cycle is over.
state = 0;
for (i = 0; i < 8; i++) {
sensorInputs[i] = 0;
}
break;
default: {
} // do nothing.
}
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;
}
 
// set up for next state.
ad_channel = pgm_read_byte(&channelsForStates[state]);
// ad_channel = channelsForStates[state];
// 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;
}
}
}
 
// set adc muxer to next ad_channel
ADMUX = (ADMUX & 0xE0) | ad_channel;
// after full cycle stop further interrupts
if (state)
analog_start();
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;
}
 
void analog_calibrate(void) {
#define GYRO_OFFSET_CYCLES 32
uint8_t i, axis;
int32_t deltaOffsets[3] = { 0, 0, 0 };
void analog_update(void) {
analog_updateGyros();
analog_updateAccelerometers();
analog_updateAirPressure();
analog_updateBatteryVoltage();
#ifdef USE_MK3MAG
magneticHeading = volatileMagneticHeading;
#endif
}
 
gyro_calibrate();
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;
}
 
// 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_Mess(20);
for (axis = PITCH; axis <= YAW; axis++) {
deltaOffsets[axis] += rawGyroSum[axis];
}
}
// Noise is relative to offset. So, reset noise measurements when changing offsets.
for (uint8_t i=PITCH; i<=ROLL; i++) {
gyroNoisePeak[i] = 0;
accNoisePeak[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);
 
for (axis = PITCH; axis <= YAW; axis++) {
gyroOffset[axis] = (deltaOffsets[axis] + GYRO_OFFSET_CYCLES / 2) / GYRO_OFFSET_CYCLES;
// DebugOut.Analog[20 + axis] = gyroOffset[axis];
}
gyroActivity = 0;
}
 
// Noise is relativ to offset. So, reset noise measurements when changing offsets.
gyroNoisePeak[PITCH] = gyroNoisePeak[ROLL] = 0;
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);
}
}
for (axis = PITCH; axis <= YAW; axis++) {
gyroOffset.offsets[axis] = (offsets[axis] + GYRO_OFFSET_CYCLES / 2) / GYRO_OFFSET_CYCLES;
 
accOffset[PITCH] = GetParamWord(PID_ACC_PITCH);
accOffset[ROLL] = GetParamWord(PID_ACC_ROLL);
accOffset[Z] = GetParamWord(PID_ACC_Z);
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;
}
 
// Rough estimate. Hmm no nothing happens at calibration anyway.
// airPressureSum = simpleAirPressure * (AIRPRESSURE_SUMMATION_FACTOR/2);
// pressureMeasurementCount = 0;
 
delay_ms_Mess(100);
gyroOffset_writeToEEProm();
startAnalogConversionCycle();
}
 
/*
460,64 → 618,59
* directly from here, though.
*/
void analog_calibrateAcc(void) {
#define ACC_OFFSET_CYCLES 10
/*
uint8_t i, axis;
int32_t deltaOffset[3] = { 0, 0, 0 };
int16_t filteredDelta;
// int16_t pressureDiff, savedRawAirPressure;
#define ACC_OFFSET_CYCLES 32
uint8_t i, axis;
int32_t offsets[3] = { 0, 0, 0 };
 
for (i = 0; i < ACC_OFFSET_CYCLES; i++) {
delay_ms_Mess(10);
for (axis = PITCH; axis <= YAW; axis++) {
deltaOffset[axis] += acc[axis];
}
}
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);
}
}
 
for (axis = PITCH; axis <= YAW; axis++) {
filteredDelta = (deltaOffset[axis] + ACC_OFFSET_CYCLES / 2)
/ ACC_OFFSET_CYCLES;
accOffset[axis] += ACC_REVERSED[axis] ? -filteredDelta : filteredDelta;
}
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;
}
} else {
min = (512-200) * ACC_OVERSAMPLING_XY;
max = (512+200) * ACC_OVERSAMPLING_XY;
}
if(gyroOffset.offsets[axis] < min || gyroOffset.offsets[axis] > max) {
versionInfo.hardwareErrors[0] |= FC_ERROR0_ACC_X << axis;
}
}
 
// Save ACC neutral settings to eeprom
SetParamWord(PID_ACC_PITCH, accOffset[PITCH]);
SetParamWord(PID_ACC_ROLL, accOffset[ROLL]);
SetParamWord(PID_ACC_Z, accOffset[Z]);
accOffset_writeToEEProm();
startAnalogConversionCycle();
}
 
// Noise is relative to offset. So, reset noise measurements when
// changing offsets.
accNoisePeak[PITCH] = accNoisePeak[ROLL] = 0;
void analog_setGround() {
groundPressure = filteredAirPressure;
}
 
// Setting offset values has an influence in the analog.c ISR
// Therefore run measurement for 100ms to achive stable readings
delay_ms_Mess(100);
int32_t analog_getHeight(void) {
return groundPressure - filteredAirPressure;
}
 
*/
// Set the feedback so that air pressure ends up in the middle of the range.
// (raw pressure high --> OCR0A also high...)
/*
OCR0A += ((rawAirPressure - 1024) / rangewidth) - 1;
delay_ms_Mess(1000);
 
pressureDiff = 0;
// DebugOut.Analog[16] = rawAirPressure;
 
#define PRESSURE_CAL_CYCLE_COUNT 5
for (i=0; i<PRESSURE_CAL_CYCLE_COUNT; i++) {
savedRawAirPressure = rawAirPressure;
OCR0A+=2;
delay_ms_Mess(500);
// raw pressure will decrease.
pressureDiff += (savedRawAirPressure - rawAirPressure);
savedRawAirPressure = rawAirPressure;
OCR0A-=2;
delay_ms_Mess(500);
// raw pressure will increase.
pressureDiff += (rawAirPressure - savedRawAirPressure);
}
 
rangewidth = (pressureDiff + PRESSURE_CAL_CYCLE_COUNT * 2 * 2 - 1) / (PRESSURE_CAL_CYCLE_COUNT * 2 * 2);
DebugOut.Analog[27] = rangewidth;
*/
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;
}
/branches/dongfang_FC_fixedwing/analog.h
1,11 → 1,8
#ifndef _ANALOG_H
#define _ANALOG_H
#include <inttypes.h>
#include "configuration.h"
 
//#include "invenSense.h"
//#include "ENC-03_FC1.3.h"
//#include "ADXRS610_FC2.0.h"
 
/*
About setting constants for different gyros:
Main parameters are positive directions and voltage/angular speed gain.
16,28 → 13,19
- Nose down for pitch
- Left hand side down for roll
- Clockwise seen from above for yaw.
 
Setting gyro gain correctly: All sensor measurements in analog.c take
place in a cycle, each cycle comprising all sensors. Some sensors are
sampled more than ones, and the results added. The pitch and roll gyros
are sampled 4 times and the yaw gyro 2 times in the original H&I V0.74
code.
sampled more than once (oversampled), and the results added.
In the H&I code, the results for pitch and roll are multiplied by 2 (FC1.0)
or 4 (other versions), offset to zero, low pass filtered and then assigned
to the "HiResXXXX" and "AdWertXXXXFilter" variables, where XXXX is nick or
roll.
So:
roll. The factor 2 or 4 or whatever is called GYRO_FACTOR_PITCHROLL here.
*/
#define GYRO_FACTOR_PITCHROLL 1
 
gyro = V * (ADCValue1 + ADCValue2 + ADCValue3 + ADCValue4),
where V is 2 for FC1.0 and 4 for all others.
 
Assuming constant ADCValue, in the H&I code:
gyro = I * ADCValue.
 
where I is 8 for FC1.0 and 16 for all others.
 
The relation between rotation rate and ADCValue:
/*
GYRO_HW_FACTOR is the relation between rotation rate and ADCValue:
ADCValue [units] =
rotational speed [deg/s] *
gyro sensitivity [V / deg/s] *
45,9 → 33,7
1024 [units] /
3V full range [V]
 
or: H is the number of steps the ADC value changes with,
for a 1 deg/s change in rotational velocity:
H = ADCValue [units] / rotation rate [deg/s] =
GYRO_HW_FACTOR is:
gyro sensitivity [V / deg/s] *
amplifier gain [units] *
1024 [units] /
55,78 → 41,40
 
Examples:
FC1.3 has 0.67 mV/deg/s gyros and amplifiers with a gain of 5.7:
H = 0.00067 V / deg / s * 5.7 * 1024 / 3V = 1.304 units/(deg/s).
GYRO_HW_FACTOR = 0.00067 V / deg / s * 5.7 * 1024 / 3V = 1.304 units/(deg/s).
 
FC2.0 has 6*(3/5) mV/deg/s gyros (they are ratiometric) and no amplifiers:
H = 0.006 V / deg / s * 1 * 1024 * 3V / (3V * 5V) = 1.2288 units/(deg/s).
GYRO_HW_FACTOR = 0.006 V / deg / s * 1 * 1024 * 3V / (3V * 5V) = 1.2288 units/(deg/s).
 
My InvenSense copter has 2mV/deg/s gyros and no amplifiers:
H = 0.002 V / deg / s * 1 * 1024 / 3V = 0.6827 units/(deg/s)
GYRO_HW_FACTOR = 0.002 V / deg / s * 1 * 1024 / 3V = 0.6827 units/(deg/s)
(only about half as sensitive as V1.3. But it will take about twice the
rotation rate!)
 
All together: gyro = I * H * rotation rate [units / (deg/s)].
*/
GYRO_HW_FACTOR is given in the makefile.
*/
 
/*
* A factor that the raw gyro values are multiplied by,
* before being filtered and passed to the attitude module.
* A value of 1 would cause a little bit of loss of precision in the
* filtering (on the other hand the values are so noisy in flight that
* it will not really matter - but when testing on the desk it might be
* noticeable). 4 is fine for the default filtering.
* Experiment: Set it to 1.
*/
#define GYRO_FACTOR_PITCHROLL 1
 
/*
* How many samples are summed in one ADC loop, for pitch&roll and yaw,
* How many samples are added in one ADC loop, for pitch&roll and yaw,
* respectively. This is = the number of occurences of each channel in the
* channelsForStates array in analog.c.
*/
#define GYRO_SUMMATION_FACTOR_PITCHROLL 4
#define GYRO_SUMMATION_FACTOR_YAW 2
#define GYRO_OVERSAMPLING_PITCHROLL 4
#define GYRO_OVERSAMPLING_YAW 2
 
#define ACC_SUMMATION_FACTOR_PITCHROLL 2
#define ACC_SUMMATION_FACTOR_Z 1
#define ACC_OVERSAMPLING_XY 2
#define ACC_OVERSAMPLING_Z 1
 
/*
Integration:
The HiResXXXX values are divided by 8 (in H&I firmware) before integration.
In the Killagreg rewrite of the H&I firmware, the factor 8 is called
HIRES_GYRO_AMPLIFY. In this code, it is called HIRES_GYRO_INTEGRATION_FACTOR,
and care has been taken that all other constants (gyro to degree factor, and
180 degree flip-over detection limits) are corrected to it. Because the
division by the constant takes place in the flight attitude code, the
constant is there.
 
The control loop executes every 2ms, and for each iteration
gyro_ATT[PITCH/ROLL] is added to gyroIntegral[PITCH/ROLL].
Assuming a constant rotation rate v and a zero initial gyroIntegral
(for this explanation), we get:
 
gyroIntegral =
N * gyro / HIRES_GYRO_INTEGRATION_FACTOR =
N * I * H * v / HIRES_GYRO_INTEGRATION_FACTOR
 
where N is the number of summations; N = t/2ms.
 
For one degree of rotation: t*v = 1:
 
gyroIntegralXXXX = t/2ms * I * H * 1/t = INTEGRATION_FREQUENCY * I * H / HIRES_GYRO_INTEGRATION_FACTOR.
 
This number (INTEGRATION_FREQUENCY * I * H) is the integral-to-degree factor.
 
Examples:
FC1.3: I=2, H=1.304, HIRES_GYRO_INTEGRATION_FACTOR=8 --> integralDegreeFactor = 1304
FC2.0: I=2, H=2.048, HIRES_GYRO_INTEGRATION_FACTOR=13 --> integralDegreeFactor = 1260
My InvenSense copter: HIRES_GYRO_INTEGRATION_FACTOR=4, H=0.6827 --> integralDegreeFactor = 1365
* The product of the 3 above constants. This represents the expected change in ADC value sums for 1 deg/s of rotation rate.
*/
#define GYRO_RATE_FACTOR_PITCHROLL (GYRO_HW_FACTOR * GYRO_OVERSAMPLING_PITCHROLL * GYRO_FACTOR_PITCHROLL)
#define GYRO_RATE_FACTOR_YAW (GYRO_HW_FACTOR * GYRO_OVERSAMPLING_YAW)
 
/*
* The value of gyro[PITCH/ROLL] for one deg/s = The hardware factor H * the number of samples * multiplier factor.
* Will be about 10 or so for InvenSense, and about 33 for ADXRS610.
*/
#define GYRO_RATE_FACTOR_PITCHROLL (GYRO_HW_FACTOR * GYRO_SUMMATION_FACTOR_PITCHROLL * GYRO_FACTOR_PITCHROLL)
#define GYRO_RATE_FACTOR_YAW (GYRO_HW_FACTOR * GYRO_SUMMATION_FACTOR_YAW)
 
/*
* Gyro saturation prevention.
134,7 → 82,7
// How far from the end of its range a gyro is considered near-saturated.
#define SENSOR_MIN_PITCHROLL 32
// Other end of the range (calculated)
#define SENSOR_MAX_PITCHROLL (GYRO_SUMMATION_FACTOR_PITCHROLL * 1023 - SENSOR_MIN_PITCHROLL)
#define SENSOR_MAX_PITCHROLL (GYRO_OVERSAMPLING_PITCHROLL * 1023 - SENSOR_MIN_PITCHROLL)
// Max. boost to add "virtually" to gyro signal at total saturation.
#define EXTRAPOLATION_LIMIT 2500
// Slope of the boost (calculated)
159,26 → 107,30
* in filtering, and when a gyro becomes near saturated.
* Maybe this distinction is not really necessary.
*/
extern volatile int16_t gyro_PID[2];
extern volatile int16_t gyro_ATT[2];
extern volatile int16_t gyroD[3];
extern volatile int16_t yawGyro;
extern volatile uint16_t ADCycleCount;
extern volatile int16_t UBat;
extern int16_t gyro_PID[2];
extern int16_t gyro_ATT[2];
#define GYRO_D_WINDOW_LENGTH 8
extern int16_t gyroD[3];
extern int16_t yawGyro;
extern int16_t UBat;
 
// 1:11 voltage divider, 1024 counts per 3V, and result is divided by 3.
#define UBAT_AT_5V (int16_t)((5.0 * (1.0/11.0)) * 1024 / (3.0 * 3))
 
extern sensorOffset_t gyroOffset;
extern sensorOffset_t accOffset;
extern sensorOffset_t gyroAmplifierOffset;
 
/*
* This is not really for external use - but the ENC-03 gyro modules needs it.
*/
extern volatile int16_t rawGyroSum[3];
//extern volatile int16_t rawGyroSum[3];
 
/*
* The acceleration values that this module outputs. They are zero based.
*/
extern volatile int16_t acc[3];
extern volatile int16_t filteredAcc[2];
extern int16_t acc[3];
extern int16_t filteredAcc[3];
// extern volatile int32_t stronglyFilteredAcc[3];
 
/*
186,17 → 138,40
* only really reflect the noise level when the copter stands still but with
* its motors running.
*/
extern volatile uint16_t gyroNoisePeak[2];
extern volatile uint16_t accNoisePeak[2];
extern uint16_t gyroNoisePeak[3];
extern uint16_t accNoisePeak[3];
 
/*
* Air pressure.
* The sensor has a sensitivity of 46 mV/kPa.
* An approximate p(h) formula is = p(h[m])[Pa] = p_0 - 11.95 * 10^-3 * h
* That is: dV = 46 mV * 11.95 * 10^-3 dh = 0.5497 mV / m.
* That is, with 2 * 1.024 / 3 steps per mV: 0.037 steps / m
*/
#define AIRPRESSURE_SUMMATION_FACTOR 16
* The sensor has a sensitivity of 45 mV/kPa.
* An approximate p(h) formula is = p(h[m])[kPa] = p_0 - 11.95 * 10^-3 * h
* p(h[m])[kPa] = 101.3 - 11.95 * 10^-3 * h
* 11.95 * 10^-3 * h = 101.3 - p[kPa]
* h = (101.3 - p[kPa])/0.01195
* That is: dV = -45 mV * 11.95 * 10^-3 dh = -0.53775 mV / m.
* That is, with 38.02 * 1.024 / 3 steps per mV: -7 steps / m
 
Display pressures
4165 mV-->1084.7
4090 mV-->1602.4 517.7
3877 mV-->3107.8 1503.4
 
4165 mV-->1419.1
3503 mV-->208.1
Diff.: 1211.0
 
Calculated Vout = 5V(.009P-0.095) --> 5V .009P = Vout + 5V 0.095 --> P = (Vout + 5V 0.095)/(5V 0.009)
4165 mV = 5V(0.009P-0.095) P = 103.11 kPa h = -151.4m
4090 mV = 5V(0.009P-0.095) P = 101.44 kPa h = -11.7m 139.7m
3877 mV = 5V(0.009P-0.095) P = 96.7 kPa h = 385m 396.7m
 
4165 mV = 5V(0.009P-0.095) P = 103.11 kPa h = -151.4m
3503 mV = 5V(0.009P-0.095) P = 88.4 kPa h = 384m Diff: 1079.5m
Pressure at sea level: 101.3 kPa. voltage: 5V * (0.009P-0.095) = 4.0835V
This is OCR2 = 143.15 at 1.5V in --> simple pressure =
*/
 
#define AIRPRESSURE_OVERSAMPLING 14
#define AIRPRESSURE_FILTER 8
// Minimum A/D value before a range change is performed.
#define MIN_RAWPRESSURE (200 * 2)
209,32 → 184,61
#define PRESSURE_EXTRAPOLATION_COEFF 25L
#define AUTORANGE_WAIT_FACTOR 1
 
extern volatile uint16_t simpleAirPressure;
#define ABS_ALTITUDE_OFFSET 108205
 
extern uint16_t simpleAirPressure;
/*
* At saturation, the filteredAirPressure may actually be (simulated) negative.
*/
extern volatile int32_t filteredAirPressure;
extern int32_t filteredAirPressure;
 
extern int16_t magneticHeading;
 
extern uint32_t gyroActivity;
 
/*
* Flag: Interrupt handler has done all A/D conversion and processing.
*/
extern volatile uint8_t analogDataReady;
 
 
void analog_init(void);
 
// clear ADC enable & ADC Start Conversion & ADC Interrupt Enable bit
#define analog_stop() (ADCSRA &= ~((1<<ADEN)|(1<<ADSC)|(1<<ADIE)))
/*
* This is really only for use for the ENC-03 code module, which needs to get the raw value
* for its calibration. The raw value should not be used for anything else.
*/
uint16_t rawGyroValue(uint8_t axis);
 
// set ADC enable & ADC Start Conversion & ADC Interrupt Enable bit
#define analog_start() (ADCSRA |= (1<<ADEN)|(1<<ADSC)|(1<<ADIE))
/*
* Start the conversion cycle. It will stop automatically.
*/
void startAnalogConversionCycle(void);
 
/*
* "Warm" calibration: Zero-offset gyros.
* Process the sensor data to update the exported variables. Must be called after each measurement cycle and before the data is used.
*/
void analog_calibrate(void);
void analog_update(void);
 
/*
* "Cold" calibration: Zero-offset accelerometers and write the calibration data to EEPROM.
* Read gyro and acc.meter calibration from EEPROM.
*/
void analog_setNeutral(void);
 
/*
* Zero-offset gyros and write the calibration data to EEPROM.
*/
void analog_calibrateGyros(void);
 
/*
* Zero-offset accelerometers and write the calibration data to EEPROM.
*/
void analog_calibrateAcc(void);
 
 
void analog_setGround(void);
 
int32_t analog_getHeight(void);
int16_t analog_getDHeight(void);
 
#endif //_ANALOG_H