main.c
Go to the documentation of this file.
00001 /*
00002 
00003 AscTec AutoPilot HL SDK v2.0
00004 
00005 Copyright (c) 2011, Ascending Technologies GmbH
00006 All rights reserved.
00007 
00008 Redistribution and use in source and binary forms, with or without
00009 modification, are permitted provided that the following conditions are met:
00010 
00011  * Redistributions of source code must retain the above copyright notice,
00012    this list of conditions and the following disclaimer.
00013  * Redistributions in binary form must reproduce the above copyright
00014    notice, this list of conditions and the following disclaimer in the
00015    documentation and/or other materials provided with the distribution.
00016 
00017 THIS SOFTWARE IS PROVIDED BY THE AUTHOR AND CONTRIBUTORS ``AS IS'' AND ANY
00018 EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00019 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00020 DISCLAIMED. IN NO EVENT SHALL THE AUTHOR OR CONTRIBUTORS BE LIABLE FOR ANY
00021 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00023 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00024 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00025 LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
00026 OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
00027 DAMAGE.
00028 
00029  */
00030 
00031 /**********************************************************
00032                   Header files
00033  **********************************************************/
00034 #include "LPC214x.h"
00035 #include "main.h"
00036 #include "system.h"
00037 #include "uart.h"
00038 #include "mymath.h"
00039 #include "hardware.h"
00040 #include "irq.h"
00041 #include "i2c.h"
00042 #include "gpsmath.h"
00043 #include "adc.h"
00044 #include "uart.h"
00045 #include "uart1.h"
00046 #include "ssp.h"
00047 #include "LL_HL_comm.h"
00048 #include "sdk.h"
00049 #include "buzzer.h"
00050 #include "ublox.h"
00051 #include "pelican_ptu.h"
00052 #include "declination.h"
00053 
00054 /* *********************************************************
00055                Function declarations
00056   ********************************************************* */
00057 
00058 void Initialize(void);
00059 void feed(void);
00060 void beeper(unsigned char);
00061 
00062 /**********************************************************
00063                   Global Variables
00064  **********************************************************/
00065 struct HL_STATUS HL_Status;
00066 struct IMU_CALCDATA IMU_CalcData, IMU_CalcData_tmp;
00067 struct GPS_TIME GPS_Time;
00068 
00069 volatile unsigned int int_cnt=0, cnt=0, mainloop_cnt=0;
00070 volatile unsigned char mainloop_trigger=0;
00071 volatile unsigned int GPS_timeout=0;
00072 volatile unsigned int trigger_cnt=0;
00073 volatile char SYSTEM_initialized=0;
00074 
00075 unsigned int uart_cnt;
00076 unsigned char DataOutputsPerSecond=10;
00077 
00078 
00079 void timer0ISR(void) __irq
00080 {
00081   T0IR = 0x01;      //Clear the timer 0 interrupt
00082   IENABLE;
00083   trigger_cnt++;
00084   if(trigger_cnt==ControllerCyclesPerSecond)
00085   {
00086         trigger_cnt=0;
00087         HL_Status.up_time++;
00088         HL_Status.cpu_load=mainloop_cnt;
00089 
00090         mainloop_cnt=0;
00091   }
00092 
00093   if (mainloop_trigger < 10)
00094     mainloop_trigger++;
00095   timestamp += ControllerCyclesPerSecond;
00096 
00097   IDISABLE;
00098   VICVectAddr = 0; // Acknowledge Interrupt
00099 }
00100 
00101 void timer1ISR(void) __irq
00102 {
00103   T1IR = 0x01; //Clear the timer 1 interrupt
00104   IENABLE;
00105 
00106   IDISABLE;
00107   VICVectAddr = 0; // Acknowledge Interrupt
00108 }
00109 
00110 /**********************************************************
00111                        MAIN
00112 **********************************************************/
00113 int     main (void) {
00114 
00115   static int vbat1; //battery_voltage (lowpass-filtered)
00116 
00117   init();
00118   buzzer(OFF);
00119   LL_write_init();
00120   PTU_init();
00121   ADC0triggerSampling(1<<VOLTAGE_1); //activate ADC sampling
00122   sdkInit();
00123 
00124   HL_Status.up_time=0;
00125 
00126   LED(1,ON);
00127 
00128   while(1)
00129   {
00130       if(mainloop_trigger)
00131       {
00132         if(GPS_timeout<ControllerCyclesPerSecond) GPS_timeout++;
00133                 else if(GPS_timeout==ControllerCyclesPerSecond)
00134                 {
00135                         GPS_timeout=ControllerCyclesPerSecond+1;
00136                         GPS_Data.status=0;
00137                         GPS_Data.numSV=0;
00138                 }
00139 
00140         //battery monitoring
00141         ADC0getSamplingResults(0xFF,adcChannelValues);
00142         vbat1=(vbat1*14+(adcChannelValues[VOLTAGE_1]*9872/579))/15;     //voltage in mV
00143 
00144                 HL_Status.battery_voltage_1=vbat1;
00145         mainloop_cnt++;
00146                 if(!(mainloop_cnt%10)) buzzer_handler(HL_Status.battery_voltage_1, hli_config.battery_warning_voltage);
00147 
00148             if(mainloop_trigger) mainloop_trigger--;
00149         mainloop();
00150       }
00151   }
00152   return 0;
00153 }
00154 
00155 
00156 void mainloop(void) //mainloop is triggered at 1 kHz
00157 {
00158     static unsigned char led_cnt=0, led_state=1;
00159 
00160         //blink red led if no GPS lock available
00161         led_cnt++;
00162         if((GPS_Data.status&0xFF)==0x03)
00163         {
00164                 LED(0,OFF);
00165         }
00166         else
00167         {
00168             if(led_cnt==150)
00169             {
00170               LED(0,ON);
00171             }
00172             else if(led_cnt==200)
00173             {
00174               led_cnt=0;
00175               LED(0,OFF);
00176             }
00177         }
00178 
00179         //after first lock, determine magnetic inclination and declination
00180         if (SYSTEM_initialized)
00181         {
00182                 if ((!declinationAvailable) && (GPS_Data.horizontal_accuracy<10000) && ((GPS_Data.status&0x03)==0x03)) //make sure GPS lock is valid
00183                 {
00184                         int status;
00185                         estimatedDeclination=getDeclination(GPS_Data.latitude,GPS_Data.longitude,GPS_Data.height/1000,2012,&status);
00186                         if (estimatedDeclination<-32000) estimatedDeclination=-32000;
00187                         if (estimatedDeclination>32000) estimatedDeclination=32000;
00188                         declinationAvailable=1;
00189                 }
00190         }
00191 
00192         //toggle green LED and update SDK input struct when GPS data packet is received
00193     if (gpsLEDTrigger)
00194     {
00195                 if(led_state)
00196                 {
00197                         led_state=0;
00198                         LED(1,OFF);
00199                 }
00200                 else
00201                 {
00202                         LED(1,ON);
00203                         led_state=1;
00204                 }
00205 
00206                 RO_ALL_Data.GPS_height=GPS_Data.height;
00207                 RO_ALL_Data.GPS_latitude=GPS_Data.latitude;
00208                 RO_ALL_Data.GPS_longitude=GPS_Data.longitude;
00209                 RO_ALL_Data.GPS_speed_x=GPS_Data.speed_x;
00210                 RO_ALL_Data.GPS_speed_y=GPS_Data.speed_y;
00211                 RO_ALL_Data.GPS_status=GPS_Data.status;
00212                 RO_ALL_Data.GPS_sat_num=GPS_Data.numSV;
00213                 RO_ALL_Data.GPS_week=GPS_Time.week;
00214                 RO_ALL_Data.GPS_time_of_week=GPS_Time.time_of_week;
00215                 RO_ALL_Data.GPS_heading=GPS_Data.heading;
00216                 RO_ALL_Data.GPS_position_accuracy=GPS_Data.horizontal_accuracy;
00217                 RO_ALL_Data.GPS_speed_accuracy=GPS_Data.speed_accuracy;
00218                 RO_ALL_Data.GPS_height_accuracy=GPS_Data.vertical_accuracy;
00219 
00220                 gpsLEDTrigger=0;
00221     }
00222 
00223     //handle gps data reception
00224     uBloxReceiveEngine();
00225 
00226         //run SDK mainloop. Please put all your data handling / controller code in sdk.c
00227         SDK_mainloop();
00228 
00229     //write data to transmit buffer for immediate transfer to LL processor
00230     HL2LL_write_cycle();
00231 
00232     //control pan-tilt-unit ("cam option 4" @ AscTec Pelican)
00233     PTU_update();
00234 
00235 
00236 }
00237 
00238 


asctec_hl_firmware
Author(s): Markus Achtelik, Michael Achtelik, Stephan Weiss, Laurent Kneip
autogenerated on Tue Jan 7 2014 11:05:19