code:parafoil_tsip
Differences
This shows you the differences between two versions of the page.
Both sides previous revisionPrevious revisionNext revision | Previous revision | ||
code:parafoil_tsip [2008/11/27 18:37] – laurenceb | code:parafoil_tsip [2009/02/26 02:19] (current) – laurenceb | ||
---|---|---|---|
Line 6: | Line 6: | ||
#include " | #include " | ||
//globals | //globals | ||
+ | #include " | ||
#ifdef GROUND | #ifdef GROUND | ||
volatile u16 diff; | volatile u16 diff; | ||
- | volatile u08 counter; | + | volatile u08 counter=0; |
#endif | #endif | ||
const char config_string[44] PROGMEM={0x10, | const char config_string[44] PROGMEM={0x10, | ||
Line 27: | Line 27: | ||
volatile kalman_state our_state; | volatile kalman_state our_state; | ||
- | volatile kalman_model our_model; | + | /*volatile*/ kalman_model our_model; |
volatile u08 Kalman_flag; | volatile u08 Kalman_flag; | ||
Line 80: | Line 80: | ||
| | ||
sbi(PINB, | sbi(PINB, | ||
+ | |||
//enable the power to the servo | //enable the power to the servo | ||
ENABLE_SMPS; | ENABLE_SMPS; | ||
+ | |||
//SPI setup - do this here as the /SS pin is already set as an output | //SPI setup - do this here as the /SS pin is already set as an output | ||
SPCR = (1<< | SPCR = (1<< | ||
//outb( SPSR, (1<< | //outb( SPSR, (1<< | ||
+ | |||
//Timer 1 setup | //Timer 1 setup | ||
TCCR1B = (1<< | TCCR1B = (1<< | ||
Line 107: | Line 107: | ||
sbi(TCCR1A, | sbi(TCCR1A, | ||
cbi(TCCR1A, | cbi(TCCR1A, | ||
+ | |||
//Turn on the servo pwm - OCR1B will previously have been at 0 - we've left the SMPS for a while to stabilise | //Turn on the servo pwm - OCR1B will previously have been at 0 - we've left the SMPS for a while to stabilise | ||
OCR1B=3*PWM_COUNT_TIME; | OCR1B=3*PWM_COUNT_TIME; | ||
+ | |||
+ | |||
//Kalman setup // | //Kalman setup // | ||
our_model.F.tl=1.0; | our_model.F.tl=1.0; | ||
Line 266: | Line 267: | ||
} | } | ||
- | u08 cutdownrulecheck(int time, float * altitude) | + | u08 cutdownrulecheck(int time,volatile |
{ | { | ||
if(time< | if(time< | ||
Line 299: | Line 300: | ||
} | } | ||
} | } | ||
+ | |||
void wiggleservo() | void wiggleservo() | ||
{ | { | ||
Line 330: | Line 331: | ||
Gps.packetflag=FALSE; | Gps.packetflag=FALSE; | ||
while(!Gps.packetflag); | while(!Gps.packetflag); | ||
- | } | ||
- | |||
- | float driftfactor(int altitude) | ||
- | { | ||
- | return WEIGHTINGFACTOR*exp(SCALEHEIGHT*((float)altitude-0.5)); | ||
} | } | ||
- | void dataprint(u08 flight_status, | + | void dataprint(u08 flight_status, |
{ | { | ||
u08 local_char; | u08 local_char; | ||
Line 376: | Line 372: | ||
if(flight_status=='<' | if(flight_status=='<' | ||
{ | { | ||
- | Kalman_flag=TRUE; | ||
rprintfFloat(1, | rprintfFloat(1, | ||
PRINT_COMMA; | PRINT_COMMA; | ||
rprintfFloat(2, | rprintfFloat(2, | ||
PRINT_COMMA; | PRINT_COMMA; | ||
+ | Kalman_flag=TRUE; | ||
rprintfFloat(1, | rprintfFloat(1, | ||
PRINT_COMMA; | PRINT_COMMA; | ||
rprintfFloat(1, | rprintfFloat(1, | ||
- | PRINT_COMMA; | ||
Kalman_flag=FALSE; | Kalman_flag=FALSE; | ||
+ | PRINT_COMMA; | ||
+ | #ifdef GROUND // | ||
+ | rprintf(" | ||
+ | PRINT_COMMA; | ||
+ | #endif | ||
} | } | ||
rprintfFloat(1, | rprintfFloat(1, | ||
PRINT_COMMA; | PRINT_COMMA; | ||
- | #ifdef GROUND // | ||
- | rprintf(" | ||
- | PRINT_COMMA; | ||
- | #endif | ||
rprintfFloat(1, | rprintfFloat(1, | ||
PRINT_COMMA; | PRINT_COMMA; | ||
Line 399: | Line 395: | ||
return ; | return ; | ||
} | } | ||
+ | |||
void put_char(unsigned char c) | void put_char(unsigned char c) | ||
{ | { | ||
Line 417: | Line 413: | ||
int main() | int main() | ||
{ | { | ||
- | wdt_enable(WDTO_4S); | + | wdt_enable(WDTO_8S); |
#ifdef EEPROM | #ifdef EEPROM | ||
u32 I2Caddress; | u32 I2Caddress; | ||
#endif | #endif | ||
- | int time; | + | u16 time; |
int L; | int L; | ||
u08 Heightupto=1; | u08 Heightupto=1; | ||
float K; | float K; | ||
+ | float b, | ||
float descent_drift_n=0; | float descent_drift_n=0; | ||
float descent_drift_e=0; | float descent_drift_e=0; | ||
Line 463: | Line 460: | ||
getgps(); | getgps(); | ||
} | } | ||
+ | wdt_enable(WDTO_4S); | ||
rprintfProgStr(PSTR(" | rprintfProgStr(PSTR(" | ||
_delay_10ms(100); | _delay_10ms(100); | ||
Line 472: | Line 470: | ||
for (L=0; | for (L=0; | ||
{ | { | ||
+ | wdt_reset(); | ||
rprintfProgStr(PSTR(" | rprintfProgStr(PSTR(" | ||
rprintf(" | rprintf(" | ||
rprintf(" | rprintf(" | ||
rprintfProgStr(PSTR(", | rprintfProgStr(PSTR(", | ||
- | wdt_reset(); | + | if((s08)(eeprom_read_byte((u08*)& |
+ | { | ||
+ | eeprom_write_byte((u08*)& | ||
+ | eeprom_write_byte((u08*)& | ||
+ | } | ||
} | } | ||
} | } | ||
Line 494: | Line 497: | ||
disable_ground_control(); | disable_ground_control(); | ||
#endif | #endif | ||
- | for (L=0;( L<255 && (s08)(eeprom_read_byte((u08*)& | ||
- | { | ||
- | eeprom_write_byte((u08*)& | ||
- | eeprom_write_byte((u08*)& | ||
- | } | ||
for(L=100; | for(L=100; | ||
{ | { | ||
Line 520: | Line 518: | ||
{ | { | ||
rprintfProgStr(PSTR(" | rprintfProgStr(PSTR(" | ||
- | time=eeprom_read_word(& | + | time=eeprom_read_word(& |
for(; | for(; | ||
{ | { | ||
- | if((I2Caddress/ | + | read_data((u08*)& |
- | { | + | if(*(u32*)& |
- | read_data((u08*)& | + | break; |
- | } | + | rprintfFloat(9, |
+ | PRINT_COMMA; | ||
+ | if(((I2Caddress-1)/12)>=time) // | ||
+ | L++; | ||
else | else | ||
+ | L+=2; | ||
+ | if(L> | ||
{ | { | ||
- | read_data((u08*)& | + | rprintf(" |
- | if(*(u08*)& | + | rprintfCRLF(); |
- | break; //quit when we get to painted EEPROM | + | L=0; |
- | rprintfFloat(9, | + | |
- | PRINT_COMMA; | + | |
- | rprintfFloat(9, | + | |
- | PRINT_COMMA; | + | |
- | rprintfFloat(9, | + | |
- | PRINT_COMMA; | + | |
} | } | ||
- | if(*(u08*)& | ||
- | break; | ||
- | rprintfFloat(9, | ||
- | PRINT_COMMA; | ||
- | rprintfFloat(9, | ||
- | PRINT_COMMA; | ||
- | rprintfFloat(9, | ||
- | PRINT_COMMA; | ||
- | rprintf(" | ||
- | rprintfCRLF(); | ||
wdt_reset(); | wdt_reset(); | ||
- | } // | + | } |
I2Caddress=0; | I2Caddress=0; | ||
- | getgps(); | ||
} | } | ||
else | else | ||
Line 576: | Line 562: | ||
wdt_reset(); | wdt_reset(); | ||
#endif | #endif | ||
- | rprintfProgStr(PSTR(" | + | rprintfProgStr(PSTR(" |
} | } | ||
else // | else // | ||
Line 583: | Line 569: | ||
I2Caddress=findtop(); | I2Caddress=findtop(); | ||
#endif | #endif | ||
- | if(eeprom_read_byte(& | + | if(eeprom_read_byte(& |
{ | { | ||
getgps(); | getgps(); | ||
Heightupto=(int)(Gps.altitude/ | Heightupto=(int)(Gps.altitude/ | ||
- | for(L=0; | ||
- | { | ||
- | K=driftfactor(L); | ||
- | descent_drift_e+=(float)(s08)eeprom_read_byte((u08*)& | ||
- | descent_drift_n+=(float)(s08)eeprom_read_byte((u08*)& | ||
- | } | ||
} | } | ||
else | else | ||
{ | { | ||
- | for(L=0; | + | for(L=0; |
{ | { | ||
- | K=driftfactor(L); | ||
- | descent_drift_e+=(float)(s08)eeprom_read_byte((u08*)& | ||
- | descent_drift_n+=(float)(s08)eeprom_read_byte((u08*)& | ||
Heightupto++; | Heightupto++; | ||
} | } | ||
} | } | ||
L=0; | L=0; | ||
- | rprintfProgStr(PSTR(" | + | rprintfProgStr(PSTR(" |
rprintf(" | rprintf(" | ||
rprintfCRLF(); | rprintfCRLF(); | ||
Line 618: | Line 595: | ||
| | ||
| | ||
- | if (Gps.altitude > Heightupto*100) // | + | if (Gps.altitude > Heightupto*100) // |
{ | { | ||
Wind_e/ | Wind_e/ | ||
Line 624: | Line 601: | ||
eeprom_write_byte((u08*)& | eeprom_write_byte((u08*)& | ||
eeprom_write_byte((u08*)& | eeprom_write_byte((u08*)& | ||
- | K=driftfactor(Heightupto); | ||
- | descent_drift_e+=Wind_e*K; | ||
- | descent_drift_n+=Wind_n*K; | ||
Heightupto++; | Heightupto++; | ||
L = 0; | L = 0; | ||
Line 664: | Line 638: | ||
else | else | ||
{ | { | ||
- | if(L) // | + | if(L>0) // |
{ // | { // | ||
Wind_e/ | Wind_e/ | ||
Wind_n/ | Wind_n/ | ||
- | L=0; | + | L=-1; |
} | } | ||
- | else | + | else |
{ | { | ||
Wind_e=0.0; | Wind_e=0.0; | ||
Line 676: | Line 650: | ||
} | } | ||
} | } | ||
- | if((int)Gps.altitude< | + | //clockwise is defined as +ive, everything uses the local ENU wind frame / wind in this frame |
- | { | + | |
- | if((s08)eeprom_read_byte((u08*)& | + | |
- | { // | + | |
- | K=driftfactor(Heightupto); | + | |
- | descent_drift_e-=Wind_e*K; | + | |
- | descent_drift_n-=Wind_n*K; | + | |
- | } | + | |
- | Heightupto--; | + | |
- | } | + | |
// | // | ||
Target = atan2((targeteast - Gps.longitude)*cos(targetnorth) - descent_drift_e, | Target = atan2((targeteast - Gps.longitude)*cos(targetnorth) - descent_drift_e, | ||
Line 736: | Line 701: | ||
set_address(& | set_address(& | ||
write_data((u08*)& | write_data((u08*)& | ||
- | write_data((u08*)& | + | write_data((u08*)& |
- | write_data((u08*)& | + | Kalman_flag=TRUE; |
+ | write_data((u08*)& | ||
+ | Kalman_flag=FALSE; | ||
i2cstop(); | i2cstop(); | ||
#endif | #endif | ||
+ | L=(int)(Gps.altitude/ | ||
+ | if(descent_variable> | ||
+ | { | ||
+ | for(Heightupto=0; | ||
+ | { | ||
+ | K=descent_variable*(float)pgm_read_byte(& | ||
+ | descent_drift_e+=(s08)eeprom_read_byte((u08*)& | ||
+ | descent_drift_n+=(s08)eeprom_read_byte((u08*)& | ||
+ | } | ||
+ | } | ||
+ | Heightupto++; | ||
+ | descent_variable_noise+=DESCENT_PROCESS_NOISE; | ||
+ | if(Gps.vup< | ||
+ | { //we run if we are descending and estimate the transit time coefficient | ||
+ | b=(float)pgm_read_byte(& | ||
+ | K=descent_variable_noise/ | ||
+ | b=(-100.0)/ | ||
+ | descent_variable+=K*(b-descent_variable); | ||
+ | descent_variable_noise-=descent_variable_noise*K; | ||
+ | } | ||
getgps(); | getgps(); | ||
} | } | ||
Line 747: | Line 734: | ||
} | } | ||
///////////////////////////// | ///////////////////////////// | ||
- | |||
cbi(TIMSK1, | cbi(TIMSK1, | ||
cbi(TCCR1A, | cbi(TCCR1A, | ||
Line 763: | Line 749: | ||
getgps(); | getgps(); | ||
} | } | ||
- | } | + | }</ |
- | </ | + | |
==== Main.h ==== | ==== Main.h ==== | ||
Line 785: | Line 769: | ||
#include < | #include < | ||
#define BAUDRATE (int)9600 // | #define BAUDRATE (int)9600 // | ||
- | #define DELTA_TIME (float)0.02 //20ms | + | #define DELTA_TIME (float)0.02 //20ms |
#define DELAY _delay_loop_2((u16)((float)F_CPU/ | #define DELAY _delay_loop_2((u16)((float)F_CPU/ | ||
#define SET PORTD |= 0x10 // | #define SET PORTD |= 0x10 // | ||
#define CLEAR PORTD &= ~0x10 | #define CLEAR PORTD &= ~0x10 | ||
+ | |||
//kalman filter - NOTE: these constants are airframe specific | //kalman filter - NOTE: these constants are airframe specific | ||
#define DAMPING_CONSTANT (float)0.3 // | #define DAMPING_CONSTANT (float)0.3 // | ||
#define CONTROL (float)0.75 // | #define CONTROL (float)0.75 // | ||
#define CONTROL_GAIN (DAMPING_CONSTANT*CONTROL) // | #define CONTROL_GAIN (DAMPING_CONSTANT*CONTROL) // | ||
+ | |||
#define TOP_COUNT (u16)((float)F_CPU*DELTA_TIME/ | #define TOP_COUNT (u16)((float)F_CPU*DELTA_TIME/ | ||
#define PWM_COUNT_TIME (u16)((float)F_CPU*0.0005/ | #define PWM_COUNT_TIME (u16)((float)F_CPU*0.0005/ | ||
- | + | ||
- | #define I_C -0.001 //control loop | + | #define I_C -0.001 //control loop |
#define P_C -0.3 | #define P_C -0.3 | ||
#define D_C -0.5 | #define D_C -0.5 | ||
#define INTEGRAL_LIMIT 0.2/ | #define INTEGRAL_LIMIT 0.2/ | ||
+ | |||
+ | #define GPS_VEL_NOISE (0.25*(6378000.0/ | ||
+ | #define DESCENT_PROCESS_NOISE 1.0e-22 // | ||
+ | #define DESCENT_INIT 1.5e-8 | ||
+ | #define DESCENT_NOISE_INIT 5.0e-17 | ||
- | #define SCALEHEIGHT (float)(-1.0/ | ||
- | #define WEIGHTINGFACTOR (float)(20.0)/ | ||
- | |||
#define read_rate (u08)0b10010100 // | #define read_rate (u08)0b10010100 // | ||
#define read_temp (u08)0b10011100 | #define read_temp (u08)0b10011100 | ||
#define read_melexis (u08)0x80 | #define read_melexis (u08)0x80 | ||
- | + | ||
- | #define gyro_null | + | #define gyro_null |
#define altitudelimit 10000 // | #define altitudelimit 10000 // | ||
#define timelimit 30 // | #define timelimit 30 // | ||
- | #define targeteast (float)(-1.0*Deg2rad) //target waypoint ~ Cambridge | + | #define targeteast (float)(0.1*Deg2rad) //target waypoint ~ Cambridge |
#define targetnorth (float)(52.0*Deg2rad) | #define targetnorth (float)(52.0*Deg2rad) | ||
#define Rad2deg 180.0/ | #define Rad2deg 180.0/ | ||
#define Deg2rad PI/180.0 | #define Deg2rad PI/180.0 | ||
+ | |||
#define PRINT_COMMA rprintfChar(pgm_read_byte(& | #define PRINT_COMMA rprintfChar(pgm_read_byte(& | ||
#define battery_factor (float)0.02505 // | #define battery_factor (float)0.02505 // | ||
- | #define battery_chan 0x00 //ADC0 | + | #define battery_chan 0x00 //ADC0 |
- | #define toggle_pin PIND=0x20 //led on port D.5 | + | #define toggle_pin PIND=0x20 //led on port D.5 |
#define BAUDDIV | #define BAUDDIV | ||
+ | |||
#define radio_cts bit_is_set(PIND, | #define radio_cts bit_is_set(PIND, | ||
+ | |||
#define led_left PORTC = ((PORTC & ~0x0C) | 0x04) | #define led_left PORTC = ((PORTC & ~0x0C) | 0x04) | ||
#define led_right PORTC = ((PORTC & ~0x0C) | 0x08) | #define led_right PORTC = ((PORTC & ~0x0C) | 0x08) | ||
+ | |||
#define USER_PRESENT !(PINC& | #define USER_PRESENT !(PINC& | ||
+ | |||
#define cutter_on PORTD|=(1<< | #define cutter_on PORTD|=(1<< | ||
#define cutter_off PORTD& | #define cutter_off PORTD& | ||
+ | |||
#define DISABLE_SMPS PORTD|=(1<< | #define DISABLE_SMPS PORTD|=(1<< | ||
#define ENABLE_SMPS PORTD& | #define ENABLE_SMPS PORTD& | ||
+ | |||
#define GYRO_OFF PORTB|=1<< | #define GYRO_OFF PORTB|=1<< | ||
#define GYRO_ON PORTB& | #define GYRO_ON PORTB& | ||
+ | |||
#ifdef ADCSRA | #ifdef ADCSRA | ||
#ifndef ADCSR | #ifndef ADCSR | ||
Line 855: | Line 841: | ||
#endif | #endif | ||
#ifdef GROUND | #ifdef GROUND | ||
- | # | + | void enable_ground_control(); //enables the input capture interrupt |
- | # | + | void disable_ground_control(); //disables input capture interrupt |
- | #define PULSE_MIN 0.001*F_CPU/8 //pwm must be in the range 1 to 2 ms | + | #define PULSE_MIN |
- | #define PULSE_MAX 0.002*F_CPU/8 | + | #define PULSE_MAX |
#define GROUND_LED_ON PORTD|=(1<< | #define GROUND_LED_ON PORTD|=(1<< | ||
#define GROUND_LED_OFF PORTD& | #define GROUND_LED_OFF PORTD& | ||
#define GROUND_LED_SET PORTD& | #define GROUND_LED_SET PORTD& | ||
+ | void run_ground_control(); | ||
#endif | #endif | ||
Line 883: | Line 870: | ||
void _delay_10ms(char time); | void _delay_10ms(char time); | ||
float driftfactor(int altitude); | float driftfactor(int altitude); | ||
+ | u08 I2Cdataprint(u32* I2Caddress); | ||
</ | </ |
code/parafoil_tsip.1227811020.txt.gz · Last modified: 2008/11/27 18:37 by laurenceb