StoRC
Autonomous Payload Delivery System
storc.h
Go to the documentation of this file.
00001 /***********************************************************
00002  * StoRC - Search to Rescue Craft
00003  * MEAM Senior Design 2011-2012
00004  * 
00005  * Authors:  Michael Posner (CIS, MEAM '12)
00006  * Timothy Hennelly (ESE '12)
00007  * Jacob Orloff (MEAM '12)
00008  * 
00009  * (some code from ArduPilot Mega project, found here:
00010  * http://code.google.com/p/ardupilot-mega/ )
00011  * 
00012  * Licensing:
00013  * 
00014  * This program is free software: you can redistribute it and/or modify 
00015  * it under the terms of the GNU General Public License as published by 
00016  * the Free Software Foundation, either version 3 of the License, or 
00017  * (at your option) any later version. 
00018  * 
00019  * This program is distributed in the hope that it will be useful, 
00020  * but WITHOUT ANY WARRANTY; without even the implied warranty of 
00021  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 
00022  * GNU General Public License for more details. 
00023  * 
00024  * You should have received a copy of the GNU General Public License 
00025  * along with this program. If not, see <http://www.gnu.org/licenses/>.
00026  * 
00027  ***********************************************************/
00028 
00029 /**
00030 *  @file storc.h
00031 *  @brief Main header file, contains global variables, includes, macros, etc.
00032 *  @author Michael Posner (CIS, MEAM '12)
00033 *  @author Timothy Hennelly (ESE '12)
00034 *  @author Jacob Orloff (MEAM '12)
00035 *  
00036 */
00037 
00038 
00039 //Definitions -------------------------------------------------------
00040 #define LOG 0  ///< Easy way to turn logging on (1) and off (0)
00041 #define TELEMETRY 1  ///< Easy way to turn telemetry on (1) and off (0)
00042 #define CONTROLS 1   ///< Easy way to turn controls on (1) and off (0) - if off, Payload release is ON
00043 #define NAVIGATION 0 ///< Turn outer loop navigation on (1) and off (0)
00044 
00045 #define GRAVITY 9.81  ///< acceleration due to gravity
00046 #define K_DRIFT 0.2564
00047 #define OFFSET_DRIFT 6.4577
00048 
00049 #define DEG2RAD(x) (x*0.0174532925)  ///< Macro to convert degrees to radians
00050 #define RAD2DEG(x) (x*57.2957795)   ///< Macro to convert radians to degrees
00051 
00052 #define DELT_M2GPS_LAT(x) (x*105.37407797)  ///< Macro to convert a delta of meters to a delta of GPS decimal*10^7 (latitude)
00053 #define DELT_M2GPS_LON(x) (x*74.51564828)  ///< Macro to convert a delta of meters to a delta of GPS decimal*10^7 (longitude)
00054 #define DELT_GPS_LAT2M(x) (x*0.00949)  ///< Macro to convert a delta of GPS decimal*10^7 to a delta of meters (latitude)
00055 #define DELT_GPS_LON2M(x) (x*0.01342)  ///< Macro to convert a delta of GPS decimal*10^7 to a delta of meters (longitude)
00056 
00057 // System and Loop Clocks
00058 #define SYSTEM_CLOCK 16000000  ///< ATmega 2560 clock speed in Hz
00059 #define SLOW_LOOP_CLOCK 5  ///< Slow loop clock speed in Hz
00060 #define MED_LOOP_CLOCK 25  ///< Medium loop clock speed in Hz
00061 #define FAST_LOOP_CLOCK 50  ///< Fast loop clock speed in Hz
00062 #define TELEMETRY_CLOCK 5  ///< Telemetry transmit speed in Hz
00063 #define LOGGING_CLOCK 15  ///< Logging speed in Hz (except for GPS and barometer, which are in the slow loop)
00064 
00065 // LEDs and Switches
00066 #define A_LED 37  ///< set this pin to output to control LED A on the shield
00067 #define B_LED 36  ///< set this pin to output to control LED B on the shield
00068 #define C_LED 35  ///< set this pin to output to control LED C on the shield
00069 #define SLIDE_SWITCH 40  ///< set this pin to input to read the state of the sliding switch on the shield
00070 #define RELAY_SWITCH 47  ///< set this pin to output to control the Relay Switch on the shield
00071 #define LOGGING_SWITCH 6  ///< switch attached to analog 6 to control whether or not to log
00072 
00073 // Sensors
00074 #define PITOT_CH 7      ///< The external ADC channel for the pitot probe
00075 #define PITOT_RATIO 1.0  ///< Conversion between pitot probe voltage and kPa:  once the offset (PITOT_OFFSET) is subtracted, 2V -> 2 kPa
00076 #define PITOT_OFFSET 2.8   ///< This voltage reading from the pitot probe corresponds to 0 pressure difference between static and dynamic
00077 #define RHO 1.2  ///< The density of air at sea level
00078 
00079 // RC Channel Definitions
00080 #define ELEVATOR_CH 0               ///< Elevator Channel definition
00081 #define RUDDER_CH 1              ///< Rudder Channel definition
00082 #define THROTTLE_CH 2           ///< Throttle Channel definition
00083 
00084 // Payload drop
00085 #define RC4_CH 3           ///< Payload Drop Channel Switch: Ouput #9 on Receiver -  Input #4 on APM
00086 #define DROP_SERVO 3            ///< Drop servo on APM output #4
00087 
00088 #define RC5_CH 4                ///< RC ch5 definition
00089 #define RC6_CH 5                ///< RC ch6 definition
00090 #define RC7_CH 6               ///< RC ch7 definition
00091 #define RC8_CH 7                ///< RC ch8 definition
00092 
00093 // Time conversions for GPS
00094 #define SEC_PER_DAY 86400  ///< Number of seconds in a day
00095 #define SEC_PER_HOUR 3600  ///< Number of seconds in an hour
00096 #define SEC_PER_MIN 60  ///< Number of seconds in a minute
00097 
00098 // Logging Definitions (mostly the same convention used by ArduPilot Mega)
00099 #define HEAD_BYTE1 0xA3    ///< Header byte for flash memory writing (Decimal 163)
00100 #define HEAD_BYTE2 0x95    ///< Header byte for flash memory writing (Decimal 149)
00101 #define END_BYTE 0xBA      ///< End byte for flash memory writing (Decimal 186)
00102 
00103 #define LOG_INDEX_MSG                   0xF0  ///< Index header byte for flash memory writing (for determining log numbering)
00104 #define LOG_ATTITUDE_MSG                0x01  ///< Attitude header byte for flash memory writing (used by ArduPilot Mega, here to keep track of what's used)
00105 #define LOG_GPS_MSG                     0x02  ///< GPS header byte for flash memory writing
00106 #define LOG_MODE_MSG                    0X03  ///< Mode header byte for flash memory writing (used by ArduPilot Mega, here to keep track of what's used)
00107 #define LOG_BAROMETER_MSG               0X04  ///< Barometer header byte for flash memory writing
00108 #define LOG_IMU_MSG                     0X05  ///< IMU header byte for flash memory writing 
00109 #define LOG_RC_MSG                      0X06  ///< RC header byte for flash memory writing
00110 #define LOG_AIRSPEED_MSG                0x07  ///< Airspeed header byte for flash memory writing
00111 #define LOG_MAG_MSG                     0x08  ///< Magnetometer header byte for flash memory writing
00112 #define LOG_CONTROLS_RUDDER_MSG         0x09  ///< Controls roll comp header byte for flash memory writing
00113 #define LOG_CONTROLS_ELEVATOR_MSG       0x0A  ///< Controls elevator header byte for flash memory writing
00114 #define LOG_CONTROLS_THROTTLE_MSG       0x0B  ///< Controls throttle header byte for flash memory writing
00115 #define LOG_STATE_MSG                   0x0C  ///< State header byte for flash memory writing
00116 #define LOG_NAVIGATION_MSG              0x0D  ///< Navigation header byte for flash memory writing
00117 
00118 #define TYPE_AIRSTART_MSG               0x00  ///< Airstart header byte for flash memory writing (used by ArduPilot Mega, here to keep track of what's used)
00119 #define TYPE_GROUNDSTART_MSG            0x01  ///< Groundstart header byte for flash memory writing (used by ArduPilot Mega, here to keep track of what's used)
00120 #define MAX_NUM_LOGS                    50  ///< Maximum number of logs allowed in flash memory
00121 
00122 //DCM
00123 #define GYRO_INT_TIME  0.02  ///< Gyro integration time for the DCM
00124 
00125 
00126 //Global Variables --------------------------------------------------
00127 
00128 //Timers
00129 unsigned long fast_timer;  /**< timer for fast loop:  stores how much time has elapsed since
00130                             the last time this loop was run (in milliseconds) */
00131 unsigned long medium_timer;/**< timer for medium loop:  stores how much time has elapsed since
00132                             the last time this loop was run (in milliseconds) */
00133 unsigned long slow_timer;  /**< timer for slow loop:  stores how much time has elapsed since
00134                             the last time this loop was run (in milliseconds) */
00135 unsigned long telemetry_timer;  /**< timer for telemetry:  stores how much time has elapsed since
00136                             the last time data was transmitted (in milliseconds) */
00137 unsigned long logging_timer;  /**< timer for higher speed logging:  stores how much time has elapsed since
00138                             the last time data was transmitted (in milliseconds) */
00139 
00140 // RC Values
00141 int rc_elevator = 0;       ///< RC Elevator Input
00142 int rc_rudder = 0;         ///< RC Rudder Input
00143 int rc_throttle = 0;       ///< RC Throttle Input
00144 int rc_4 = 0;              ///< RC Payload Drop Input & ELE_control on/off
00145 int rc_5 = 0;              ///< RC switch for turning controls on/off
00146 int rc_6 = 0;              ///< RC knob for adjusting controls gain
00147 int rc_7 = 0;              ///< RC knob for adjusting controls gain
00148 int rc_8 = 0;
00149 
00150 // Drop timer
00151 unsigned long drop_timer;  ///< makes sure the rc input wasnt just a fluke, keeps track of how long the input is high to make sure you want to drop
00152 
00153 //Airspeed Values
00154 float airspeed;  ///< stores current airspeed reading
00155 float pitot_pressure_offset;  ///< stores an offset for zeroing the pitot pressure measurements
00156 //avg wind calcs
00157 boolean get_wind_profile = true;
00158 float sum_wind_ns = 0;  ///< running sum of wind samples in North South direction during ascent
00159 float sum_wind_ew = 0;  ///< running sum of wind samples in East West direction during ascent
00160 int total_ns = 0;  ///< total number of wind samples in NS direction during ascent
00161 int total_ew = 0;  ///< total number of wind samples in EW direction during ascent
00162 float avg_wind_ns = 0;  ///< average wind in NS direction during ascent
00163 float avg_wind_ew = 0;  ///< average wind in EW direction during ascent
00164 
00165 float drift_ns = 0.0;
00166 float drift_ew = 0.0;
00167 
00168 //Switch/state values
00169 int slide_sw = LOW;  ///< state of hardware switch on shield ( either LOW (0) or HIGH (1) )
00170 int logging_sw = 0;  ///< state of the logging switch on analog 6 (see LOGGING_SWITCH)
00171 boolean drop_state = false;  ///< state of the drop servo
00172 
00173 boolean use_gps = false;  ///< whether or not to use gps, based on reading the slide_switch at power-on
00174 
00175 //Acceleration and Gyro
00176 Vector3f accel;
00177 Vector3f gyro;
00178 
00179 //GPS starting location
00180 long gps_start_lat = 0;
00181 long gps_start_lon = 0;
00182 
00183 //Declarations ---------------------------------------------------------
00184 
00185 //Serial setup
00186 FastSerialPort0(Serial);  ///< setup fast serial port (for FTDI)
00187 FastSerialPort1(Serial1);  ///< setup fast serial port (for GPS) to make gps library happy
00188 FastSerialPort3(Serial3);  ///< setup fast serial port for telemetry communication
00189 
00190 static GPS * gps;  ///< GPS pointer
00191 AP_GPS_Auto gps_driver (&Serial1,&gps);  ///< Initialize GPS (has to be outside of a function for some reason)
00192 
00193 static AP_ADC_ADS7844 adc; ///< declare an instance of the ADC class
00194 
00195 APM_BMP085_Class barometer;  ///< declare an instance of the Barometer class
00196 
00197 AP_IMU_Oilpan imu(&adc, 0);  ///< declare an instance of the IMU class, set to 0 to disable warm start (warm start = start in air in flight) 
00198 
00199 AP_Compass_HMC5843 compass;  ///< declare an instance of the Magnetometer class
00200 
00201 AP_DCM  dcm(&imu, gps);  ///< declare an instance of the DCM class
00202