main.h
Go to the documentation of this file.
00001 #ifndef MAIN_H_
00002 #define MAIN_H_
00003 
00004 #include "util.h"
00005 
00006 extern void mainloop(void);
00007 extern void timer0ISR(void);
00008 extern void timer1ISR(void);
00009 
00010 volatile unsigned int GPS_timeout;
00011 extern unsigned int GPS_cnt_trigger[4];
00012 unsigned char GPS_init_status;
00013 volatile char SYSTEM_initialized; //new
00014 void calibrate(void);
00015 
00016 //#define BATTERY_WARNING_VOLTAGE 10700   //10500 mV, for newer batteries with flatter discharging characteristic, such as TP 5000
00017 #define BATTERY_WARNING_VOLTAGE 10000   //9800 mV
00018 #define BAT_DIV 10//(BATTERY_WARNING_VOLTAGE-9000)/100
00019 
00020 #define TRIGGER_SERVO_ACTIVE    1800
00021 #define TRIGGER_SERVO_INACTIVE  3600
00022 #define CAMER_OFFSET_HUMMINGBIRD        63000
00023 
00024 #define ControllerCyclesPerSecond       1000
00025 
00026 //defines for VP_CAMREMOTE (in �s)
00027 #define VP_SHOOT                                2000
00028 #define VP_LENSCLOSE_SLEEP              1900
00029 #define VP_REFOCUS_LOCKFOCUS    1800
00030 #define VP_ZOOM_IN                              1700
00031 #define VP_ZOOM_OUT                             1600
00032 #define VP_NEXT_PROFILE                 1500
00033 #define VP_PREVIOUS_PROFILE             1400
00034 #define VP_SHUTTER_SPEED_INC    1300
00035 #define VP_SHUTTER_SPEED_DEC    1200
00036 #define VP_APERTURE_INC                 1100
00037 #define VP_APERTURE_DEC                 1000
00038 
00039 #define OFF 0
00040 #define ON  1
00041 
00042 #define NORMAL 0
00043 
00044 //reconfigure GPS if needed
00045 #define GPS_STARTUP                     0
00046 #define GPS_NEEDS_CONFIGURATION 1
00047 #define GPS_IS_CONFIGURED               2
00048 #define GPS_CONFIG_ERROR                3
00049 
00050 //packet descriptors
00051 #define PD_IMURAWDATA       0x01
00052 #define PD_LLSTATUS             0x02
00053 #define PD_IMUCALCDATA      0x03
00054 #define PD_HLSTATUS             0x04
00055 
00056 #define PD_CTRLOUT                      0x11
00057 #define PD_FLIGHTPARAMS     0x12
00058 #define PD_CTRLCOMMANDS         0x13
00059 #define PD_CTRLINTERNAL         0x14
00060 #define PD_RCDATA               0x15
00061 #define PD_CTRLSTATUS           0x16
00062 
00063 #define PD_WAYPOINT             0x20
00064 #define PD_CURRENTWAY           0x21
00065 #define PD_NMEADATA             0x22
00066 #define PD_GPSDATA                      0x23
00067 
00068 #define PD_CAMERACOMMANDS       0x30
00069 
00070 #define CAM_TRIGGERED           0x04
00071 
00072 struct IMU_CALCDATA {
00073 //angles derived by integration of gyro_outputs, drift compensated by data fusion; -90000..+90000 pitch(nick) and roll, 0..360000 yaw; 1000 = 1 degree
00074     int angle_nick;
00075     int angle_roll;
00076     int angle_yaw;
00077 
00078 //angular velocities, raw values [16 bit], bias free, in 0.0154 �/s (=> 64.8 = 1 �/s)
00079     int angvel_nick;
00080     int angvel_roll;
00081     int angvel_yaw;
00082 
00083 //acc-sensor outputs, calibrated: -10000..+10000 = -1g..+1g
00084     short acc_x_calib;
00085     short acc_y_calib;
00086     short acc_z_calib;
00087 
00088 //horizontal / vertical accelerations: -10000..+10000 = -1g..+1g
00089     short acc_x;
00090     short acc_y;
00091     short acc_z;
00092 
00093 //reference angles derived by accelerations only: -90000..+90000; 1000 = 1 degree
00094     int acc_angle_nick;
00095     int acc_angle_roll;
00096 
00097 //total acceleration measured (10000 = 1g)
00098     int acc_absolute_value;
00099 
00100 //magnetic field sensors output, offset free and scaled; units not determined, as only the direction of the field vector is taken into account
00101     int Hx;
00102     int Hy;
00103     int Hz;
00104 
00105 //compass reading: angle reference for angle_yaw: 0..360000; 1000 = 1 degree
00106     int mag_heading;
00107 
00108 //pseudo speed measurements: integrated accelerations, pulled towards zero; units unknown; used for short-term position stabilization
00109     int speed_x;
00110     int speed_y;
00111     int speed_z;
00112 
00113 //height in mm (after data fusion)
00114     int height;
00115 
00116 //diff. height in mm/s (after data fusion)
00117     int dheight;
00118 
00119 //diff. height measured by the pressure sensor [mm/s]
00120     int dheight_reference;
00121 
00122 //height measured by the pressure sensor [mm]
00123     int height_reference;
00124 };
00125 extern struct IMU_CALCDATA IMU_CalcData, IMU_CalcData_tmp;
00126 
00127 struct IMU_RAWDATA {
00128 //pressure sensor 24-bit value, not scaled but bias free
00129         int pressure;
00130 
00131 //16-bit gyro readings; 32768 = 2.5V
00132     short gyro_x;
00133         short gyro_y;
00134         short gyro_z;
00135 
00136 //10-bit magnetic field sensor readings
00137     short mag_x;
00138         short mag_y;
00139         short mag_z;
00140 
00141 //16-bit accelerometer readings
00142     short acc_x;
00143         short acc_y;
00144     short acc_z;
00145 
00146 //16-bit temperature measurement using yaw-gyro internal sensor
00147         unsigned short temp_gyro;
00148 
00149 //16-bit temperature measurement using ADC internal sensor
00150         unsigned int temp_ADC;
00151 };
00152 
00153 extern struct IMU_RAWDATA IMU_RawData;
00154 
00155 
00156 struct SYSTEM_PERMANENT_DATA
00157 {
00158         unsigned int total_uptime;
00159         unsigned int total_flighttime;
00160         unsigned int onoff_cycles;
00161         unsigned int number_of_flights;
00162         unsigned int chksum;
00163 };
00164 extern struct SYSTEM_PERMANENT_DATA SYSTEM_Permanent_Data;
00165 
00166 #endif /*MAIN_H_*/
00167 


ccny_asctec_firmware_2
Author(s): Ivan Dryanovski, Roberto G. Valenti
autogenerated on Tue Jan 7 2014 11:04:17