StoRC
Autonomous Payload Delivery System
pitot.pde
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 pitot.pde
00031  *  @brief Contains functions for reading pitot probe measurements
00032  *  @author Michael Posner (CIS, MEAM '12)
00033  *  @author Timothy Hennelly (ESE '12)
00034  *  @author Jacob Orloff (MEAM '12)
00035  *  
00036  *  Contains functions for reading and adjusting pressure 
00037  * measurements taken with the pitot probe.  Requires ADC functionality.
00038  */
00039 
00040 /**
00041 * Zero the airspeed measurement by storing the current pressure offset.
00042 */
00043 void zero_pitot(void) {
00044   
00045   float differential = 0;  ///< differential between static and dynamic pressure values
00046   
00047   //this sequence helps account for the instability in the readings by reading a few measurements and averaging
00048   for(int i = 0; i < 10; i++){
00049     delay(20);
00050     //differential = (differential * .75) + ((float)adc.Ch(PITOT_CH) * .25);  //read in raw value from ADC
00051     differential += (float)adc.Ch(PITOT_CH);
00052     
00053   }
00054   differential /= 10.0f;
00055   
00056   pitot_pressure_offset = (differential/1000.0f - PITOT_OFFSET) * PITOT_RATIO;  //convert voltage reading to pressure in kPa
00057 
00058 }
00059 
00060 
00061 /**
00062  * Read airspeed from pitot probe, convert appropriately, and store
00063  */
00064 void update_airspeed(void) {
00065 
00066   float differential = (float)adc.Ch(PITOT_CH);  //read in raw value from ADC (differential
00067   // between static and dynamic values)
00068 
00069   //Serial.print("Raw ADC: "); Serial.println(differential);
00070 
00071   float dynamic_pressure = ((differential/1000.0f - PITOT_OFFSET) * PITOT_RATIO) - pitot_pressure_offset;  //convert voltage reading to pressure in kPa
00072                                                       //shouldn't be negative (or else we're flying backwards)
00073   if(dynamic_pressure >= 0) {
00074     airspeed = sqrt(2.0f*dynamic_pressure*1000.0f/RHO);  // Pd = 1/2 * rho * V^2
00075   } else {
00076     airspeed = -1;  //some kind of error happened - maybe the wind was blowing into the side and decreasing the static pressure?
00077   }
00078 }
00079