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 [2009/01/14 02:51] – 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; | ||
Line 18: | Line 18: | ||
signed char EEMEM windeast[254]; | signed char EEMEM windeast[254]; | ||
signed char EEMEM windnorth[254]; | signed char EEMEM windnorth[254]; | ||
+ | |||
unsigned char EEMEM flight_status; | unsigned char EEMEM flight_status; | ||
#ifdef EEPROM | #ifdef EEPROM | ||
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 300: | Line 300: | ||
} | } | ||
} | } | ||
+ | |||
void wiggleservo() | void wiggleservo() | ||
{ | { | ||
Line 332: | Line 332: | ||
while(!Gps.packetflag); | while(!Gps.packetflag); | ||
} | } | ||
+ | |||
void dataprint(u08 flight_status, | void dataprint(u08 flight_status, | ||
{ | { | ||
Line 395: | Line 395: | ||
return ; | return ; | ||
} | } | ||
+ | |||
void put_char(unsigned char c) | void put_char(unsigned char c) | ||
{ | { | ||
Line 708: | Line 708: | ||
#endif | #endif | ||
L=(int)(Gps.altitude/ | L=(int)(Gps.altitude/ | ||
- | for(Heightupto=0; | + | if(descent_variable> |
{ | { | ||
- | K=descent_variable*(float)sqrt_density[Heightupto]; | + | for(Heightupto=0; |
- | descent_drift_e+=windeast[Heightupto]*K; | + | { |
- | descent_drift_n+=windnorth[Heightupto]*K; | + | K=descent_variable*(float)pgm_read_byte(& |
+ | descent_drift_e+=(s08)eeprom_read_byte((u08*)& | ||
+ | descent_drift_n+=(s08)eeprom_read_byte((u08*)& | ||
+ | } | ||
} | } | ||
- | Heightupto++; | + | Heightupto++; |
descent_variable_noise+=DESCENT_PROCESS_NOISE; | descent_variable_noise+=DESCENT_PROCESS_NOISE; | ||
- | if(Gps.vup< | + | if(Gps.vup< |
- | { //we run if we are descending and estimate the transit time coefficient | + | { //we run if we are descending and estimate the transit time coefficient |
- | b=(-100.0)/ | + | b=(float)pgm_read_byte(& |
- | K=descent_variable_noise/ | + | K=descent_variable_noise/ |
+ | b=(-100.0)/ | ||
descent_variable+=K*(b-descent_variable); | descent_variable+=K*(b-descent_variable); | ||
descent_variable_noise-=descent_variable_noise*K; | descent_variable_noise-=descent_variable_noise*K; | ||
Line 745: | Line 749: | ||
getgps(); | getgps(); | ||
} | } | ||
- | } | + | }</ |
- | </ | + | |
- | + | ||
==== Main.h ==== | ==== Main.h ==== | ||
Line 768: | 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 GPS_VEL_NOISE 0.25 | ||
- | #define DESCENT_PROCESS_NOISE 0.0001 | ||
- | |||
#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 840: | 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 868: | 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.1231901468.txt.gz · Last modified: 2009/01/14 02:51 by laurenceb