Prof Greg Egan
/
UAVXArm-GKE
UAVX Multicopter Flight Controller.
menu.c@2:90292f8bd179, 2011-04-26 (annotated)
- Committer:
- gke
- Date:
- Tue Apr 26 12:12:29 2011 +0000
- Revision:
- 2:90292f8bd179
- Parent:
- 1:1e3318a30ddd
Not flightworthy. Posted for others to make use of the I2C SW code.
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
gke | 0:62a1c91a859a | 1 | // =============================================================================================== |
gke | 0:62a1c91a859a | 2 | // = UAVXArm Quadrocopter Controller = |
gke | 0:62a1c91a859a | 3 | // = Copyright (c) 2008 by Prof. Greg Egan = |
gke | 0:62a1c91a859a | 4 | // = Original V3.15 Copyright (c) 2007 Ing. Wolfgang Mahringer = |
gke | 2:90292f8bd179 | 5 | // = http://code.google.com/p/uavp-mods/ = |
gke | 0:62a1c91a859a | 6 | // =============================================================================================== |
gke | 0:62a1c91a859a | 7 | |
gke | 0:62a1c91a859a | 8 | // This is part of UAVXArm. |
gke | 0:62a1c91a859a | 9 | |
gke | 0:62a1c91a859a | 10 | // UAVXArm is free software: you can redistribute it and/or modify it under the terms of the GNU |
gke | 0:62a1c91a859a | 11 | // General Public License as published by the Free Software Foundation, either version 3 of the |
gke | 0:62a1c91a859a | 12 | // License, or (at your option) any later version. |
gke | 0:62a1c91a859a | 13 | |
gke | 0:62a1c91a859a | 14 | // UAVXArm is distributed in the hope that it will be useful,but WITHOUT ANY WARRANTY; without |
gke | 0:62a1c91a859a | 15 | // even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. |
gke | 0:62a1c91a859a | 16 | // See the GNU General Public License for more details. |
gke | 0:62a1c91a859a | 17 | |
gke | 0:62a1c91a859a | 18 | // You should have received a copy of the GNU General Public License along with this program. |
gke | 0:62a1c91a859a | 19 | // If not, see http://www.gnu.org/licenses/ |
gke | 0:62a1c91a859a | 20 | |
gke | 0:62a1c91a859a | 21 | #include "UAVXArm.h" |
gke | 0:62a1c91a859a | 22 | |
gke | 0:62a1c91a859a | 23 | void ShowPrompt(void); |
gke | 0:62a1c91a859a | 24 | void ShowRxSetup(void); |
gke | 0:62a1c91a859a | 25 | void ShowSetup(boolean); |
gke | 0:62a1c91a859a | 26 | uint8 MakeUpper(uint8); |
gke | 0:62a1c91a859a | 27 | void ProcessCommand(void); |
gke | 0:62a1c91a859a | 28 | |
gke | 0:62a1c91a859a | 29 | const uint8 SerHello[] = "UAVXArm " |
gke | 0:62a1c91a859a | 30 | " Copyright 2008 G.K. Egan & 2007 W. Mahringer\r\n" |
gke | 0:62a1c91a859a | 31 | "This is FREE SOFTWARE and comes with ABSOLUTELY NO WARRANTY " |
gke | 0:62a1c91a859a | 32 | "see http://www.gnu.org/licenses/!\r\n"; |
gke | 0:62a1c91a859a | 33 | const uint8 SerHelp[] = "\r\nCommands:\r\n" |
gke | 0:62a1c91a859a | 34 | "A..Attitude test\r\n" |
gke | 0:62a1c91a859a | 35 | "C..Compass test\r\n" |
gke | 0:62a1c91a859a | 36 | "D..Load default parameter set\r\n" |
gke | 0:62a1c91a859a | 37 | "G..GPS test\r\n" |
gke | 0:62a1c91a859a | 38 | "H..Barometer/Rangefinder test\r\n" |
gke | 0:62a1c91a859a | 39 | "I..I2C bus scan\r\n" |
gke | 0:62a1c91a859a | 40 | "K..Calibrate compass scan\r\n" |
gke | 0:62a1c91a859a | 41 | // "M..Modify parameters\r\n" |
gke | 0:62a1c91a859a | 42 | "P..Rx test\r\n" |
gke | 0:62a1c91a859a | 43 | "S..Setup\r\n" |
gke | 0:62a1c91a859a | 44 | "T..All LEDs and buzzer test\r\n" |
gke | 0:62a1c91a859a | 45 | "V..Battery test\r\n" |
gke | 0:62a1c91a859a | 46 | "X..Flight stats\r\n" |
gke | 0:62a1c91a859a | 47 | "Y..Program YGE I2C ESC\r\n" |
gke | 0:62a1c91a859a | 48 | "1-8..Individual LED/buzzer test\r\n"; // last line must be in this form for UAVPSet |
gke | 0:62a1c91a859a | 49 | |
gke | 0:62a1c91a859a | 50 | const uint8 RxChMnem[] = "TAERG12"; |
gke | 0:62a1c91a859a | 51 | |
gke | 0:62a1c91a859a | 52 | uint8 MakeUpper(uint8 ch) { |
gke | 0:62a1c91a859a | 53 | if ( ( ch >='a') && ( ch <='z' ) ) |
gke | 0:62a1c91a859a | 54 | ch = (ch - 'a') + 'A'; |
gke | 0:62a1c91a859a | 55 | |
gke | 0:62a1c91a859a | 56 | return (ch); |
gke | 0:62a1c91a859a | 57 | } // MakeUpper |
gke | 0:62a1c91a859a | 58 | |
gke | 0:62a1c91a859a | 59 | void ShowPrompt(void) { |
gke | 0:62a1c91a859a | 60 | TxString("\r\n>"); |
gke | 0:62a1c91a859a | 61 | } // ShowPrompt |
gke | 0:62a1c91a859a | 62 | |
gke | 0:62a1c91a859a | 63 | void ShowRxSetup(void) { |
gke | 0:62a1c91a859a | 64 | if ( F.UsingSerialPPM ) |
gke | 0:62a1c91a859a | 65 | if ( PPMPosPolarity[P[TxRxType]] ) |
gke | 0:62a1c91a859a | 66 | TxString("Serial PPM frame (Positive Polarity)"); |
gke | 0:62a1c91a859a | 67 | else |
gke | 0:62a1c91a859a | 68 | TxString("Serial PPM frame (Negative Polarity)"); |
gke | 0:62a1c91a859a | 69 | else |
gke | 0:62a1c91a859a | 70 | TxString("Odd Rx Channels PPM"); |
gke | 0:62a1c91a859a | 71 | } // ShowRxSetup |
gke | 0:62a1c91a859a | 72 | |
gke | 0:62a1c91a859a | 73 | void ShowSetup(boolean h) { |
gke | 0:62a1c91a859a | 74 | int8 i; |
gke | 0:62a1c91a859a | 75 | |
gke | 0:62a1c91a859a | 76 | TxNextLine(); |
gke | 0:62a1c91a859a | 77 | if ( h ) |
gke | 0:62a1c91a859a | 78 | ParamSet = 1; |
gke | 0:62a1c91a859a | 79 | |
gke | 0:62a1c91a859a | 80 | TxString(SerHello); |
gke | 0:62a1c91a859a | 81 | |
gke | 0:62a1c91a859a | 82 | UpdateRTC(); |
gke | 0:62a1c91a859a | 83 | i = 0; |
gke | 0:62a1c91a859a | 84 | while ( RTCString[i] != NULL ) |
gke | 0:62a1c91a859a | 85 | TxChar(RTCString[i++]); |
gke | 0:62a1c91a859a | 86 | TxNextLine(); |
gke | 0:62a1c91a859a | 87 | |
gke | 0:62a1c91a859a | 88 | TxString("Clock: 92MHz LPC1768 (mbed)\r\n"); |
gke | 0:62a1c91a859a | 89 | |
gke | 0:62a1c91a859a | 90 | TxString("Aircraft: "); |
gke | 0:62a1c91a859a | 91 | switch ( UAVXAirframe ) { |
gke | 0:62a1c91a859a | 92 | case QuadAF: |
gke | 0:62a1c91a859a | 93 | TxString("QUADROCOPTER\r\n"); |
gke | 0:62a1c91a859a | 94 | break; |
gke | 0:62a1c91a859a | 95 | case TriAF: |
gke | 0:62a1c91a859a | 96 | TxString("TRICOPTER\r\n"); |
gke | 0:62a1c91a859a | 97 | break; |
gke | 0:62a1c91a859a | 98 | case VTAF: |
gke | 0:62a1c91a859a | 99 | TxString("VTCOPTER\r\n"); |
gke | 0:62a1c91a859a | 100 | break; |
gke | 0:62a1c91a859a | 101 | case HeliAF: |
gke | 0:62a1c91a859a | 102 | TxString("HELICOPTER\r\n"); |
gke | 0:62a1c91a859a | 103 | break; |
gke | 0:62a1c91a859a | 104 | case ElevAF: |
gke | 0:62a1c91a859a | 105 | TxString("FLYING WING\r\n"); |
gke | 0:62a1c91a859a | 106 | break; |
gke | 0:62a1c91a859a | 107 | case AilAF: |
gke | 0:62a1c91a859a | 108 | TxString("AILERON\r\n"); |
gke | 0:62a1c91a859a | 109 | break; |
gke | 0:62a1c91a859a | 110 | default: |
gke | 0:62a1c91a859a | 111 | TxString("UNKNOWN\r\n"); |
gke | 0:62a1c91a859a | 112 | } |
gke | 0:62a1c91a859a | 113 | |
gke | 0:62a1c91a859a | 114 | if ( F.CompassValid ) { |
gke | 0:62a1c91a859a | 115 | TxString("Compass: "); |
gke | 0:62a1c91a859a | 116 | ShowCompassType(); |
gke | 0:62a1c91a859a | 117 | TxString(" ( offset "); |
gke | 0:62a1c91a859a | 118 | TxVal32((int16)P[CompassOffsetQtr] * 90,0,0); |
gke | 0:62a1c91a859a | 119 | TxString("deg. )\r\n"); |
gke | 0:62a1c91a859a | 120 | } |
gke | 0:62a1c91a859a | 121 | |
gke | 0:62a1c91a859a | 122 | TxString("Baro: "); |
gke | 0:62a1c91a859a | 123 | ShowBaroType(); |
gke | 0:62a1c91a859a | 124 | |
gke | 0:62a1c91a859a | 125 | TxString("Accelerometers: "); |
gke | 0:62a1c91a859a | 126 | ShowAccType(); |
gke | 0:62a1c91a859a | 127 | TxNextLine(); |
gke | 0:62a1c91a859a | 128 | |
gke | 0:62a1c91a859a | 129 | TxString("Gyros: "); |
gke | 0:62a1c91a859a | 130 | ShowGyroType(); |
gke | 0:62a1c91a859a | 131 | TxNextLine(); |
gke | 0:62a1c91a859a | 132 | |
gke | 0:62a1c91a859a | 133 | TxString("Motor ESCs: "); |
gke | 0:62a1c91a859a | 134 | switch ( P[ESCType] ) { |
gke | 0:62a1c91a859a | 135 | case ESCPPM: |
gke | 0:62a1c91a859a | 136 | TxString("PPM "); |
gke | 0:62a1c91a859a | 137 | break; |
gke | 0:62a1c91a859a | 138 | case ESCHolger: |
gke | 0:62a1c91a859a | 139 | TxString("Holger I2C {"); |
gke | 0:62a1c91a859a | 140 | break; |
gke | 0:62a1c91a859a | 141 | case ESCX3D: |
gke | 0:62a1c91a859a | 142 | TxString("X-3D I2C {"); |
gke | 0:62a1c91a859a | 143 | break; |
gke | 0:62a1c91a859a | 144 | case ESCYGEI2C: |
gke | 0:62a1c91a859a | 145 | TxString("YGE I2C {"); |
gke | 0:62a1c91a859a | 146 | break; |
gke | 0:62a1c91a859a | 147 | } |
gke | 0:62a1c91a859a | 148 | |
gke | 0:62a1c91a859a | 149 | if ( P[ESCType] != ESCPPM ) { |
gke | 0:62a1c91a859a | 150 | for ( i = 0; i < NoOfI2CESCOutputs; i++ ) |
gke | 0:62a1c91a859a | 151 | if ( ESCI2CFail[i] ) |
gke | 0:62a1c91a859a | 152 | TxString(" Fail"); |
gke | 0:62a1c91a859a | 153 | else |
gke | 0:62a1c91a859a | 154 | TxString(" OK"); |
gke | 0:62a1c91a859a | 155 | TxString(" }"); |
gke | 0:62a1c91a859a | 156 | } |
gke | 0:62a1c91a859a | 157 | TxNextLine(); |
gke | 0:62a1c91a859a | 158 | |
gke | 0:62a1c91a859a | 159 | if ( F.HaveBatterySensor ) |
gke | 0:62a1c91a859a | 160 | TxString("External Volt/Amp Sensor Fitted\r\n"); |
gke | 0:62a1c91a859a | 161 | #ifdef RX6CH |
gke | 0:62a1c91a859a | 162 | TxString("6 CHANNEL VERSION - 5 ACTIVE CHANNELS ONLY\r\n"); |
gke | 0:62a1c91a859a | 163 | #endif // RX6CH |
gke | 0:62a1c91a859a | 164 | |
gke | 0:62a1c91a859a | 165 | TxString("Tx/Rx: "); |
gke | 0:62a1c91a859a | 166 | |
gke | 0:62a1c91a859a | 167 | switch ( P[TxRxType] ) { |
gke | 0:62a1c91a859a | 168 | case FutabaCh3: |
gke | 0:62a1c91a859a | 169 | TxString("Futaba Th 3 {"); |
gke | 0:62a1c91a859a | 170 | break; |
gke | 0:62a1c91a859a | 171 | case FutabaCh2: |
gke | 0:62a1c91a859a | 172 | TxString("Futaba Th 2 {"); |
gke | 0:62a1c91a859a | 173 | break; |
gke | 0:62a1c91a859a | 174 | case FutabaDM8: |
gke | 0:62a1c91a859a | 175 | TxString("Futaba DM8 & AR7000 {"); |
gke | 0:62a1c91a859a | 176 | break; |
gke | 0:62a1c91a859a | 177 | case JRPPM: |
gke | 0:62a1c91a859a | 178 | TxString("JR PPM {"); |
gke | 0:62a1c91a859a | 179 | break; |
gke | 0:62a1c91a859a | 180 | case JRDM9: |
gke | 0:62a1c91a859a | 181 | TxString("JR DM9 & AR7000{"); |
gke | 0:62a1c91a859a | 182 | break; |
gke | 0:62a1c91a859a | 183 | case JRDXS12: |
gke | 0:62a1c91a859a | 184 | TxString("JR DSX12 & AR7000 {"); |
gke | 0:62a1c91a859a | 185 | break; |
gke | 0:62a1c91a859a | 186 | case DX7AR7000: |
gke | 0:62a1c91a859a | 187 | TxString("Spektrum DX7 & AR7000 {"); |
gke | 0:62a1c91a859a | 188 | break; |
gke | 0:62a1c91a859a | 189 | case DX7AR6200: |
gke | 0:62a1c91a859a | 190 | TxString("Spektrum DX7 & AR6200 {"); |
gke | 0:62a1c91a859a | 191 | break; |
gke | 0:62a1c91a859a | 192 | case CustomTxRx: |
gke | 0:62a1c91a859a | 193 | TxString("Custom {"); |
gke | 0:62a1c91a859a | 194 | break; |
gke | 0:62a1c91a859a | 195 | case FutabaCh3_6_7: |
gke | 0:62a1c91a859a | 196 | TxString("Futaba Th 2 Swap 6&7 {"); |
gke | 0:62a1c91a859a | 197 | break; |
gke | 0:62a1c91a859a | 198 | case DX7AR6000: |
gke | 0:62a1c91a859a | 199 | TxString("Spektrum DX7 & AR6000 {"); |
gke | 0:62a1c91a859a | 200 | break; |
gke | 0:62a1c91a859a | 201 | case DX6iAR6200: |
gke | 0:62a1c91a859a | 202 | TxString("Spektrum DX6i & AR6200 {"); |
gke | 0:62a1c91a859a | 203 | break; |
gke | 0:62a1c91a859a | 204 | case FutabaCh3_R617FS: |
gke | 0:62a1c91a859a | 205 | TxString("Futaba Th 3 & R617FS {"); |
gke | 0:62a1c91a859a | 206 | break; |
gke | 0:62a1c91a859a | 207 | case GraupnerMX16s: |
gke | 0:62a1c91a859a | 208 | TxString("Graupner MX16s {"); |
gke | 0:62a1c91a859a | 209 | break; |
gke | 0:62a1c91a859a | 210 | case DX7aAR7000: |
gke | 0:62a1c91a859a | 211 | TxString("Spektrum DX7a & AR7000 {"); |
gke | 0:62a1c91a859a | 212 | break; |
gke | 0:62a1c91a859a | 213 | case FrSkyDJT_D8R: |
gke | 0:62a1c91a859a | 214 | TxString("FrSky DJT & D8R-SP Composite {"); |
gke | 0:62a1c91a859a | 215 | break; |
gke | 0:62a1c91a859a | 216 | case ExternalDecoder: |
gke | 0:62a1c91a859a | 217 | TxString("External Decoder {"); |
gke | 0:62a1c91a859a | 218 | break; |
gke | 0:62a1c91a859a | 219 | case UnknownTxRx: |
gke | 0:62a1c91a859a | 220 | TxString("UNKNOWN {"); |
gke | 0:62a1c91a859a | 221 | break; |
gke | 0:62a1c91a859a | 222 | default: |
gke | 0:62a1c91a859a | 223 | ; |
gke | 0:62a1c91a859a | 224 | } // switch |
gke | 0:62a1c91a859a | 225 | |
gke | 0:62a1c91a859a | 226 | if ( F.UsingSerialPPM ) |
gke | 0:62a1c91a859a | 227 | ShowRxSetup(); |
gke | 0:62a1c91a859a | 228 | else |
gke | 0:62a1c91a859a | 229 | if ( P[TxRxType] != UnknownTxRx ) { |
gke | 0:62a1c91a859a | 230 | for ( i = 0; i < RC_CONTROLS; i++) |
gke | 0:62a1c91a859a | 231 | TxChar(RxChMnem[RMap[i]]); |
gke | 0:62a1c91a859a | 232 | |
gke | 0:62a1c91a859a | 233 | TxString("} connect {"); |
gke | 0:62a1c91a859a | 234 | |
gke | 0:62a1c91a859a | 235 | for ( i = 0; i < RC_CONTROLS; i+=2) { |
gke | 0:62a1c91a859a | 236 | TxChar(RxChMnem[RMap[i]]); |
gke | 0:62a1c91a859a | 237 | TxChar(' '); |
gke | 0:62a1c91a859a | 238 | } |
gke | 0:62a1c91a859a | 239 | } |
gke | 0:62a1c91a859a | 240 | TxChar('}'); |
gke | 0:62a1c91a859a | 241 | if (( P[TxRxType] == DX7AR6200 ) || ( P[TxRxType] == DX6iAR6200)) |
gke | 0:62a1c91a859a | 242 | TxString(" Mix Rudder to Aux1/Flaps "); |
gke | 0:62a1c91a859a | 243 | if ( F.UsingTxMode2 ) |
gke | 0:62a1c91a859a | 244 | TxString(" Tx Mode 2"); |
gke | 0:62a1c91a859a | 245 | else |
gke | 0:62a1c91a859a | 246 | TxString(" Tx Mode 1"); |
gke | 0:62a1c91a859a | 247 | TxNextLine(); |
gke | 0:62a1c91a859a | 248 | |
gke | 0:62a1c91a859a | 249 | TxString("Selected parameter set: "); // must be exactly this string as UAVPSet expects it |
gke | 0:62a1c91a859a | 250 | TxChar('0' + ParamSet); |
gke | 0:62a1c91a859a | 251 | TxNextLine(); |
gke | 0:62a1c91a859a | 252 | |
gke | 0:62a1c91a859a | 253 | #ifdef MULTICOPTER |
gke | 0:62a1c91a859a | 254 | TxString("Forward Flight: "); |
gke | 0:62a1c91a859a | 255 | TxVal32((int16)Orientation * 75L, 1, 0); |
gke | 0:62a1c91a859a | 256 | TxString("deg CW from K1 motor(s)\r\n"); |
gke | 0:62a1c91a859a | 257 | #endif // MULTICOPTER |
gke | 0:62a1c91a859a | 258 | |
gke | 0:62a1c91a859a | 259 | if ( F.UsingAngleControl ) |
gke | 0:62a1c91a859a | 260 | TxString("\tSticks control roll/pitch angle directly\r\n"); |
gke | 0:62a1c91a859a | 261 | else |
gke | 0:62a1c91a859a | 262 | TxString("\tSticks control rate of change of roll/pitch angle\r\n"); |
gke | 0:62a1c91a859a | 263 | |
gke | 0:62a1c91a859a | 264 | if ( F.UsingRTHAutoDescend ) |
gke | 0:62a1c91a859a | 265 | TxString("\tAuto descend ENABLED\r\n"); |
gke | 0:62a1c91a859a | 266 | else |
gke | 0:62a1c91a859a | 267 | TxString("\tAuto descend disabled\r\n"); |
gke | 0:62a1c91a859a | 268 | |
gke | 0:62a1c91a859a | 269 | if ( F.AllowTurnToWP ) |
gke | 0:62a1c91a859a | 270 | TxString("\tTurn toward Way Point\r\n"); |
gke | 0:62a1c91a859a | 271 | else |
gke | 0:62a1c91a859a | 272 | TxString("\tHold heading\r\n"); |
gke | 0:62a1c91a859a | 273 | |
gke | 0:62a1c91a859a | 274 | if ( F.AllowNavAltitudeHold ) |
gke | 0:62a1c91a859a | 275 | TxString("\tAllow Nav altitude hold\r\n"); |
gke | 0:62a1c91a859a | 276 | else |
gke | 0:62a1c91a859a | 277 | TxString("\tWARNING - Manual Nav altitude hold\r\n"); |
gke | 0:62a1c91a859a | 278 | |
gke | 0:62a1c91a859a | 279 | if ( !F.SDCardValid ) |
gke | 0:62a1c91a859a | 280 | TxString("\tSD Card NOT loaded - DISCONNECT power and load card if required.\r\n"); |
gke | 0:62a1c91a859a | 281 | |
gke | 0:62a1c91a859a | 282 | TxString("\r\nALARM (if any):\r\n"); |
gke | 0:62a1c91a859a | 283 | if ( P[TxRxType] == UnknownTxRx ) |
gke | 0:62a1c91a859a | 284 | TxString("\tTx/Rx TYPE not set\r\n"); |
gke | 0:62a1c91a859a | 285 | #ifdef TESTING |
gke | 0:62a1c91a859a | 286 | TxString("\tTEST VERSION - No Motors\r\n"); |
gke | 0:62a1c91a859a | 287 | #endif // TESTING |
gke | 0:62a1c91a859a | 288 | |
gke | 0:62a1c91a859a | 289 | if ( !F.ParametersValid ) |
gke | 0:62a1c91a859a | 290 | TxString("\tINVALID flight parameters (PID)!\r\n"); |
gke | 0:62a1c91a859a | 291 | |
gke | 0:62a1c91a859a | 292 | if ( !F.BaroAltitudeValid ) |
gke | 0:62a1c91a859a | 293 | TxString("\tBarometer OFFLINE\r\n"); |
gke | 0:62a1c91a859a | 294 | if ( BaroRetries >= BARO_INIT_RETRIES ) |
gke | 0:62a1c91a859a | 295 | TxString("\tBaro Init: FAILED\r\n"); |
gke | 0:62a1c91a859a | 296 | |
gke | 0:62a1c91a859a | 297 | if ( !F.RangefinderAltitudeValid ) |
gke | 0:62a1c91a859a | 298 | TxString("\tRangefinder OFFLINE\r\n"); |
gke | 0:62a1c91a859a | 299 | |
gke | 0:62a1c91a859a | 300 | if ( F.GyroFailure ) |
gke | 0:62a1c91a859a | 301 | TxString("\tGyro FAILURE\r\n"); |
gke | 0:62a1c91a859a | 302 | |
gke | 0:62a1c91a859a | 303 | if ( !F.AccelerationsValid ) |
gke | 0:62a1c91a859a | 304 | TxString("\tAccelerometers OFFLINE\r\n"); |
gke | 0:62a1c91a859a | 305 | |
gke | 0:62a1c91a859a | 306 | if ( !F.CompassValid ) |
gke | 0:62a1c91a859a | 307 | TxString("\tCompass OFFLINE\r\n"); |
gke | 0:62a1c91a859a | 308 | |
gke | 0:62a1c91a859a | 309 | if ( !F.Signal ) |
gke | 0:62a1c91a859a | 310 | TxString("\tBad EPAs or Tx switched off?\r\n"); |
gke | 0:62a1c91a859a | 311 | if ( Armed && FirstPass ) |
gke | 0:62a1c91a859a | 312 | TxString("\tUAVX is armed - DISARM!\r\n"); |
gke | 0:62a1c91a859a | 313 | |
gke | 0:62a1c91a859a | 314 | if ( F.Navigate || F.ReturnHome ) |
gke | 0:62a1c91a859a | 315 | TxString("\tNavigate/RTH is selected - DESELECT!\r\n"); |
gke | 0:62a1c91a859a | 316 | |
gke | 0:62a1c91a859a | 317 | if ( InitialThrottle >= RC_THRES_START ) |
gke | 0:62a1c91a859a | 318 | TxString("\tThrottle may be open - CLOSE!\r\n"); |
gke | 2:90292f8bd179 | 319 | |
gke | 2:90292f8bd179 | 320 | if ( !F.UsingLEDDriver ) |
gke | 2:90292f8bd179 | 321 | TxString("\tPCA Line Driver OFFLINE - no BUZZER warnings!\r\n"); |
gke | 2:90292f8bd179 | 322 | |
gke | 0:62a1c91a859a | 323 | ShowPrompt(); |
gke | 0:62a1c91a859a | 324 | } // ShowSetup |
gke | 0:62a1c91a859a | 325 | |
gke | 0:62a1c91a859a | 326 | void ProcessCommand(void) { |
gke | 0:62a1c91a859a | 327 | static int8 p; |
gke | 0:62a1c91a859a | 328 | static uint8 ch; |
gke | 0:62a1c91a859a | 329 | static int8 d; |
gke | 0:62a1c91a859a | 330 | |
gke | 0:62a1c91a859a | 331 | if ( 1 ) {//!Armed.read() ) { |
gke | 0:62a1c91a859a | 332 | ch = PollRxChar(); |
gke | 0:62a1c91a859a | 333 | if ( ch != NUL ) { |
gke | 0:62a1c91a859a | 334 | ch = MakeUpper(ch); |
gke | 0:62a1c91a859a | 335 | |
gke | 0:62a1c91a859a | 336 | switch ( ch ) { |
gke | 0:62a1c91a859a | 337 | case 'D': |
gke | 0:62a1c91a859a | 338 | UseDefaultParameters(); |
gke | 2:90292f8bd179 | 339 | InitParameters(); |
gke | 0:62a1c91a859a | 340 | ShowPrompt(); |
gke | 0:62a1c91a859a | 341 | break; |
gke | 0:62a1c91a859a | 342 | case 'L' : // List parameters |
gke | 0:62a1c91a859a | 343 | TxString("\r\nParameter list for set #"); // do not change (UAVPset!) |
gke | 0:62a1c91a859a | 344 | TxChar('0' + ParamSet); |
gke | 0:62a1c91a859a | 345 | ReadParameters(); |
gke | 0:62a1c91a859a | 346 | for ( p = 0 ; p < MAX_PARAMETERS; p++ ) { |
gke | 0:62a1c91a859a | 347 | TxString("\r\nRegister "); |
gke | 0:62a1c91a859a | 348 | TxValU((uint8)(p+1)); |
gke | 0:62a1c91a859a | 349 | TxString(" = "); |
gke | 0:62a1c91a859a | 350 | TxValS(P[p]); |
gke | 0:62a1c91a859a | 351 | } |
gke | 0:62a1c91a859a | 352 | ShowPrompt(); |
gke | 0:62a1c91a859a | 353 | break; |
gke | 0:62a1c91a859a | 354 | case 'M' : // modify parameters |
gke | 0:62a1c91a859a | 355 | // no reprogramming in flight!!!!!!!!!!!!!!! |
gke | 0:62a1c91a859a | 356 | LEDBlue_ON; |
gke | 0:62a1c91a859a | 357 | TxString("\r\nRegister "); |
gke | 0:62a1c91a859a | 358 | p = (uint16)(RxNumU()-1); |
gke | 0:62a1c91a859a | 359 | // Attempts to block use of old versions of UAVPSet not compatible with UAVX |
gke | 0:62a1c91a859a | 360 | // assumes parameters are written sequentially from 0..(MAX_PARAMETERS-1) |
gke | 0:62a1c91a859a | 361 | |
gke | 0:62a1c91a859a | 362 | TxString(" = "); |
gke | 0:62a1c91a859a | 363 | d = RxNumS(); |
gke | 0:62a1c91a859a | 364 | if ( p < MAX_PARAMETERS ) { |
gke | 0:62a1c91a859a | 365 | // Keep RAM based set up to date. |
gke | 0:62a1c91a859a | 366 | if ( ParamSet == (uint8)1 ) { |
gke | 0:62a1c91a859a | 367 | WritePX(p, d); |
gke | 0:62a1c91a859a | 368 | if ( DefaultParams[p][1] ) |
gke | 0:62a1c91a859a | 369 | WritePX(MAX_PARAMETERS + p, d); |
gke | 0:62a1c91a859a | 370 | } else { |
gke | 0:62a1c91a859a | 371 | if ( !DefaultParams[p][1] ) |
gke | 0:62a1c91a859a | 372 | WritePX(MAX_PARAMETERS + p, d); |
gke | 0:62a1c91a859a | 373 | } |
gke | 0:62a1c91a859a | 374 | ParametersChanged = true; |
gke | 0:62a1c91a859a | 375 | } |
gke | 0:62a1c91a859a | 376 | if ( p < (MAX_PARAMETERS-1) ) |
gke | 0:62a1c91a859a | 377 | F.ParametersValid = false; |
gke | 0:62a1c91a859a | 378 | else |
gke | 0:62a1c91a859a | 379 | if ( p == (MAX_PARAMETERS-1) ) { |
gke | 0:62a1c91a859a | 380 | WritePXImagefile(); |
gke | 0:62a1c91a859a | 381 | F.ParametersValid = true; // ALL parameters must be written |
gke | 0:62a1c91a859a | 382 | } |
gke | 0:62a1c91a859a | 383 | LEDBlue_OFF; |
gke | 0:62a1c91a859a | 384 | ShowPrompt(); |
gke | 0:62a1c91a859a | 385 | break; |
gke | 0:62a1c91a859a | 386 | case 'N' : // neutral values |
gke | 2:90292f8bd179 | 387 | GetNeutralAccelerations(); |
gke | 0:62a1c91a859a | 388 | TxString("\r\nNeutral R:"); |
gke | 2:90292f8bd179 | 389 | TxValS(NewAccNeutral[LR]); |
gke | 0:62a1c91a859a | 390 | |
gke | 0:62a1c91a859a | 391 | TxString(" P:"); |
gke | 2:90292f8bd179 | 392 | TxValS(NewAccNeutral[BF]); |
gke | 2:90292f8bd179 | 393 | |
gke | 0:62a1c91a859a | 394 | TxString(" V:"); |
gke | 0:62a1c91a859a | 395 | TxValS(NewAccNeutral[UD]); |
gke | 0:62a1c91a859a | 396 | ShowPrompt(); |
gke | 0:62a1c91a859a | 397 | break; |
gke | 0:62a1c91a859a | 398 | case 'Z' : // set Paramset |
gke | 0:62a1c91a859a | 399 | p = RxNumU(); |
gke | 0:62a1c91a859a | 400 | if ( p != (int8)ParamSet ) { |
gke | 0:62a1c91a859a | 401 | ParamSet = p; |
gke | 0:62a1c91a859a | 402 | ParametersChanged = true; |
gke | 0:62a1c91a859a | 403 | ReadParameters(); |
gke | 0:62a1c91a859a | 404 | } |
gke | 0:62a1c91a859a | 405 | break; |
gke | 0:62a1c91a859a | 406 | case 'W' : // comms with UAVXNav utility NOT UAVPSet |
gke | 0:62a1c91a859a | 407 | UAVXNavCommand(); |
gke | 0:62a1c91a859a | 408 | //ShowPrompt(); |
gke | 0:62a1c91a859a | 409 | break; |
gke | 0:62a1c91a859a | 410 | case 'R': // receiver values |
gke | 0:62a1c91a859a | 411 | TxString("\r\nT:"); |
gke | 0:62a1c91a859a | 412 | TxValU(ToPercent(RC[ThrottleRC], RC_MAXIMUM)); |
gke | 0:62a1c91a859a | 413 | TxString(",R:"); |
gke | 0:62a1c91a859a | 414 | TxValS(ToPercent(((RC[RollRC]- RC_NEUTRAL) * 2L), RC_MAXIMUM)); |
gke | 0:62a1c91a859a | 415 | TxString(",P:"); |
gke | 0:62a1c91a859a | 416 | TxValS(ToPercent(((RC[PitchRC]- RC_NEUTRAL) * 2L), RC_MAXIMUM)); |
gke | 0:62a1c91a859a | 417 | TxString(",Y:"); |
gke | 0:62a1c91a859a | 418 | TxValS(ToPercent(((RC[YawRC]- RC_NEUTRAL) * 2L), RC_MAXIMUM)); |
gke | 0:62a1c91a859a | 419 | TxString(",5:"); |
gke | 0:62a1c91a859a | 420 | TxValU(ToPercent(RC[RTHRC], RC_MAXIMUM)); |
gke | 0:62a1c91a859a | 421 | TxString(",6:"); |
gke | 0:62a1c91a859a | 422 | TxValS(ToPercent(((RC[CamPitchRC] - RC_NEUTRAL) * 2L), RC_MAXIMUM)); |
gke | 0:62a1c91a859a | 423 | TxString(",7:"); |
gke | 0:62a1c91a859a | 424 | TxValU(ToPercent(RC[NavGainRC], RC_MAXIMUM)); |
gke | 0:62a1c91a859a | 425 | ShowPrompt(); |
gke | 0:62a1c91a859a | 426 | break; |
gke | 0:62a1c91a859a | 427 | case 'S' : // show status |
gke | 0:62a1c91a859a | 428 | ShowSetup(false); |
gke | 0:62a1c91a859a | 429 | break; |
gke | 0:62a1c91a859a | 430 | case 'X' : // flight stats |
gke | 0:62a1c91a859a | 431 | ShowStats(); |
gke | 0:62a1c91a859a | 432 | ShowPrompt(); |
gke | 0:62a1c91a859a | 433 | break; |
gke | 0:62a1c91a859a | 434 | case 'A' : // linear sensor |
gke | 0:62a1c91a859a | 435 | AttitudeTest(); |
gke | 0:62a1c91a859a | 436 | ShowPrompt(); |
gke | 0:62a1c91a859a | 437 | break; |
gke | 0:62a1c91a859a | 438 | case 'G': // GPS |
gke | 2:90292f8bd179 | 439 | GPSTest(); |
gke | 0:62a1c91a859a | 440 | ShowPrompt(); |
gke | 0:62a1c91a859a | 441 | break; |
gke | 0:62a1c91a859a | 442 | case 'H': // barometer |
gke | 0:62a1c91a859a | 443 | BaroTest(); |
gke | 0:62a1c91a859a | 444 | ShowPrompt(); |
gke | 0:62a1c91a859a | 445 | break; |
gke | 0:62a1c91a859a | 446 | case 'I': |
gke | 0:62a1c91a859a | 447 | TxString("\r\nI2C devices ...\r\n"); |
gke | 0:62a1c91a859a | 448 | TxVal32(ScanI2CBus(),0,0); |
gke | 0:62a1c91a859a | 449 | TxString(" device(s) found\r\n"); |
gke | 0:62a1c91a859a | 450 | ShowPrompt(); |
gke | 0:62a1c91a859a | 451 | break; |
gke | 0:62a1c91a859a | 452 | case 'P' : // Receiver test |
gke | 0:62a1c91a859a | 453 | ReceiverTest(); |
gke | 0:62a1c91a859a | 454 | ShowPrompt(); |
gke | 0:62a1c91a859a | 455 | break; |
gke | 0:62a1c91a859a | 456 | case 'C' : // Compass test |
gke | 0:62a1c91a859a | 457 | DoCompassTest(); |
gke | 0:62a1c91a859a | 458 | ShowPrompt(); |
gke | 0:62a1c91a859a | 459 | break; |
gke | 0:62a1c91a859a | 460 | |
gke | 0:62a1c91a859a | 461 | case 'K' : //Calibrate compass |
gke | 0:62a1c91a859a | 462 | CalibrateCompass(); |
gke | 0:62a1c91a859a | 463 | ShowPrompt(); |
gke | 0:62a1c91a859a | 464 | break; |
gke | 0:62a1c91a859a | 465 | |
gke | 0:62a1c91a859a | 466 | case 'Y': // configure YGE30i EScs |
gke | 0:62a1c91a859a | 467 | ConfigureESCs(); |
gke | 0:62a1c91a859a | 468 | ShowPrompt(); |
gke | 0:62a1c91a859a | 469 | break; |
gke | 0:62a1c91a859a | 470 | case '1': |
gke | 0:62a1c91a859a | 471 | case '2': |
gke | 0:62a1c91a859a | 472 | case '3': |
gke | 0:62a1c91a859a | 473 | case '4': |
gke | 0:62a1c91a859a | 474 | case '5': |
gke | 0:62a1c91a859a | 475 | case '6': |
gke | 0:62a1c91a859a | 476 | case '7': |
gke | 0:62a1c91a859a | 477 | case '8': |
gke | 0:62a1c91a859a | 478 | TxString("\r\nOutput test\r\n"); |
gke | 0:62a1c91a859a | 479 | TxChar(ch); |
gke | 0:62a1c91a859a | 480 | TxChar(':'); |
gke | 0:62a1c91a859a | 481 | switch ( ch ) { |
gke | 0:62a1c91a859a | 482 | case '1': |
gke | 0:62a1c91a859a | 483 | TxString("Aux2"); |
gke | 0:62a1c91a859a | 484 | break; |
gke | 0:62a1c91a859a | 485 | case '2': |
gke | 0:62a1c91a859a | 486 | TxString("Blue"); |
gke | 0:62a1c91a859a | 487 | break; |
gke | 0:62a1c91a859a | 488 | case '3': |
gke | 0:62a1c91a859a | 489 | TxString("Red"); |
gke | 0:62a1c91a859a | 490 | break; |
gke | 0:62a1c91a859a | 491 | case '4': |
gke | 0:62a1c91a859a | 492 | TxString("Green"); |
gke | 0:62a1c91a859a | 493 | break; |
gke | 0:62a1c91a859a | 494 | case '5': |
gke | 0:62a1c91a859a | 495 | TxString("Aux1"); |
gke | 0:62a1c91a859a | 496 | break; |
gke | 0:62a1c91a859a | 497 | case '6': |
gke | 0:62a1c91a859a | 498 | TxString("Yellow"); |
gke | 0:62a1c91a859a | 499 | break; |
gke | 0:62a1c91a859a | 500 | case '7': |
gke | 0:62a1c91a859a | 501 | TxString("Aux3"); |
gke | 0:62a1c91a859a | 502 | break; |
gke | 0:62a1c91a859a | 503 | case '8': |
gke | 0:62a1c91a859a | 504 | TxString("Beeper"); |
gke | 0:62a1c91a859a | 505 | break; |
gke | 0:62a1c91a859a | 506 | } |
gke | 0:62a1c91a859a | 507 | TxNextLine(); |
gke | 0:62a1c91a859a | 508 | PowerOutput(ch-'1'); |
gke | 0:62a1c91a859a | 509 | ShowPrompt(); |
gke | 0:62a1c91a859a | 510 | break; |
gke | 0:62a1c91a859a | 511 | case 'T': |
gke | 0:62a1c91a859a | 512 | LEDsAndBuzzer(); |
gke | 0:62a1c91a859a | 513 | ShowPrompt(); |
gke | 0:62a1c91a859a | 514 | break; |
gke | 0:62a1c91a859a | 515 | |
gke | 0:62a1c91a859a | 516 | case 'V' : // Battery test |
gke | 0:62a1c91a859a | 517 | BatteryTest(); |
gke | 0:62a1c91a859a | 518 | ShowPrompt(); |
gke | 0:62a1c91a859a | 519 | break; |
gke | 0:62a1c91a859a | 520 | case '?' : // help |
gke | 0:62a1c91a859a | 521 | TxString(SerHelp); |
gke | 0:62a1c91a859a | 522 | ShowPrompt(); |
gke | 0:62a1c91a859a | 523 | break; |
gke | 0:62a1c91a859a | 524 | default: |
gke | 0:62a1c91a859a | 525 | break; |
gke | 0:62a1c91a859a | 526 | } |
gke | 0:62a1c91a859a | 527 | } |
gke | 0:62a1c91a859a | 528 | } |
gke | 0:62a1c91a859a | 529 | } // ProcessCommand |
gke | 0:62a1c91a859a | 530 |