UKHAS Wiki

UK High Altitude Society

User Tools

Site Tools


code:parafoil_tsip

Differences

This shows you the differences between two versions of the page.

Link to this comparison view

Both sides previous revisionPrevious revision
Next revision
Previous revision
code:parafoil_tsip [2008/11/27 18:37] laurencebcode:parafoil_tsip [2009/02/26 02:19] (current) laurenceb
Line 6: Line 6:
 #include "main.h" #include "main.h"
 //globals //globals
 +#include "sqrt_density.h"
 #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,0xBB,0x03,0x00,0x03,0x03,0x00,0x3D,0xB2,0xCA,0x58, const char config_string[44] PROGMEM={0x10,0xBB,0x03,0x00,0x03,0x03,0x00,0x3D,0xB2,0xCA,0x58,
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:
   SET; //set software uart to gps   SET; //set software uart to gps
  sbi(PINB,2); //experimental hack to set the /SS input to 1 ?  sbi(PINB,2); //experimental hack to set the /SS input to 1 ?
 + 
  //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<<MSTR)|(1<<SPE)|(1<<CPHA)|(1<<CPOL); //F_CPU/4=5MHz, master, CPOL=CPHA=1  SPCR = (1<<MSTR)|(1<<SPE)|(1<<CPHA)|(1<<CPOL); //F_CPU/4=5MHz, master, CPOL=CPHA=1
  //outb( SPSR, (1<<SPI2X));  //outb( SPSR, (1<<SPI2X));
 + 
  //Timer 1 setup  //Timer 1 setup
  TCCR1B = (1<<ICNC1)|0x02; //clock at F_CPU/8, enable noise cancelling on ICP  TCCR1B = (1<<ICNC1)|0x02; //clock at F_CPU/8, enable noise cancelling on ICP
Line 107: Line 107:
  sbi(TCCR1A,COM1B1);  sbi(TCCR1A,COM1B1);
  cbi(TCCR1A,COM1B0);  cbi(TCCR1A,COM1B0);
 + 
  //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; //center servo - servo is on OC1B  OCR1B=3*PWM_COUNT_TIME; //center servo - servo is on OC1B
 +  
 + 
  //Kalman setup //\/MATRIX\/COMMENTS  //Kalman setup //\/MATRIX\/COMMENTS
  our_model.F.tl=1.0; //propogator  our_model.F.tl=1.0; //propogator
Line 266: Line 267:
 } }
    
-u08 cutdownrulecheck(int time, float * altitude)+u08 cutdownrulecheck(int time,volatile float * altitude)
 { {
  if(time<timelimit && *altitude<altitudelimit)  if(time<timelimit && *altitude<altitudelimit)
Line 299: Line 300:
  }  }
 } }
 + 
 void wiggleservo() void wiggleservo()
 { {
Line 330: Line 331:
  Gps.packetflag=FALSE; //"Unlock" the global variable, so GPS parsing ISR can update it  Gps.packetflag=FALSE; //"Unlock" the global variable, so GPS parsing ISR can update it
  while(!Gps.packetflag); //wait for some new gps  while(!Gps.packetflag); //wait for some new gps
-} 
- 
-float driftfactor(int altitude) 
-{ 
- return WEIGHTINGFACTOR*exp(SCALEHEIGHT*((float)altitude-0.5)); 
 } }
    
-void dataprint(u08 flight_status,gps_type * gps)+void dataprint(u08 flight_status,volatile gps_type * gps)
 { {
  u08 local_char;  u08 local_char;
Line 376: Line 372:
  if(flight_status=='<') //print the kalman data if the control loop is running  if(flight_status=='<') //print the kalman data if the control loop is running
  {  {
- Kalman_flag=TRUE; //lock the kalman data 
  rprintfFloat(1,(double)Heading);  rprintfFloat(1,(double)Heading);
  PRINT_COMMA;  PRINT_COMMA;
  rprintfFloat(2,(double)Target);  rprintfFloat(2,(double)Target);
  PRINT_COMMA;  PRINT_COMMA;
 + Kalman_flag=TRUE; //lock the kalman data
  rprintfFloat(1,(double)our_state.state.t);  rprintfFloat(1,(double)our_state.state.t);
  PRINT_COMMA;  PRINT_COMMA;
  rprintfFloat(1,(double)our_state.state.b);  rprintfFloat(1,(double)our_state.state.b);
- PRINT_COMMA; 
  Kalman_flag=FALSE;  Kalman_flag=FALSE;
 + PRINT_COMMA;
 + #ifdef GROUND //only print ground control info if ground control is enabled
 + rprintf("%x",counter);
 + PRINT_COMMA;
 + #endif
  }  }
  rprintfFloat(1,(double)getbatteryvoltage());  rprintfFloat(1,(double)getbatteryvoltage());
  PRINT_COMMA;  PRINT_COMMA;
- #ifdef GROUND //only print ground control info if ground control is enabled 
- rprintf("%x",counter); 
- PRINT_COMMA; 
- #endif 
  rprintfFloat(1,(double) (0.1953*(float)(temperature-1277)) );//mlx90609 rough temperature conversion  rprintfFloat(1,(double) (0.1953*(float)(temperature-1277)) );//mlx90609 rough temperature conversion
  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); //watchdog set to 4 seconds+ wdt_enable(WDTO_8S); //watchdog set to 4 seconds
  #ifdef EEPROM  #ifdef EEPROM
  u32 I2Caddress;  u32 I2Caddress;
  #endif  #endif
- int time;+ u16 time;
  int L;  int L;
  u08 Heightupto=1; //this rounds up  u08 Heightupto=1; //this rounds up
  float K;  float K;
 + float b,descent_variable=0.05882,descent_variable_noise=0.002;
  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("3D GPS Lock, press for wind data\r\n"));  rprintfProgStr(PSTR("3D GPS Lock, press for wind data\r\n"));
  _delay_10ms(100); //a 1 second delay  _delay_10ms(100); //a 1 second delay
Line 472: Line 470:
  for (L=0;L<255;L++)  for (L=0;L<255;L++)
  {  {
 + wdt_reset();
  rprintfProgStr(PSTR("Record no."));  rprintfProgStr(PSTR("Record no."));
  rprintf("%d:%d,E,",L,(int)(s08)eeprom_read_byte((u08*)&windeast[L]));  rprintf("%d:%d,E,",L,(int)(s08)eeprom_read_byte((u08*)&windeast[L]));
  rprintf("%d",(int)(s08)eeprom_read_byte((u08*)&windnorth[L]));  rprintf("%d",(int)(s08)eeprom_read_byte((u08*)&windnorth[L]));
  rprintfProgStr(PSTR(",W\r\n"));  rprintfProgStr(PSTR(",W\r\n"));
- wdt_reset();+ if((s08)(eeprom_read_byte((u08*)&windeast[L]))!=-126)//paint the eeprom with -126 
 +
 + eeprom_write_byte((u08*)&windeast[L],(s08)-126); 
 + eeprom_write_byte((u08*)&windnorth[L],(s08)-126); 
 + }
  }  }
  }  }
Line 494: Line 497:
  disable_ground_control();  disable_ground_control();
  #endif  #endif
- for (L=0;( L<255 && (s08)(eeprom_read_byte((u08*)&windeast[L]))!=-126);L++) //paint eeprom with -126 
- { 
- eeprom_write_byte((u08*)&windeast[L],(s08)-126); 
- eeprom_write_byte((u08*)&windnorth[L],(s08)-126); 
- } 
  for(L=100;L;L--)   for(L=100;L;L--)
  {  {
Line 520: Line 518:
  {  {
  rprintfProgStr(PSTR("[OK]\r\n")); //I2C debug crap  rprintfProgStr(PSTR("[OK]\r\n")); //I2C debug crap
- time=eeprom_read_word(&I2Crectransit)-3;//reads the transit location into time variable+ time=eeprom_read_word(&I2Crectransit); //reads the transit location into time variable
  for(;I2Caddress<131072;) //reads out all our data  for(;I2Caddress<131072;) //reads out all our data
  {  {
- if((I2Caddress/12)<time) //time is number of records before transition to 24 byte records + read_data((u08*)&K,4,&I2Caddress); //read out a float 
- { + if(*(u32*)&K==0xFFFFFFFF) //0xFFFFFFFF 
- read_data((u08*)&Gps.altitude,12,&I2Caddress);//shove a,l,l record into the gps struct + break; //quit when we get to painted EEPROM 
- }+ rprintfFloat(9,K); //this will be position fix info / filter and target info 
 + PRINT_COMMA; 
 + if(((I2Caddress-1)/12)>=time) //time is number of records before transition to 24 byte records 
 + L++;
  else  else
 + L+=2;
 + if(L>=6)
  {  {
- read_data((u08*)&Gps.vnorth,24,&I2Caddress);//shove a,l,l,heading,kalman heading, kalman rate + rprintf("%d",I2Cerr); 
- if(*(u08*)&Gps.vnorth==MAGIC_NUMBER) + rprintfCRLF(); 
- break; //quit when we get to painted EEPROM + L=0;
- rprintfFloat(9,Gps.time); +
- PRINT_COMMA; +
- rprintfFloat(9,Gps.veast); +
- PRINT_COMMA; +
- rprintfFloat(9,Gps.vnorth); +
- PRINT_COMMA;+
  }  }
- if(*(u08*)&Gps.altitude==MAGIC_NUMBER) 
- break; //quit when we get to painted EEPROM 
- rprintfFloat(9,Gps.latitude); //this will be the kalman and heading data after cutdown 
- PRINT_COMMA; 
- rprintfFloat(9,Gps.longitude); 
- PRINT_COMMA; 
- rprintfFloat(9,Gps.altitude); 
- PRINT_COMMA; 
- rprintf("%d",I2Cerr); 
- rprintfCRLF(); 
  wdt_reset();  wdt_reset();
- } //dump all the eeprom upto cutdown+ }
  I2Caddress=0;  I2Caddress=0;
- getgps(); //get some valid data into the gps struct  
  }  }
  else  else
Line 576: Line 562:
  wdt_reset();  wdt_reset();
  #endif  #endif
- rprintfProgStr(PSTR("Configuration done\r\n"));+ rprintfProgStr(PSTR("Config done\r\n"));
  }  }
  else //---------------------       erranous reset recovery code    -----------------------------------------  else //---------------------       erranous reset recovery code    -----------------------------------------
Line 583: Line 569:
  I2Caddress=findtop(); //we need to avoid overwiting old data   I2Caddress=findtop(); //we need to avoid overwiting old data
  #endif  #endif
- if(eeprom_read_byte(&flight_status)) //we have cutdown - find Heightupto from GPS+ if(eeprom_read_byte(&flight_status)==0x01) //we are in descent phase - find Heightupto from GPS
  {  {
  getgps(); //get the gps - hopefully we have a valid altitude  getgps(); //get the gps - hopefully we have a valid altitude
  Heightupto=(int)(Gps.altitude/100.0)+1; //c rounds down - we need to add one  Heightupto=(int)(Gps.altitude/100.0)+1; //c rounds down - we need to add one
- for(L=0;L<Heightupto && ((s08)eeprom_read_byte((u08*)&windeast[L])!=-126);L++)//- do not include present layer in integral hence < in loop terminator 
- { 
- K=driftfactor(L); 
- descent_drift_e+=(float)(s08)eeprom_read_byte((u08*)&windeast[L])*K; //we use this for optimised descent 
- descent_drift_n+=(float)(s08)eeprom_read_byte((u08*)&windnorth[L])*K; 
- }  
  }  }
  else  else
  {  {
- for(L=0;((s08)eeprom_read_byte((u08*)&windeast[L])!=-126) && L<255;L++) //calculate drift coefficients integrating over all non painted eeprom+ for(L=0;((s08)eeprom_read_byte((u08*)&windeast[L])!=-126) && L<255;L++) //calculate heightupto
  {  {
- K=driftfactor(L); 
- descent_drift_e+=(float)(s08)eeprom_read_byte((u08*)&windeast[L])*K; //we use this for optimised descent 
- descent_drift_n+=(float)(s08)eeprom_read_byte((u08*)&windnorth[L])*K; 
  Heightupto++;  Heightupto++;
  }  }
  }  }
  L=0;  L=0;
- rprintfProgStr(PSTR("Setup complete "));+ rprintfProgStr(PSTR("Setup complete, EEPROM top="));
  rprintf("%d",I2Caddress/12);  rprintf("%d",I2Caddress/12);
  rprintfCRLF();  rprintfCRLF();
Line 618: Line 595:
   Wind_n += Gps.vnorth;   Wind_n += Gps.vnorth;
   L++;                              //incrament the denominator for our averaging   L++;                              //incrament the denominator for our averaging
-        if (Gps.altitude > Heightupto*100) //do we now fall into another (higher) 100m incrament ?+         if (Gps.altitude > Heightupto*100) //do we now fall into another (higher) 100m incrament ?
   {   {
  Wind_e/=L;  Wind_e/=L;
Line 624: Line 601:
  eeprom_write_byte((u08*)&windeast[Heightupto],(s08)(Wind_e));//we are storing as a signed byte  eeprom_write_byte((u08*)&windeast[Heightupto],(s08)(Wind_e));//we are storing as a signed byte
  eeprom_write_byte((u08*)&windnorth[Heightupto],(s08)(Wind_n));//we find the average and shove it in the eeprom  eeprom_write_byte((u08*)&windnorth[Heightupto],(s08)(Wind_n));//we find the average and shove it in the eeprom
- K=driftfactor(Heightupto); 
- descent_drift_e+=Wind_e*K; //we use this for optimised descent 
- descent_drift_n+=Wind_n*K; 
  Heightupto++;   Heightupto++;
  L = 0;  L = 0;
Line 664: Line 638:
  else  else
  {  {
- if(L) //allows us to use data from last layer+ if(L>0) //allows us to use data from last layer
  { //if we are still in it and have arrived  { //if we are still in it and have arrived
  Wind_e/=L; //here from ascent loop with some data  Wind_e/=L; //here from ascent loop with some data
  Wind_n/=L;  Wind_n/=L;
- L=0;+ L=-1;
  }  }
- else+ else if (L!=-1) //if we havent used last layer data for find a solution
  {  {
  Wind_e=0.0; //painted eeprom has no valid data  Wind_e=0.0; //painted eeprom has no valid data
Line 676: Line 650:
  }  }
  }  }
- if((int)Gps.altitude<=(Heightupto-1)*100) //round up - we need to match up with recorded layers + //clockwise is defined as +ive, everything uses the local ENU wind frame / wind in this frame
-+
- if((s08)eeprom_read_byte((u08*)&windeast[Heightupto])!=-126)//dont take off any painted eeprom +
- { //this might happen if we are still in the cut layer +
- K=driftfactor(Heightupto); +
- descent_drift_e-=Wind_e*K; //take off layers of wind from our integral +
- descent_drift_n-=Wind_n*K; +
-+
- Heightupto--; +
- }+
  //direction to target (uses "equatorial radian units" - my invention, distance equal to PI on equator)  //direction to target (uses "equatorial radian units" - my invention, distance equal to PI on equator)
  Target = atan2((targeteast - Gps.longitude)*cos(targetnorth) - descent_drift_e,targetnorth - Gps.latitude - descent_drift_n);  Target = atan2((targeteast - Gps.longitude)*cos(targetnorth) - descent_drift_e,targetnorth - Gps.latitude - descent_drift_n);
Line 736: Line 701:
  set_address(&I2Caddress);  set_address(&I2Caddress);
  write_data((u08*)&Gps.altitude,12,&I2Caddress);  write_data((u08*)&Gps.altitude,12,&I2Caddress);
- write_data((u08*)&Heading,4,&I2Caddress); + write_data((u08*)&Target,4,&I2Caddress); 
- write_data((u08*)&our_state.state,8,&I2Caddress);//shove ze data in the eeprom+ Kalman_flag=TRUE; //lock the data 
 + write_data((u08*)&(our_state.state),8,&I2Caddress); //shove ze data in the eeprom 
 + Kalman_flag=FALSE;
  i2cstop();  i2cstop();
  #endif  #endif
 + L=(int)(Gps.altitude/100.0);
 + if(descent_variable>LOWER_DESCENT_LIMIT && descent_variable<UPPER_DESCENT_LIMIT)//check its sensible
 + {
 + for(Heightupto=0;(Heightupto<=L)&&((s08)eeprom_read_byte((u08*)&windeast[Heightupto])!=-126);Heightupto++)
 + {
 + K=descent_variable*(float)pgm_read_byte(&sqrt_density[Heightupto]);
 + descent_drift_e+=(s08)eeprom_read_byte((u08*)&windeast[Heightupto])*K; //add layers of wind to our integral
 + descent_drift_n+=(s08)eeprom_read_byte((u08*)&windnorth[Heightupto])*K;
 + }
 + }
 + Heightupto++; //we increment Heightupto so it is correct for obtaining the wind
 + descent_variable_noise+=DESCENT_PROCESS_NOISE; //this is a single component state vector extended kalman filter
 + if(Gps.vup<-0.5 && Gps.vup>-50.0) //sanity check for a descent
 + { //we run if we are descending and estimate the transit time coefficient
 + b=(float)pgm_read_byte(&sqrt_density[Heightupto]);
 + K=descent_variable_noise/((GPS_VEL_NOISE*b*b*descent_variable*descent_variable*descent_variable*descent_variable)+descent_variable_noise);//this is K
 + b=(-100.0)/(6378000.0*Gps.vup*b); //estimate of the proportionality constant
 + descent_variable+=K*(b-descent_variable);
 + descent_variable_noise-=descent_variable_noise*K;
 + }
  getgps();  getgps();
  }  }
Line 747: Line 734:
  }  }
  /////////////////////////////Recovery loop  /////////////////////////////Recovery loop
-  
  cbi(TIMSK1, OCIE1B); //turn off kalman  cbi(TIMSK1, OCIE1B); //turn off kalman
  cbi(TCCR1A, COM1B1); //turn off servo  cbi(TCCR1A, COM1B1); //turn off servo
Line 763: Line 749:
  getgps();  getgps();
  }  }
-} +}</code>
-</code> +
  
 ==== Main.h ==== ==== Main.h ====
Line 785: Line 769:
 #include <avr/pgmspace.h>  #include <avr/pgmspace.h> 
 #define BAUDRATE (int)9600 //9600 baud for lassen iq #define BAUDRATE (int)9600 //9600 baud for lassen iq
-#define DELTA_TIME (float)0.02 //20ms+#define DELTA_TIME (float)0.02 //20ms
 #define DELAY _delay_loop_2((u16)((float)F_CPU/(4.0*(float)BAUDRATE))) //delay for suart routine #define DELAY _delay_loop_2((u16)((float)F_CPU/(4.0*(float)BAUDRATE))) //delay for suart routine
 #define SET PORTD |= 0x10 //PORTD.4 is the tx #define SET PORTD |= 0x10 //PORTD.4 is the tx
 #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 //approx how fast oscillations die down as faction per second #define DAMPING_CONSTANT (float)0.3 //approx how fast oscillations die down as faction per second
 #define CONTROL (float)0.75 //full control input of 1 gives ~ this turn rate #define CONTROL (float)0.75 //full control input of 1 gives ~ this turn rate
 #define CONTROL_GAIN (DAMPING_CONSTANT*CONTROL) //as used in the kalman filter #define CONTROL_GAIN (DAMPING_CONSTANT*CONTROL) //as used in the kalman filter
 + 
 #define TOP_COUNT (u16)((float)F_CPU*DELTA_TIME/8.0) //timer1 pwm frequency #define TOP_COUNT (u16)((float)F_CPU*DELTA_TIME/8.0) //timer1 pwm frequency
 #define PWM_COUNT_TIME (u16)((float)F_CPU*0.0005/8.0) //500us #define PWM_COUNT_TIME (u16)((float)F_CPU*0.0005/8.0) //500us
- +  
-#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/I_C //integral servo shift limited to 1/5 of full scale range #define INTEGRAL_LIMIT 0.2/I_C //integral servo shift limited to 1/5 of full scale range
 + 
 +#define GPS_VEL_NOISE (0.25*(6378000.0/100.0)*(6378000.0/100.0))//these seem to be tolerant to errors of ~an order of mag
 +#define DESCENT_PROCESS_NOISE 1.0e-22 //tested with badger data
 +#define DESCENT_INIT 1.5e-8
 +#define DESCENT_NOISE_INIT 5.0e-17
  
-#define SCALEHEIGHT (float)(-1.0/160.0) //optimised descent- 1/( atm scale height in 100m units * 2) - http://en.wikipedia.org/wiki/Scale_height 
-#define WEIGHTINGFACTOR (float)(20.0)/(1012000.0)//time to drop 100m at STP/one radian expressed as meters on earth surface 
-  
 #define read_rate (u08)0b10010100 //gyro specific #define read_rate (u08)0b10010100 //gyro specific
 #define read_temp (u08)0b10011100 #define read_temp (u08)0b10011100
 #define read_melexis (u08)0x80 #define read_melexis (u08)0x80
- +  
-#define gyro_null 1012+#define gyro_null 1022
    
 #define altitudelimit 10000 //flight termination conditions #define altitudelimit 10000 //flight termination conditions
 #define timelimit 30 //NOTE: for debug #define timelimit 30 //NOTE: for debug
    
-#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/PI //bloody obvious #define Rad2deg 180.0/PI //bloody obvious
 #define Deg2rad PI/180.0 #define Deg2rad PI/180.0
 + 
 #define PRINT_COMMA rprintfChar(pgm_read_byte(&comma)) //prints a comma #define PRINT_COMMA rprintfChar(pgm_read_byte(&comma)) //prints a comma
    
 #define battery_factor (float)0.02505 //for measuring battery voltage- checked from test #define battery_factor (float)0.02505 //for measuring battery voltage- checked from test
-#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  (u16)( ((float)F_CPU/(BAUDRATE*16UL)) -1 )//baud divider #define BAUDDIV  (u16)( ((float)F_CPU/(BAUDRATE*16UL)) -1 )//baud divider
 + 
 #define radio_cts bit_is_set(PIND,2) //hardware, however its wired up #define radio_cts bit_is_set(PIND,2) //hardware, however its wired up
 + 
 #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&0x02) #define USER_PRESENT !(PINC&0x02)
 + 
 #define cutter_on PORTD|=(1<<7) //release mechanism (hot resistor off mosfet) #define cutter_on PORTD|=(1<<7) //release mechanism (hot resistor off mosfet)
 #define cutter_off PORTD&=~(1<<7) #define cutter_off PORTD&=~(1<<7)
 + 
 #define DISABLE_SMPS PORTD|=(1<<6) //turns the SMPS for the servo on/off - never send pwm if its off #define DISABLE_SMPS PORTD|=(1<<6) //turns the SMPS for the servo on/off - never send pwm if its off
 #define ENABLE_SMPS PORTD&=~(1<<6) #define ENABLE_SMPS PORTD&=~(1<<6)
 + 
 #define GYRO_OFF PORTB|=1<<1 //SS line #define GYRO_OFF PORTB|=1<<1 //SS line
 #define GYRO_ON PORTB&=~(1<<1) #define GYRO_ON PORTB&=~(1<<1)
 + 
 #ifdef ADCSRA #ifdef ADCSRA
  #ifndef ADCSR  #ifndef ADCSR
Line 855: Line 841:
 #endif #endif
 #ifdef GROUND #ifdef GROUND
- #define enable_ground_control TIMSK1|=(1<<ICIE1) //enables the input capture interrupt + void enable_ground_control(); //enables the input capture interrupt 
- #define disable_ground_control TIMSK1&=~(1<<ICIE1) //disables 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 to 2 ms + #define PULSE_MIN (u16)(0.0008*(float)F_CPU/8.0) //pwm must be in the range 0.8 to 2.2 ms 
- #define PULSE_MAX 0.002*F_CPU/8+ #define PULSE_MAX (u16)(0.0022*(float)F_CPU/8.0) //due to the bit shift we divide by 16
  #define GROUND_LED_ON PORTD|=(1<<3)  #define GROUND_LED_ON PORTD|=(1<<3)
  #define GROUND_LED_OFF PORTD&=~(1<<3)  #define GROUND_LED_OFF PORTD&=~(1<<3)
  #define GROUND_LED_SET PORTD&(1<<3)  #define GROUND_LED_SET PORTD&(1<<3)
 + 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> </code>
code/parafoil_tsip.1227811020.txt.gz · Last modified: 2008/11/27 18:37 by laurenceb

Donate Powered by PHP Valid HTML5 Valid CSS Driven by DokuWiki