Subversion Repositories FlightCtrl

Compare Revisions

Ignore whitespace Rev 2108 → Rev 2109

/branches/dongfang_FC_fixedwing/arduino_atmega328/invenSense.d
File deleted
/branches/dongfang_FC_fixedwing/arduino_atmega328/invenSense.c
File deleted
/branches/dongfang_FC_fixedwing/arduino_atmega328/invenSense.lst
File deleted
/branches/dongfang_FC_fixedwing/arduino_atmega328/ADXRS610_FC2.0.c
File deleted
/branches/dongfang_FC_fixedwing/arduino_atmega328/sensors.h
File deleted
/branches/dongfang_FC_fixedwing/arduino_atmega328/README.txt
16,8 → 16,8
 
PD0 RxD serial for configuration, diags etc.
PD1 TxD serial for configuration, diags etc.
PD2 unused
PD3/OC2B: CLK of 4017
PD2 Performance analysis
PD3/OC2B: CLK of 4017 change B3
PD4: RESET of 4017
PD5 Beeper
PD6,7 LEDs
/branches/dongfang_FC_fixedwing/arduino_atmega328/analog.c
44,8 → 44,8
*/
uint32_t airpressure;
uint16_t airspeedVelocity = 0;
int16_t airpressureWindow[AIRPRESSURE_WINDOW_LENGTH];
uint8_t airpressureWindowIdx = 0;
//int16_t airpressureWindow[AIRPRESSURE_WINDOW_LENGTH];
//uint8_t airpressureWindowIdx = 0;
 
/*
* Offset values. These are the raw gyro and acc. meter sums when the copter is
212,8 → 212,6
}
 
void startAnalogConversionCycle(void) {
sensorDataReady = 0;
 
// Stop the sampling. Cycle is over.
for (uint8_t i = 0; i<8; i++) {
ADSensorInputs[i] = 0;
224,6 → 222,7
ADMUX = (ADMUX & 0xE0) | adChannel;
startADC();
twimaster_startCycle();
sensorDataReady = 0;
}
 
/*****************************************************
308,17 → 307,25
void analog_updateAirspeed(void) {
uint16_t rawAirpressure = ADSensorInputs[AD_AIRPRESSURE];
int16_t temp = rawAirpressure - airpressureOffset;
airpressure -= airpressureWindow[airpressureWindowIdx];
airpressure += temp;
airpressureWindow[airpressureWindowIdx] = temp;
airpressureWindowIdx++;
if (airpressureWindowIdx == AIRPRESSURE_WINDOW_LENGTH) {
airpressureWindowIdx = 0;
}
// airpressure -= airpressureWindow[airpressureWindowIdx];
// airpressure += temp;
// airpressureWindow[airpressureWindowIdx] = temp;
// airpressureWindowIdx++;
// if (airpressureWindowIdx == AIRPRESSURE_WINDOW_LENGTH) {
// airpressureWindowIdx = 0;
// }
 
if (temp<0) temp = 0;
airspeedVelocity = (staticParams.airspeedCorrection * isqrt32(airpressure)) >> LOG_AIRSPEED_FACTOR;
isFlying = (airspeedVelocity >= staticParams.isFlyingThreshold);
#define AIRPRESSURE_FILTER 16
airpressure = ((int32_t)airpressure * (AIRPRESSURE_FILTER-1) + (AIRPRESSURE_FILTER/2) + temp) / AIRPRESSURE_FILTER;
 
uint16_t p2 = (airpressure<0) ? 0 : airpressure;
airspeedVelocity = (staticParams.airspeedCorrection * isqrt16(p2)) >> LOG_AIRSPEED_FACTOR;
debugOut.analog[17] = airpressure;
debugOut.analog[18] = airpressureOffset;
debugOut.analog[19] = airspeedVelocity;
isFlying = 0; //(airspeedVelocity >= staticParams.isFlyingThreshold);
}
 
void analog_updateBatteryVoltage(void) {
355,10 → 362,6
}
}
 
for (uint8_t i=0; i<AIRPRESSURE_WINDOW_LENGTH; i++) {
airpressureWindow[i] = 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);
367,7 → 370,7
}
 
void analog_calibrate(void) {
#define OFFSET_CYCLES 64
#define OFFSET_CYCLES 32
uint8_t i, axis;
int32_t offsets[4] = { 0, 0, 0, 0};
382,15 → 385,12
for (axis = PITCH; axis <= YAW; axis++) {
gyroOffset.offsets[axis] = (offsets[axis] + OFFSET_CYCLES / 2) / OFFSET_CYCLES;
int16_t min = (512-200) * GYRO_OVERSAMPLING;
int16_t max = (512+200) * GYRO_OVERSAMPLING;
if(gyroOffset.offsets[axis] < min || gyroOffset.offsets[axis] > max)
versionInfo.hardwareErrors[0] |= FC_ERROR0_GYRO_PITCH << axis;
}
 
airpressureOffset = (offsets[3] + OFFSET_CYCLES / 2) / OFFSET_CYCLES;
int16_t min = 200;
int16_t max = (1024-200) * 2;
int16_t max = 1024-200;
 
if(airpressureOffset < min || airpressureOffset > max)
versionInfo.hardwareErrors[0] |= FC_ERROR0_PRESSURE;
 
/branches/dongfang_FC_fixedwing/arduino_atmega328/attitude.c
59,7 → 59,7
*/
 
void setStaticAttitudeAngles(void) {
attitude[PITCH] = attitude[ROLL] = 0;
attitude[PITCH] = attitude[ROLL] = attitude[YAW] = 0;
}
 
/************************************************************************
/branches/dongfang_FC_fixedwing/arduino_atmega328/commands.c
19,8 → 19,6
uint8_t command = controlMixer_getCommand();
uint8_t repeated = controlMixer_isCommandRepeated();
uint8_t argument = controlMixer_getArgument();
 
// TODO! Mode change gadget of some kind.
if (!isFlying) {
if (command == COMMAND_GYROCAL && !repeated) {
// Gyro calinbration, with or without selecting a new parameter-set.
/branches/dongfang_FC_fixedwing/arduino_atmega328/configuration.c
85,6 → 85,9
staticParams.externalControl = 0;
staticParams.IFactor = 52;
 
staticParams.airspeedCorrection = 100;
staticParams.isFlyingThreshold = 100;
 
// Servos
staticParams.servoCount = 7;
staticParams.servoManualMaxSpeed = 10;
105,6 → 108,7
staticParams.gyroPID[i].P = 80;
staticParams.gyroPID[i].I = 80;
staticParams.gyroPID[i].D = 40;
staticParams.gyroPID[i].iMax = 45;
}
 
staticParams.stickIElevator = 80;
/branches/dongfang_FC_fixedwing/arduino_atmega328/controlMixer.c
54,6 → 54,7
int16_t targetvalue;
for (i=0; i < VARIABLE_COUNT; i++) {
targetvalue = RC_getVariable(i);
if (i<2) debugOut.analog[18+i] = targetvalue;
if (targetvalue < 0)
targetvalue = 0;
if (variables[i] < targetvalue && variables[i] < 255)
/branches/dongfang_FC_fixedwing/arduino_atmega328/flight.c
107,9 → 107,9
term[CONTROL_THROTTLE] = controls[CONTROL_THROTTLE];
 
// These params are just left the same in all modes. In MANUAL and RATE the results are ignored anyway.
target[PITCH] += (controls[CONTROL_ELEVATOR] * staticParams.stickIElevator) >> 6;
target[ROLL] += (controls[CONTROL_AILERONS] * staticParams.stickIAilerons) >> 6;
target[YAW] += (controls[CONTROL_RUDDER] * staticParams.stickIRudder) >> 6;
target[PITCH] += (controls[CONTROL_ELEVATOR] * staticParams.stickIElevator) >> 7;
target[ROLL] += (controls[CONTROL_AILERONS] * staticParams.stickIAilerons) >> 7;
target[YAW] += (controls[CONTROL_RUDDER] * staticParams.stickIRudder) >> 7;
 
for (axis = PITCH; axis <= YAW; axis++) {
if (target[axis] > OVER180) {
/branches/dongfang_FC_fixedwing/arduino_atmega328/main.c
30,7 → 30,7
 
// This is strange: It should NOT be necessarty to do. But the call of the same,
// in channelMap_readOrDefault (if eeprom read fails) just sets all to 0,0,0,....
channelMap_default();
channelMap_default();
 
// initalize modules
output_init();
52,7 → 52,8
printf("\n\rFlightControl");
printf("\n\rHardware: Custom");
printf("\n\r CPU: Atmega328");
printf("\n\rSoftware: V%d.%d%c",VERSION_MAJOR, VERSION_MINOR, VERSION_PATCH + 'a');
printf("\n\rSoftware: V%d.%d%c",
VERSION_MAJOR, VERSION_MINOR, VERSION_PATCH + 'a');
printf("\n\r===================================");
 
// Wait for a short time (otherwise the RC channel check won't work below)
62,7 → 63,7
// Instead, while away the time by flashing the 2 outputs:
// First J16, then J17. Makes it easier to see which is which.
timer = setDelay(200);
outputSet(0,1);
outputSet(0, 1);
GRN_OFF;
RED_ON;
while (!checkDelay(timer))
69,8 → 70,8
;
 
timer = setDelay(200);
outputSet(0,0);
outputSet(1,1);
outputSet(0, 0);
outputSet(1, 1);
RED_OFF;
GRN_ON;
while (!checkDelay(timer))
79,10 → 80,10
timer = setDelay(200);
while (!checkDelay(timer))
;
outputSet(1,0);
outputSet(1, 0);
GRN_OFF;
 
printf("\n\r===================================");
printf("\n\r===================================");
 
#ifdef USE_NAVICTRL
printf("\n\rSupport for NaviCtrl");
104,7 → 105,7
 
printf("\n\n\r");
 
while (1) {
while (1) {
if (runFlightControl) { // control interval
runFlightControl = 0; // reset Flag, is enabled every 2 ms by ISR of timer0
if (sensorDataReady != ALL_DATA_READY) {
112,58 → 113,42
debugOut.digital[0] |= DEBUG_MAINLOOP_TIMER;
} else {
debugOut.digital[0] &= ~DEBUG_MAINLOOP_TIMER;
}
J4HIGH;
// This is probably the correct order:
// The attitude computation should not depend on anything from control (except maybe the estimation of control activity level)
// The control may depend on attitude - for example, attitude control uses pitch and roll angles, compass control uses yaw angle etc.
// Flight control uses results from both.
calculateFlightAttitude();
controlMixer_periodicTask();
commands_handleCommands();
flight_control();
J4LOW;
 
J4HIGH;
// This is probably the correct order:
// The attitude computation should not depend on anything from control (except maybe the estimation of control activity level)
// The control may depend on attitude - for example, attitude control uses pitch and roll angles, compass control uses yaw angle etc.
// Flight control uses results from both.
calculateFlightAttitude();
controlMixer_periodicTask();
commands_handleCommands();
flight_control();
J4LOW;
// Allow Serial Data Transmit if motors must not updated or motors are not running
if (!runFlightControl || !isFlying) {
usart0_transmitTxData();
}
// Allow Serial Data Transmit if motors must not updated or motors are not running
if (!runFlightControl || !isFlying) {
usart0_transmitTxData();
}
 
usart0_processRxData();
usart0_processRxData();
 
if (checkDelay(timer)) {
if (UBat <= UBAT_AT_5V) {
// Do nothing. The voltage on the input side of the regulator is <5V;
// we must be running off USB power. Keep it quiet.
} else if (UBat < staticParams.batteryVoltageWarning) {
beepBatteryAlarm();
}
 
#ifdef USE_NAVICTRL
SPI_StartTransmitPacket();
SendSPI = 4;
#endif
timer = setDelay(20); // every 20 ms
}
output_update();
if (checkDelay(timer)) {
// Do nothing. The voltage on the input side of the regulator is <5V;
// we must be running off USB power. Keep it quiet.
} else if (UBat < staticParams.batteryVoltageWarning && UBat > UBAT_AT_5V) {
beepBatteryAlarm();
}
 
#ifdef USE_NAVICTRL
if(!SendSPI) {
// SendSPI is decremented in timer0.c with a rate of 9.765 kHz.
// within the SPI_TransmitByte() routine the value is set to 4.
// I.e. the SPI_TransmitByte() is called at a rate of 9.765 kHz/4= 2441.25 Hz,
// and therefore the time of transmission of a complete spi-packet (32 bytes) is 32*4/9.765 kHz = 13.1 ms.
SPI_TransmitByte();
}
#endif
calculateFeaturedServoValues();
timer = setDelay(20); // every 20 ms
output_update();
}
 
if (runFlightControl) { // Time for the next iteration was up before the current finished. Signal error.
debugOut.digital[1] |= DEBUG_MAINLOOP_TIMER;
} else {
debugOut.digital[1] &= ~DEBUG_MAINLOOP_TIMER;
}
calculateFeaturedServoValues();
 
if (runFlightControl) { // Time for the next iteration was up before the current finished. Signal error.
debugOut.digital[1] |= DEBUG_MAINLOOP_TIMER;
} else {
debugOut.digital[1] &= ~DEBUG_MAINLOOP_TIMER;
}
}
return (1);
/branches/dongfang_FC_fixedwing/arduino_atmega328/makefile
1,8 → 1,8
#--------------------------------------------------------------------
# MCU name
MCU = atmega328
F_CPU = 16000000
QUARZ = 16MHZ
F_CPU = 8000000
QUARZ = 8MHZ
 
#-------------------------------------------------------------------
VERSION_MAJOR = 0
13,15 → 13,9
VERSION_SERIAL_MINOR = 1 # Serial Protocol Minor Version
NC_SPI_COMPATIBLE = 6 # SPI Protocol Version
 
# Set up for cross axis gyros. Factors increased by sqrt(2).
#GYRO=ADXRS610_FC2.0
#GYRO_HW_NAME=ADXR
#GYRO_HW_FACTOR="(1.2288f * 1.4142)"
#GYRO_CORRECTION=1.0f
 
GYRO=invenSense
GYRO_HW_NAME=Isense
GYRO_HW_FACTOR=0.6827f
GYRO=IMU3200
GYRO_HW_NAME=IMU3200
GYRO_HW_FACTOR=1.45f
GYRO_CORRECTION=1.0f
 
#-------------------------------------------------------------------
/branches/dongfang_FC_fixedwing/arduino_atmega328/output.h
7,9 → 7,9
#define J3LOW PORTD &= ~(1<<PORTD5)
#define J3TOGGLE PORTD ^= (1<<PORTD5)
 
#define J4HIGH PORTD |= (1<<PORTD4)
#define J4LOW PORTD &= ~(1<<PORTD4)
#define J4TOGGLE PORTD ^= (1<<PORTD4)
#define J4HIGH PORTD |= (1<<PORTD2)
#define J4LOW PORTD &= ~(1<<PORTD2)
#define J4TOGGLE PORTD ^= (1<<PORTD2)
 
#define J5HIGH PORTD |= (1<<PORTD3)
#define J5LOW PORTD &= ~(1<<PORTD3)
/branches/dongfang_FC_fixedwing/arduino_atmega328/rc.c
15,6 → 15,8
uint8_t lastRCCommand = COMMAND_NONE;
uint8_t lastFlightMode = FLIGHT_MODE_NONE;
 
#define TIME(s) ((int16_t)(((long)F_CPU/(long)8000)*(float)s))
 
/***************************************************************
* 16bit timer 1 is used to decode the PPM-Signal
***************************************************************/
25,22 → 27,9
cli();
 
// PPM-signal is connected to the Input Capture Pin (PD6) of timer 1
DDRD &= ~(1<<6);
PORTD |= (1<<PORTD6);
DDRB &= ~(1<<0);
PORTB |= (1<<PORTB0);
 
// Channel 5,6,7 is decoded to servo signals at pin PD5 (J3), PD4(J4), PD3(J5)
// set as output
DDRD |= (1<<DDD5) | (1<<DDD4) | (1<<DDD3);
// low level
PORTD &= ~((1<<PORTD5) | (1<<PORTD4) | (1<<PORTD3));
 
// PD3 can't be used if 2nd UART is activated
// because TXD1 is at that port
// if (CPUType != ATMEGA644P) {
// DDRD |= (1<<PORTD3);
// PORTD &= ~(1<<PORTD3);
// }
 
// Timer/Counter1 Control Register A, B, C
// Normal Mode (bits: WGM13=0, WGM12=0, WGM11=0, WGM10=0)
// Compare output pin A & B is disabled (bits: COM1A1=0, COM1A0=0, COM1B1=0, COM1B0=0)
51,7 → 40,7
// The longest period is 0xFFFF / 312.5 kHz = 0.209712 s.
TCCR1A &= ~((1 << COM1A1) | (1 << COM1A0) | (1 << COM1B1) | (1 << COM1B0) | (1 << WGM11) | (1 << WGM10));
TCCR1B &= ~((1 << WGM13) | (1 << WGM12) | (1 << CS12));
TCCR1B |= (1 << CS11) | (1 << CS10) | (1 << ICES1) | (1 << ICNC1);
TCCR1B |= (1 << CS11) | (1 << ICES1) | (1 << ICNC1);
TCCR1C &= ~((1 << FOC1A) | (1 << FOC1B));
 
// Timer/Counter1 Interrupt Mask Register
88,7 → 77,7
the syncronization gap.
*/
ISR(TIMER1_CAPT_vect) { // typical rate of 1 ms to 2 ms
int16_t signal = 0, tmp;
int16_t signal, tmp;
static int16_t index;
static uint16_t oldICR1 = 0;
 
101,18 → 90,19
signal = (uint16_t) ICR1 - oldICR1;
oldICR1 = ICR1;
 
//sync gap? (3.52 ms < signal < 25.6 ms)
if ((signal > 1100) && (signal < 8000)) {
//sync gap? (3.5 ms < signal < 25.6 ms)
if (signal > TIME(3.5)) {
// never happens...
index = 0;
} else { // within the PPM frame
if (index < MAX_CHANNELS) { // PPM24 supports 12 channels
// check for valid signal length (0.8 ms < signal < 2.1984 ms)
// signal range is from 1.0ms/3.2us = 312 to 2.0ms/3.2us = 625
if ((signal > 250) && (signal < 687)) {
// check for valid signal length (0.8 ms < signal < 2.2 ms)
if ((signal >= TIME(0.8)) && (signal < TIME(2.2))) {
// shift signal to zero symmetric range -154 to 159
signal -= 475; // offset of 1.4912 ms ??? (469 * 3.2us = 1.5008 ms)
//signal -= 3750; // theoretical value
signal -= (TIME(1.5) + RC_TRIM); // best value with my Futaba in zero trim.
// check for stable signal
if (abs(signal - PPM_in[index]) < 6) {
if (abs(signal - PPM_in[index]) < TIME(0.05)) {
if (RCQuality < 200)
RCQuality += 10;
else
145,16 → 135,12
}
 
#define RCChannel(dimension) PPM_in[channelMap.channels[dimension]]
#define COMMAND_THRESHOLD 85
#define COMMAND_CHANNEL_VERTICAL CH_THROTTLE
#define COMMAND_CHANNEL_HORIZONTAL CH_YAW
 
#define RC_SCALING 4
 
uint8_t getControlModeSwitch(void) {
int16_t channel = RCChannel(CH_MODESWITCH) + POT_OFFSET;
uint8_t flightMode = channel < 256/3 ? FLIGHT_MODE_MANUAL :
(channel > 256*2/3 ? FLIGHT_MODE_ANGLES : FLIGHT_MODE_RATE);
int16_t channel = RCChannel(CH_MODESWITCH);
uint8_t flightMode = channel < -TIME(0.17) ? FLIGHT_MODE_MANUAL : (channel > TIME(0.17) ? FLIGHT_MODE_ANGLES : FLIGHT_MODE_RATE);
return flightMode;
}
 
174,10 → 160,12
 
int16_t channel = RCChannel(CH_THROTTLE);
 
if (channel <= -140) { // <= 900 us
lastRCCommand = COMMAND_GYROCAL;
if (channel <= -TIME(0.55)) {
lastRCCommand = COMMAND_GYROCAL;
debugOut.analog[17] = 1;
} else {
lastRCCommand = COMMAND_NONE;
debugOut.analog[17] = 0;
}
return lastRCCommand;
}
198,10 → 186,10
debugOut.analog[22] = RCChannel(CH_RUDDER);
debugOut.analog[23] = RCChannel(CH_THROTTLE);
 
PRYT[CONTROL_ELEVATOR] = RCChannel(CH_ELEVATOR) * RC_SCALING;
PRYT[CONTROL_AILERONS] = RCChannel(CH_AILERONS) * RC_SCALING;
PRYT[CONTROL_RUDDER] = RCChannel(CH_RUDDER) * RC_SCALING;
PRYT[CONTROL_THROTTLE] = RCChannel(CH_THROTTLE) * RC_SCALING;
PRYT[CONTROL_ELEVATOR] = RCChannel(CH_ELEVATOR) / RC_SCALING;
PRYT[CONTROL_AILERONS] = RCChannel(CH_AILERONS) / RC_SCALING;
PRYT[CONTROL_RUDDER] = RCChannel(CH_RUDDER) / RC_SCALING;
PRYT[CONTROL_THROTTLE] = RCChannel(CH_THROTTLE) / RC_SCALING;
} // if RCQuality is no good, we just do nothing.
}
 
211,12 → 199,12
int16_t RC_getVariable(uint8_t varNum) {
if (varNum < 4)
// 0th variable is 5th channel (1-based) etc.
return RCChannel(varNum + CH_POTS) + POT_OFFSET;
return (RCChannel(varNum + CH_POTS) >> 2) + VARIABLE_OFFSET;
/*
* Let's just say:
* The RC variable i is hardwired to channel i, i>=4
*/
return PPM_in[varNum] + POT_OFFSET;
return (PPM_in[varNum] >> 2) + VARIABLE_OFFSET;
}
 
uint8_t RC_getSignalQuality(void) {
/branches/dongfang_FC_fixedwing/arduino_atmega328/rc.h
21,8 → 21,14
#define CH_RUDDER 3
#define CH_MODESWITCH 4
#define CH_POTS 4
#define POT_OFFSET 120
 
// These are a little individual for differnt R/C systems... trim for zero channel readings at zero
// stick, and trim VARIABLE_OFFSET for full variable range 0..255.
#define VARIABLE_OFFSET 106
#define RC_TRIM 19
// Set this for a full stick range of about -1024..1024.
#define RC_SCALING 1
 
/*
int16_t RC_getPitch (void);
int16_t RC_getYaw (void);
/branches/dongfang_FC_fixedwing/arduino_atmega328/timer0.c
32,9 → 32,9
// disable all interrupts before reconfiguration
cli();
 
// Configure speaker port as output.
DDRD |= (1 << DDD5);
PORTD &= ~(1 << PORTD5);
// Configure speaker port as output and also the diags pin D2
DDRD |= ((1 << DDD5) | (1 << DDD2));
PORTD &= ~((1 << PORTD5) | (1 << DDD2));
 
// Timer/Counter 0 Control Register A
 
142,6 → 142,7
uint16_t t_stop;
t_stop = setDelay(w);
while (!checkDelay(t_stop)) {
debugOut.analog[30]++;
if (sensorDataReady == ALL_DATA_READY) {
analog_update();
startAnalogConversionCycle();
150,6 → 151,6
if (stop) {
// Wait for new samples to get prepared but do not restart AD conversion after that!
// Caller MUST to that.
while (!sensorDataReady != ALL_DATA_READY);
// while (!sensorDataReady != ALL_DATA_READY);
}
}
/branches/dongfang_FC_fixedwing/arduino_atmega328/timer2.c
44,9 → 44,10
cli();
 
// set PD7 as output of the PWM for pitch servo
DDRD |= (1 << DDD3);
PORTD &= ~(1 << PORTD3); // set PD7 to low
DDRB |= (1 << DDB3);
PORTB &= ~(1 << PORTB3); // set PD7 to low
 
// oc2b DDRD |= (1 << DDD4); // set PC6 as output (Reset for HEF4017)
DDRD |= (1 << DDD4); // set PC6 as output (Reset for HEF4017)
HEF4017R_ON; // enable reset
 
54,8 → 55,10
// Timer Mode is CTC (Bits: WGM22 = 0, WGM21 = 1, WGM20 = 0)
// PD3: Output OCR2 match, (Bits: COM2B1 = 1, COM2B0 = 0)
// PB3: Normal port operation, OC2A disconnected, (Bits: COM2A1 = 0, COM2A0 = 0)
TCCR2A &= ~((1 << COM2B0) | (1 << COM2A1) | (1 << COM2A0) | (1 << WGM20) | (1 << WGM22));
TCCR2A |= (1 << COM2B1) | (1 << WGM21);
// ardu TCCR2A &= ~((1 << COM2B0) | (1 << COM2A1) | (1 << COM2A0) | (1 << WGM20) | (1 << WGM22));
// ardu TCCR2A |= (1 << COM2B1) | (1 << WGM21);
TCCR2A &= ~((1 << COM2A0) | (1 << COM2B1) | (1 << COM2B0) | (1 << WGM20) | (1 << WGM22));
TCCR2A |= (1 << COM2A1) | (1 << WGM21);
 
// Timer/Counter 2 Control Register B
 
/branches/dongfang_FC_fixedwing/arduino_atmega328/twimaster.c
1,5 → 1,6
#include "twimaster.h"
#include "analog.h"
#include "output.h"
#include <inttypes.h>
#include <util/twi.h>
#include <avr/interrupt.h>
43,6 → 44,7
}
 
void I2CReset(void) {
debugOut.analog[29]++;
I2CStop();
TWCR = (1 << TWINT); // reset to original state incl. interrupt flag reset
TWAMR = 0;
61,8 → 63,12
}
 
void twimaster_startCycle(void) {
twiState = TWI_STATE_LOOP_0;
I2CStart();
if (sensorDataReady & TWI_DATA_READY) { // if OK last time
twiState = TWI_STATE_LOOP_0;
I2CStart();
} else { // go get em.
I2CReset();
}
}
 
const uint8_t EXPECTED_STATUS[] = { START, MT_SLA_ACK, MT_DATA_ACK,
145,6 → 151,7
// Dont re-init the gyro but just restart the loop.
I2CStop();
sensorDataReady |= TWI_DATA_READY;
debugOut.analog[28]++;
break;
}
}
/branches/dongfang_FC_fixedwing/arduino_atmega328/uart0.c
98,9 → 98,9
"Throttle ",
"Term Y ", //15
"Flight mode ",
" ",
" ",
" ",
"Ultralow thr. ",
"Var0 ",
"Var1 ",
"RC P ", //20
"RC R ",
"RC T ",
109,8 → 109,8
"Servo R ", //25
"Servo T ",
"Servo Y ",
" ",
" . ",
"I2C cycles ",
"I2C restarts ",
" ", //30
" "
};