StoRC
Autonomous Payload Delivery System
rc.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 rc.pde
00031  *  @brief Commands for reading and updating RC values
00032  *  @author Michael Posner (CIS, MEAM '12)
00033  *  @author Timothy Hennelly (ESE '12)
00034  *  @author Jacob Orloff (MEAM '12)
00035  *  
00036  */
00037 
00038 
00039 /**
00040  * Read RC values from the board (using the {@link APM_RC} library) and 
00041  * adjust them as necessary.
00042  * @see APM_RC
00043  */
00044 void read_RC(void) {
00045 
00046   // If a new RC Input has been received, read RC Commands
00047   //if (APM_RC.GetState() == 1){
00048 
00049     rc_elevator = APM_RC.InputCh(ELEVATOR_CH);
00050     rc_rudder = APM_RC.InputCh(RUDDER_CH);
00051     rc_throttle = APM_RC.InputCh(THROTTLE_CH);
00052 
00053     rc_4 = APM_RC.InputCh(RC4_CH);
00054     rc_5 = APM_RC.InputCh(RC5_CH);
00055     rc_6 = APM_RC.InputCh(RC6_CH);
00056     rc_7 = APM_RC.InputCh(RC7_CH);
00057     rc_8 = APM_RC.InputCh(RC8_CH);
00058 
00059   //}
00060 
00061 }
00062 
00063 
00064 /**
00065  * Send RC commands to the board outputs (using the {@link APM_RC} library)
00066  * and make sure they are reasonable.
00067  * @see APM_RC
00068  */
00069 void send_RC(void) {
00070 
00071   rc_elevator = constrain(rc_elevator,1000,2000);
00072   rc_throttle = constrain(rc_throttle,1000,2000);
00073   rc_rudder = constrain(rc_rudder,1000,2000);
00074   
00075   //Serial.print("sent ele: "); Serial.println(rc_elevator);
00076   APM_RC.OutputCh(ELEVATOR_CH,rc_elevator);
00077   APM_RC.OutputCh(RUDDER_CH,rc_rudder);
00078   APM_RC.OutputCh(THROTTLE_CH,rc_throttle);
00079 
00080 }
00081 
00082 
00083 /**
00084  * Check if the 4th RC channel is signaling a payload drop
00085  * @return true if ready to drop, false if not yet ready
00086  */
00087 boolean check_drop(void){
00088 
00089   rc_4 = constrain(rc_4,1000,2000);
00090 
00091   if(rc_4 > 1700) {
00092 
00093     if(drop_timer == -1) { //intention to drop is news to us
00094       drop_timer = millis();
00095     }
00096     else if(millis() - drop_timer > 3000) { //yeah, you really wanna drop.  we get it
00097       drop_timer = -1;
00098       return true;
00099     }
00100     else { //not sure if you really wanna drop.... 
00101       return false;
00102     }
00103 
00104   }
00105   else if(rc_4 < 1700 && drop_timer != -1) {  //you dont really wanna drop
00106     drop_timer = -1;
00107   }
00108   else if(rc_4 < 1300) { //reset drop servo
00109     reset_drop();
00110   }
00111   
00112   return false;
00113 
00114 }
00115 
00116 /**
00117 * Drop payload by sending output to the servo controlling the release.
00118 */
00119 void drop_payload(void) {
00120   APM_RC.OutputCh(DROP_SERVO,800);
00121 }
00122 
00123 /**
00124 * Reset the servo controlling the payload drop.
00125 */
00126 void reset_drop(void) {
00127   APM_RC.OutputCh(DROP_SERVO,1500);
00128 }
00129 
00130 
00131 /**
00132  * Filter RC commands when they are read. This function limits the difference
00133  * between the current and previous reading to prevent wild readings from being
00134  * used.
00135  * @param rc the current RC value as read from the board
00136  * @param rc_old the previous RC value
00137  * @return the adjusted current RC value to be used
00138  */
00139 int rc_filter(int rc, int rc_old) {
00140 
00141   int diff = rc - rc_old;  //difference between readings
00142 
00143   //if this is the first loop iteration, there is no old value so just return
00144   //  the current value
00145   if(rc_old == 0) {
00146     return rc;
00147   }
00148 
00149   //else limit things in some way
00150 
00151 }
00152 
00153