Important changes to repositories hosted on mbed.com
Mbed hosted mercurial repositories are deprecated and are due to be permanently deleted in July 2026.
To keep a copy of this software download the repository Zip archive or clone locally using Mercurial.
It is also possible to export all your personal repositories from the account settings page.
UAVXArm.h
00001 00002 // Commissioning defines 00003 00004 //#define SERIAL_TELEMETRY GPSSerial // Select the one you want Steve 00005 #define SERIAL_TELEMETRY TelemetrySerial 00006 00007 #define MAX_PID_CYCLE_HZ 200 // PID cycle rate do not exceed 00008 #define PID_CYCLE_US (1000000/MAX_PID_CYCLE_HZ) 00009 00010 #define PWM_UPDATE_HZ 200 // reduced for Turnigys - I2C runs at PID loop rate always 00011 // MUST BE LESS THAN OR EQUAL TO 450HZ 00012 // LP filter cutoffs for sensors 00013 00014 //#define SUPPRESS_ROLL_PITCH_GYRO_FILTERS 00015 #define ROLL_PITCH_FREQ (0.5*PWM_UPDATE_HZ) // must be <= ITG3200 LP filter 00016 #define ATTITUDE_ANGLE_LIMIT QUARTERPI // set to PI for aerobatics 00017 #define GYRO_PROP_NOISE 0.1 // largely prop coupled 00018 00019 //#define SUPPRESS_ACC_FILTERS 00020 #define ACC_FREQ 5 // could be lower again? 00021 00022 //#define SUPPRESS_YAW_GYRO_FILTERS 00023 //#define USE_FIXED_YAW_FILTER // does not rescale LP cutoff with yaw stick 00024 #define MAX_YAW_FREQ 10.0 // <= 10Hz 00025 #define COMPASS_SANITY_CHECK_RAD_S TWOPI // changes greater than this rate ignored 00026 00027 // DCM Attitude Estimation 00028 00029 //#define DCM_YAW_COMP 00030 //#define USE_ANGLE_DERIVED_RATE // Gyros have periodic prop noise - define to use rate derived from angle 00031 00032 // The pitch/roll angle should track CLOSELY with the noise "mostly" tuned out. 00033 // Jitter in the artificial horizon gives part of the story but better to use the UAVXFC logs. 00034 00035 // Assumes normalised gravity vector 00036 #define TAU_S 5.0 // 1-10 00037 #define Kp_RollPitch 5.0 //(2.0/TAU_S) //1.0 // 5.0 00038 #define Ki_RollPitch 0.005//((1.0/TAU_S)*(1.0/TAU_S)) //0.001 // 0.005 00039 //#define Ki_RollPitch (1.0/(TAU_S*TAU_S)) ? 00040 #define Kp_Yaw 1.2 00041 #define Ki_Yaw 0.00002 00042 00043 /* 00044 Kp Ki KpYaw KiYaw 00045 Arducopter 0.0014 0.00002 1.0 0.00002 (200Hz) 00046 Arducopter 5.0 0.005 1.2 0.00002 00047 Ihlein 0.2 0.01 0.02 0.01 (50Hz) 00048 Premerlani 0.0755 0.00943 (50Hz) 00049 Bascom 0.02 0.00002 1.2 0.00002 00050 Matrixpilot 0.04 0.008 0.016 0.0005 00051 Superstable 0.0014 0.00000015 1.2 0.00005 (200Hz) 00052 00053 */ 00054 00055 //#define DISABLE_LED_DRIVER // disables the PCA driver and also the BUZZER 00056 00057 #define DISABLE_EXTRAS // suppress altitude hold, position hold and inertial compensation 00058 #define SUPPRESS_SDCARD //DO NOT RE-ENABLE - MOTOR INTERMITTENTS WILL OCCUR 00059 00060 //BMP occasional returns bad results - changes outside this rate are deemed sensor/buss errors 00061 #define BARO_SANITY_CHECK_MPS 10.0 // dm/S 20,40,60,80 or 100 00062 00063 #define SIX_DOF // effects acc and gyro addresses 00064 00065 #define BATTERY_VOLTS_SCALE 57.85 // 51.8144 // Volts scaling for internal divider 00066 00067 #define SW_I2C // define for software I2C 400KHz 00068 00069 //#define INC_ALL_SCHEMES // runs all attitude control schemes - use "custom" telemetry 00070 00071 #define I2C_MAX_RATE_HZ 400000 00072 00073 #define USING_MBED 00074 00075 // =============================================================================================== 00076 // = UAVXArm Quadrocopter Controller = 00077 // = Copyright (c) 2008 by Prof. Greg Egan = 00078 // = Original V3.15 Copyright (c) 2007 Ing. Wolfgang Mahringer = 00079 // = http://code.google.com/p/uavp-mods/ = 00080 // =============================================================================================== 00081 00082 // This is part of UAVXArm. 00083 00084 // UAVXArm is free software: you can redistribute it and/or modify it under the terms of the GNU 00085 // General Public License as published by the Free Software Foundation, either version 3 of the 00086 // License, or (at your option) any later version. 00087 00088 // UAVXArm is distributed in the hope that it will be useful,but WITHOUT ANY WARRANTY; without 00089 // even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. 00090 // See the GNU General Public License for more details. 00091 00092 // You should have received a copy of the GNU General Public License along with this program. 00093 // If not, see http://www.gnu.org/licenses/ 00094 00095 #include "mbed.h" 00096 #include "SDFileSystem.h" 00097 #include "SerialBuffered.h" // used in preference to MODSERIAL 00098 00099 // Additional Types 00100 typedef uint8_t uint8 ; 00101 typedef int8_t int8; 00102 typedef uint16_t uint16; 00103 typedef int16_t int16; 00104 typedef int32_t int24; 00105 typedef uint32_t uint24; 00106 typedef int32_t int32; 00107 typedef uint32_t uint32; 00108 typedef uint8_t boolean; 00109 typedef float real32; 00110 00111 extern Timer timer; 00112 00113 //________________________________________________________________________________________ 00114 00115 00116 // Useful Constants 00117 #define NUL 0 00118 #define SOH 1 00119 #define EOT 4 00120 #define ACK 6 00121 #define HT 9 00122 #define LF 10 00123 #define CR 13 00124 #define NAK 21 00125 #define ESC 27 00126 #define true 1 00127 #define false 0 00128 00129 #define PI 3.141592654 00130 #define THIRDPI (PI/3.0) 00131 #define HALFPI (PI*0.5) 00132 #define ONEANDHALFPI (PI * 1.5) 00133 #define QUARTERPI (PI*0.25) 00134 #define SIXTHPI (PI/6.0) 00135 #define TWOPI (PI*2.0) 00136 #define RADDEG (180.0/PI) 00137 #define MILLIANGLE (180000.0/PI) 00138 #define DEGRAD (PI/180.0) 00139 00140 #define MILLIRAD 18 00141 #define CENTIRAD 2 00142 00143 #define MAXINT32 0x7fffffff 00144 #define MAXINT16 0x7fff 00145 00146 //#define BATCHMODE 00147 00148 #ifndef BATCHMODE 00149 //#define RX6CH 00150 //#define EXPERIMENTAL 00151 //#define TESTING 00152 //#define RX6CH // 6ch Receivers 00153 //#define SIMULATE 00154 //#define VTCOPTER 00155 //#define Y6COPTER 00156 #define QUADROCOPTER 00157 //#define TRICOPTER 00158 //#define HELICOPTER 00159 //#define AILERON 00160 // #define ELEVON 00161 #endif // !BATCHMODE 00162 00163 //________________________________________________________________________________________________ 00164 00165 #define USE_PPM_FAILSAFE 00166 00167 // Airframe 00168 00169 #if ( defined TRICOPTER | defined QUADROCOPTER | defined VTCOPTER | defined Y6COPTER ) 00170 #define MULTICOPTER 00171 #endif 00172 00173 #if ( defined HELICOPTER | defined AILERON | defined ELEVON ) 00174 #if ( defined AILERON | defined ELEVON ) 00175 #define NAV_WING 00176 #endif 00177 #endif 00178 00179 #ifdef QUADROCOPTER 00180 #define AF_TYPE QuadAF 00181 #endif 00182 #ifdef TRICOPTER 00183 #define AF_TYPE TriAF 00184 #endif 00185 #ifdef VTCOPTER 00186 #define AF_TYPE VTAF 00187 #endif 00188 #ifdef Y6COPTER 00189 #define AF_TYPE Y6AF 00190 #endif 00191 #ifdef HELICOPTER 00192 #define AF_TYPE HeliAF 00193 #endif 00194 #ifdef ELEVON 00195 #define AF_TYPE ElevAF 00196 #endif 00197 #ifdef AILERON 00198 #define AF_TYPE AilAF 00199 #endif 00200 00201 #define GPS_INC_GROUNDSPEED // GPS groundspeed is not used for flight but may be of interest 00202 00203 // Timeouts and Update Intervals 00204 00205 #define FAILSAFE_TIMEOUT_MS 1000L // mS. hold last "good" settings and then restore flight or abort 00206 #define ABORT_TIMEOUT_GPS_MS 5000L // mS. go to descend on position hold if GPS valid. 00207 #define ABORT_TIMEOUT_NO_GPS_MS 0L // mS. go to descend on position hold if GPS valid. 00208 #define ABORT_UPDATE_MS 1000L // mS. retry period for RC Signal and restore Pilot in Control 00209 #define ARMED_TIMEOUT_MS 150000L // mS. automatic disarming if armed for this long and landed 00210 00211 #define ALT_DESCENT_UPDATE_MS 1000L // mS time between throttle reduction clicks in failsafe descent without baro 00212 00213 #define RC_STICK_MOVEMENT 5L // minimum to be recognised as a stick input change without triggering failsafe 00214 00215 #define THROTTLE_LOW_DELAY_MS 1000L // mS. that motor runs at idle after the throttle is closed 00216 #define THROTTLE_UPDATE_MS 3000L // mS. constant throttle time for altitude hold 00217 00218 #define NAV_ACTIVE_DELAY_MS 10000L // mS. after throttle exceeds idle that Nav becomes active 00219 #define NAV_RTH_LAND_TIMEOUT_MS 10000L // mS. Shutdown throttle if descent lasts too long 00220 00221 #define UAVX_TEL_INTERVAL_MS 125L // mS. emit an interleaved telemetry packet 00222 #define ARDU_TEL_INTERVAL_MS 200L // mS. Ardustation 00223 #define UAVX_CONTROL_TEL_INTERVAL_MS 100L // mS. flight control only 00224 #define CUSTOM_TEL_INTERVAL_MS 125L // mS. 00225 #define FAST_CUSTOM_TEL_INTERVAL_MS 5L // mS. 00226 #define UAVX_MIN_TEL_INTERVAL_MS 1000L // mS. emit minimum FPV telemetry packet slow rate for example to FrSky 00227 00228 #define GPS_TIMEOUT_MS 2000L // mS. 00229 00230 #define ALT_UPDATE_HZ 20L // Hz based on 50mS update time for Baro 00231 00232 #ifdef MULTICOPTER 00233 //#define PWM_UPDATE_HZ 450L // PWM motor update rate must be <450 and >100 00234 #else 00235 #define PWM_UPDATE_HZ 40L // standard RC servo update rate 00236 #endif // MULTICOPTER 00237 00238 // Accelerometers 00239 00240 #define DAMP_HORIZ_LIMIT 3L // equivalent stick units - no larger than 5 00241 #define DAMP_VERT_LIMIT_LOW -5L // maximum throttle reduction 00242 #define DAMP_VERT_LIMIT_HIGH 20L // maximum throttle increase 00243 00244 // Gyros 00245 00246 #define ATTITUDE_FF_DIFF (24.0/16.0) // 0 - 32 max feedforward speeds up roll/pitch recovery on fast stick change 00247 00248 #define ATTITUDE_ENABLE_DECAY // enables decay to zero angle when roll/pitch is not in fact zero! 00249 // unfortunately there seems to be a leak which cause the roll/pitch 00250 // to increase without the decay. 00251 00252 #define ATTITUDE_SCALE 0.008 // scaling of stick units for attitude angle control 00253 00254 // Enable "Dynamic mass" compensation Roll and/or Pitch 00255 // Normally disabled for pitch only 00256 //#define ENABLE_DYNAMIC_MASS_COMP_ROLL 00257 //#define ENABLE_DYNAMIC_MASS_COMP_PITCH 00258 00259 // Altitude Hold 00260 00261 #define ALT_HOLD_MAX_ROC_MPS 0.5 // Must be changing altitude at less than this for alt. hold to be detected 00262 00263 // the range within which throttle adjustment is proportional to altitude error 00264 #define ALT_BAND_M 5.0 // Metres 00265 00266 #define LAND_M 3.0 // Metres deemed to have landed when below this height 00267 00268 #define ALT_MAX_THR_COMP 40L // Stick units was 32 00269 00270 #define ALT_INT_WINDUP_LIMIT 16L 00271 00272 #define ALT_RF_ENABLE_M 5.0 // altitude below which the rangefiner is selected as the altitude source 00273 #define ALT_RF_DISABLE_M 6.0 // altitude above which the rangefiner is deselected as the altitude source 00274 00275 // Navigation 00276 00277 #define NAV_ACQUIRE_BEEPER 00278 00279 //#define ATTITUDE_NO_LIMITS // full stick range is available otherwise it is scaled to Nav sensitivity 00280 00281 #define NAV_RTH_LOCKOUT ((10.0*PI)/180.0) // first number is degrees 00282 00283 #define NAV_MAX_ROLL_PITCH 25L // Rx stick units 00284 #define NAV_CONTROL_HEADROOM 10L // at least this much stick control headroom above Nav control 00285 #define NAV_DIFF_LIMIT 24L // Approx double NAV_INT_LIMIT 00286 #define NAV_INT_WINDUP_LIMIT 64L // ??? 00287 00288 #define NAV_ENFORCE_ALTITUDE_CEILING // limit all autonomous altitudes 00289 #define NAV_CEILING 120L // 400 feet 00290 #define NAV_MAX_NEUTRAL_RADIUS 3L // Metres also minimum closing radius 00291 #define NAV_MAX_RADIUS 99L // Metres 00292 00293 #ifdef NAV_WING 00294 #define NAV_PROXIMITY_RADIUS 20.0 // Metres if there are no WPs 00295 #define NAV_PROXIMITY_ALTITUDE 5.0 // Metres 00296 #else 00297 #define NAV_PROXIMITY_RADIUS 5.0 // Metres if there are no WPs 00298 #define NAV_PROXIMITY_ALTITUDE 3.0 // Metres 00299 #endif // NAV_WING 00300 00301 // reads $GPGGA sentence - all others discarded 00302 00303 #define GPS_MIN_SATELLITES 6 // preferably > 5 for 3D fix 00304 #define GPS_MIN_FIX 1 // must be 1 or 2 00305 #define GPS_ORIGIN_SENTENCES 30L // Number of sentences needed to obtain reasonable Origin 00306 #define GPS_MIN_HDILUTE 130L // HDilute * 100 00307 00308 #define NAV_SENS_THRESHOLD 40L // Navigation disabled if Ch7 is less than this 00309 #define NAV_SENS_ALTHOLD_THRESHOLD 20L // Altitude hold disabled if Ch7 is less than this 00310 #define NAV_SENS_6CH 80L // Low GPS gain for 6ch Rx 00311 00312 #define NAV_YAW_LIMIT 10L // yaw slew rate for RTH 00313 #define NAV_MAX_TRIM 20L // max trim offset for altitude hold 00314 #define NAV_CORR_SLEW_LIMIT 1L // *5L maximum change in roll or pitch correction per GPS update 00315 00316 #define ATTITUDE_HOLD_LIMIT 8L // dead zone for roll/pitch stick for position hold 00317 #define ATTITUDE_HOLD_RESET_INTERVAL 25L // number of impulse cycles before GPS position is re-acquired 00318 00319 //#define NAV_PPM_FAILSAFE_RTH // PPM signal failure causes RTH with Signal sampled periodically 00320 00321 // Throttle 00322 00323 #define THROTTLE_MAX_CURRENT 40L // Amps total current at full throttle for estimated mAH 00324 #define CURRENT_SENSOR_MAX 50L // Amps range of current sensor - used for estimated consumption - no actual sensor yet. 00325 #define THROTTLE_CURRENT_SCALE ((THROTTLE_MAX_CURRENT * 1024L)/(200L * CURRENT_SENSOR_MAX )) 00326 00327 #define THROTTLE_SLEW_LIMIT 0 // limits the rate at which the throttle can change (=0 no slew limit, 5 OK) 00328 #define THROTTLE_MIDDLE 10 // throttle stick dead zone for baro 00329 #define THROTTLE_MIN_ALT_HOLD 75 // min throttle stick for altitude lock 00330 00331 typedef union { 00332 int16 i16; 00333 uint16 u16; 00334 struct { 00335 uint8 b0; 00336 uint8 b1; 00337 }; 00338 struct { 00339 int8 pad; 00340 int8 i1; 00341 }; 00342 } i16u; 00343 00344 typedef union { 00345 int24 i24; 00346 uint24 u24; 00347 struct { 00348 uint8 b0; 00349 uint8 b1; 00350 uint8 b2; 00351 }; 00352 struct { 00353 uint8 pad; 00354 int16 i2_1; 00355 }; 00356 } i24u; 00357 00358 typedef union { 00359 int32 i32; 00360 uint32 u32; 00361 struct { 00362 uint8 b0; 00363 uint8 b1; 00364 uint8 b2; 00365 uint8 b3; 00366 }; 00367 struct { 00368 uint16 w0; 00369 uint16 w1; 00370 }; 00371 struct { 00372 int16 pad; 00373 int16 iw1; 00374 }; 00375 00376 struct { 00377 uint8 padding; 00378 int24 i3_1; 00379 }; 00380 } i32u; 00381 00382 #define TX_BUFF_MASK 511 00383 #define RX_BUFF_MASK 511 00384 00385 typedef struct { // PPM 00386 uint8 Head; 00387 int16 B[4][8]; 00388 } int16x8x4Q; 00389 00390 typedef struct { // Baro 00391 uint8 Head, Tail; 00392 int24 B[8]; 00393 } int24x8Q; 00394 00395 typedef struct { // GPS 00396 uint8 Head, Tail; 00397 int32 Lat[4], Lon[4]; 00398 } int32x4Q; 00399 00400 // Macros 00401 00402 #define Sign(i) (((i)<0) ? -1 : 1) 00403 00404 #define Max(i,j) ((i<j) ? j : i) 00405 #define Min(i,j) ((i<j) ? i : j ) 00406 #define Decay1(i) (((i) < 0) ? (i+1) : (((i) > 0) ? (i-1) : 0)) 00407 #define Limit(i,l,u) (((i) < l) ? l : (((i) > u) ? u : (i))) 00408 #define Limit1(i,l) (((i) < -(l)) ? -(l) : (((i) > (l)) ? (l) : (i))) 00409 #define Sqr(v) ( v * v ) 00410 00411 // To speed up NMEA sentence processing 00412 // must have a positive argument 00413 #define ConvertDDegToMPi(d) (((int32)d * 3574L)>>11) 00414 #define ConvertMPiToDDeg(d) (((int32)d * 2048L)/3574L) 00415 00416 #define ToPercent(n, m) (((n)*100L)/m) 00417 00418 // Simple filters using weighted averaging 00419 #define VerySoftFilter(O,N) (SRS16((O)+(N)*3, 2)) 00420 #define SoftFilter(O,N) (SRS16((O)+(N), 1)) 00421 #define MediumFilter(O,N) (SRS16((O)*3+(N), 2)) 00422 #define HardFilter(O,N) (SRS16((O)*7+(N), 3)) 00423 00424 // Unsigned 00425 #define VerySoftFilterU(O,N) (((O)+(N)*3+2)>>2) 00426 #define SoftFilterU(O,N) (((O)+(N)+1)>>1) 00427 #define MediumFilterU(O,N) (((O)*3+(N)+2)>>2) 00428 #define HardFilterU(O,N) (((O)*7+(N)+4)>>3) 00429 00430 #define NoFilter(O,N) (N) 00431 00432 #define DisableInterrupts (INTCONbits.GIEH=0) 00433 #define EnableInterrupts (INTCONbits.GIEH=1) 00434 #define InterruptsEnabled (INTCONbits.GIEH) 00435 00436 // PARAMS 00437 00438 #define PARAMS_ADDR_PX 0 // code assumes zero! 00439 #define MAX_PARAMETERS 64 // parameters in PXPROM start at zero 00440 00441 #define STATS_ADDR_PX ( PARAMS_ADDR_PX + (MAX_PARAMETERS *2) ) 00442 #define MAX_STATS 32 // 64 bytes 00443 00444 // uses second Page of PXPROM 00445 #define NAV_ADDR_PX 256L 00446 // 0 - 8 not used 00447 00448 #define NAV_NO_WP (NAV_ADDR_PX + 9) 00449 #define NAV_PROX_ALT (NAV_ADDR_PX + 10) 00450 #define NAV_PROX_RADIUS (NAV_ADDR_PX + 11) 00451 #define NAV_ORIGIN_ALT (NAV_ADDR_PX + 12) 00452 #define NAV_ORIGIN_LAT (NAV_ADDR_PX + 14) 00453 #define NAV_ORIGIN_LON (NAV_ADDR_PX + 18) 00454 #define NAV_RTH_ALT_HOLD (NAV_ADDR_PX + 22) // P[NavRTHAlt] 00455 #define NAV_WP_START (NAV_ADDR_PX + 24) 00456 00457 #define WAYPOINT_REC_SIZE (4 + 4 + 2 + 1) // Lat + Lon + Alt + Loiter 00458 #define NAV_MAX_WAYPOINTS ((256 - 24 - 1)/WAYPOINT_REC_SIZE) 00459 00460 //______________________________________________________________________________________________ 00461 00462 // main.c 00463 00464 enum Directions {BF, LR, UD, Alt }; // x forward, y left and z down 00465 enum Angles { Roll, Pitch, Yaw }; // X, Y, Z 00466 00467 #define FLAG_BYTES 10 00468 #define TELEMETRY_FLAG_BYTES 6 00469 typedef union { 00470 uint8 AllFlags[FLAG_BYTES]; 00471 struct { // Order of these flags subject to change 00472 uint8 00473 AltHoldEnabled: 00474 1, 00475 AllowTurnToWP: 00476 1, // stick programmed 00477 GyroFailure: 00478 1, 00479 LostModel: 00480 1, 00481 NearLevel: 00482 1, 00483 LowBatt: 00484 1, 00485 GPSValid: 00486 1, 00487 NavValid: 00488 1, 00489 00490 BaroFailure: 00491 1, 00492 AccFailure: 00493 1, 00494 CompassFailure: 00495 1, 00496 GPSFailure: 00497 1, 00498 AttitudeHold: 00499 1, 00500 ThrottleMoving: 00501 1, 00502 HoldingAlt: 00503 1, 00504 Navigate: 00505 1, 00506 00507 ReturnHome: 00508 1, 00509 WayPointAchieved: 00510 1, 00511 WayPointCentred: 00512 1, 00513 UnusedGPSAlt: // was UsingGPSAlt: 00514 1, 00515 UsingRTHAutoDescend: 00516 1, 00517 BaroAltitudeValid: 00518 1, 00519 RangefinderAltitudeValid: 00520 1, 00521 UsingRangefinderAlt: 00522 1, 00523 00524 // internal flags not really useful externally 00525 00526 AllowNavAltitudeHold: 00527 1, // stick programmed 00528 UsingPositionHoldLock: 00529 1, 00530 Ch5Active: 00531 1, 00532 Simulation: 00533 1, 00534 AcquireNewPosition: 00535 1, 00536 MotorsArmed: 00537 1, 00538 NavigationActive: 00539 1, 00540 ForceFailsafe: 00541 1, 00542 00543 Signal: 00544 1, 00545 RCFrameOK: 00546 1, 00547 ParametersValid: 00548 1, 00549 RCNewValues: 00550 1, 00551 NewCommands: 00552 1, 00553 AccelerationsValid: 00554 1, 00555 CompassValid: 00556 1, 00557 CompassMissRead: 00558 1, 00559 00560 UsingPolarCoordinates: 00561 1, 00562 UsingAngleControl: 00563 1, 00564 GPSPacketReceived: 00565 1, 00566 NavComputed: 00567 1, 00568 AltitudeValid: 00569 1, 00570 UsingSerialPPM: 00571 1, 00572 UsingTxMode2: 00573 1, 00574 UsingAltOrientation: 00575 1, 00576 00577 // outside telemetry flags 00578 00579 UsingTelemetry: 00580 1, 00581 TxToBuffer: 00582 1, 00583 NewBaroValue: 00584 1, 00585 BeeperInUse: 00586 1, 00587 RFInInches: 00588 1, 00589 FirstArmed: 00590 00591 1, 00592 HaveGPRMC: 00593 1, 00594 UsingPolar: 00595 1, 00596 RTCValid: 00597 1, 00598 SDCardValid: 00599 1, 00600 PXImageStale: 00601 1, 00602 UsingLEDDriver: 00603 1, 00604 Using9DOF: 00605 1, 00606 HaveBatterySensor: 00607 1, 00608 AccMagnitudeOK: 00609 1; 00610 }; 00611 } Flags; 00612 00613 enum FlightStates { Starting, Landing, Landed, Shutdown, InFlight}; 00614 extern volatile Flags F; 00615 extern int8 State; 00616 extern int8 r; 00617 00618 //______________________________________________________________________________________________ 00619 00620 // accel.c 00621 00622 enum AccelerometerTypes { LISLAcc, ADXL345Acc, AccUnknown }; 00623 00624 extern void ShowAccType(void); 00625 extern void ReadAccelerometers(void); 00626 extern void GetNeutralAccelerations(void); 00627 extern void GetAccelerations(void); 00628 extern void AccelerometerTest(void); 00629 extern void InitAccelerometers(void); 00630 00631 // ADXL345 3-Axis Accelerometer 00632 00633 #ifdef SIX_DOF 00634 #define ADXL345_ID 0xA6 00635 #else 00636 #define ADXL345_ID 0x53 00637 #endif // 6DOF 00638 00639 #define ADXL345_WR ADXL345_ID 00640 #define ADXL345_RD (ADXL345_ID+1) 00641 00642 extern void ReadADXL345Acc(void); 00643 extern void InitADXL345Acc(void); 00644 extern boolean ADXL345AccActive(void); 00645 00646 // LIS3LV02DG 3-Axis Accelerometer 400KHz 00647 00648 #define LISL_WHOAMI 0x0f 00649 #define LISL_OFFSET_X 0x16 00650 #define LISL_OFFSET_Y 0x17 00651 #define LISL_OFFSET_Z 0x18 00652 #define LISL_GAIN_X 0x19 00653 #define LISL_GAIN_Y 0x1A 00654 #define LISL_GAIN_Z 0x1B 00655 #define LISL_CTRLREG_1 0x20 00656 #define LISL_CTRLREG_2 0x21 00657 #define LISL_CTRLREG_3 0x22 00658 #define LISL_STATUS 0x27 00659 #define LISL_OUTX_L 0x28 00660 #define LISL_OUTX_H 0x29 00661 #define LISL_OUTY_L 0x2A 00662 #define LISL_OUTY_H 0x2B 00663 #define LISL_OUTZ_L 0x2C 00664 #define LISL_OUTZ_H 0x2D 00665 #define LISL_FF_CFG 0x30 00666 #define LISL_FF_SRC 0x31 00667 #define LISL_FF_ACK 0x32 00668 #define LISL_FF_THS_L 0x34 00669 #define LISL_FF_THS_H 0x35 00670 #define LISL_FF_DUR 0x36 00671 #define LISL_DD_CFG 0x38 00672 #define LISL_INCR_ADDR 0x40 00673 #define LISL_READ 0x80 00674 #define LISL_ID 0x3a 00675 00676 #define LISL_WR LISL_ID 00677 #define LISL_RD (LISL_ID+1) 00678 00679 extern boolean WriteLISL(uint8, uint8); 00680 extern void ReadLISLAcc(void); 00681 extern void InitLISLAcc(void); 00682 extern boolean LISLAccActive(void); 00683 00684 // other accelerometers 00685 00686 extern real32 Vel[3], AccADC[3], AccNoise[3], Acc[3], AccNeutral[3], Accp[3]; 00687 extern int16 NewAccNeutral[3]; 00688 extern uint8 AccelerometerType; 00689 extern real32 GravityR; // recip gravity scaling 00690 00691 //______________________________________________________________________________________________ 00692 00693 // analog.c 00694 00695 extern real32 ADC(uint8); 00696 extern void GetBattery(void); 00697 extern void BatteryTest(void); 00698 extern void InitBattery(void); 00699 00700 extern void GetRangefinderAltitude(void); 00701 extern void InitRangefinder(void); 00702 00703 extern real32 BatteryVolts, BatteryCurrentADCEstimated, BatteryChargeUsedAH; 00704 extern real32 BatteryCharge, BatteryCurrent; 00705 extern real32 BatteryVoltsScale; 00706 00707 extern real32 RangefinderAltitude; 00708 00709 //______________________________________________________________________________________________ 00710 00711 // attitude.c 00712 00713 enum AttitudeMethods { Integrator, Wolferl, Complementary, Kalman, PremerlaniDCM, MadgwickIMU, 00714 MadgwickIMU2, MadgwickAHRS, MultiWii, MaxAttitudeScheme}; 00715 00716 extern void AdaptiveYawLPFreq(void); 00717 extern void GetAttitude(void); 00718 extern void DoLegacyYawComp(uint8); 00719 extern void NormaliseAccelerations(void); 00720 extern void AttitudeTest(void); 00721 extern void InitAttitude(void); 00722 00723 extern real32 dT, dTOn2, dTR, dTmS; 00724 extern real32 YawFilterLPFreq; 00725 extern uint32 PrevDCMUpdate; 00726 extern uint8 AttitudeMethod; 00727 00728 extern real32 EstAngle[3][MaxAttitudeScheme]; 00729 extern real32 EstRate[3][MaxAttitudeScheme]; 00730 00731 extern real32 HE; 00732 00733 // SimpleIntegrator 00734 00735 extern void DoIntegrator(void); 00736 00737 // Wolferl 00738 00739 extern real32 Correction[2]; 00740 00741 extern void DoWolferl(void); 00742 00743 // DCM Premerlani 00744 00745 extern void DCMNormalise(void); 00746 extern void DCMDriftCorrection(void); 00747 extern void AccAdjust(void); 00748 extern void DCMMotionCompensation(void); 00749 extern void DCMUpdate(void); 00750 extern void DCMEulerAngles(void); 00751 extern void DoDCM(void); 00752 00753 extern real32 RollPitchError[3]; 00754 extern real32 AccV[3]; 00755 extern real32 GyroV[3]; 00756 extern real32 OmegaV[3]; 00757 extern real32 OmegaP[3]; 00758 extern real32 OmegaI[3]; 00759 extern real32 Omega[3]; 00760 extern real32 DCM[3][3]; 00761 extern real32 U[3][3]; 00762 extern real32 TempM[3][3]; 00763 00764 // IMU & AHRS S.O.H. Madgwick 00765 00766 extern void DoMadgwickIMU(real32, real32, real32, real32, real32, real32); 00767 extern void DoMadgwickIMU2(real32, real32, real32, real32, real32, real32); 00768 extern void DoMadgwickAHRS(real32, real32, real32, real32, real32, real32, real32, real32, real32); 00769 extern void MadgwickEulerAngles(uint8); 00770 00771 extern real32 q0, q1, q2, q3; // quaternion elements representing the estimated orientation 00772 00773 // Kalman 00774 extern void DoKalman(void); 00775 00776 // Complementary 00777 extern void DoCF(void); 00778 00779 // MultiWii 00780 extern void DoMultiWii(); 00781 00782 //______________________________________________________________________________________________ 00783 00784 // autonomous.c 00785 00786 extern void DoShutdown(void); 00787 extern void FailsafeHoldPosition(void); 00788 extern void DoPolarOrientation(void); 00789 extern void Navigate(int32, int32); 00790 extern void SetDesiredAltitude(int16); 00791 extern void DoFailsafeLanding(void); 00792 extern void AcquireHoldPosition(void); 00793 extern void DoNavigation(void); 00794 extern void FakeFlight(void); 00795 extern void DoPPMFailsafe(void); 00796 extern void WriteWayPointPX(uint8, int32, int32, int16, uint8); 00797 extern void UAVXNavCommand(void); 00798 extern void GetWayPointPX(int8); 00799 extern void InitNavigation(void); 00800 00801 typedef struct { 00802 int32 E, N; 00803 int16 A; 00804 uint8 L; 00805 } WayPoint; 00806 00807 enum NavStates { HoldingStation, ReturningHome, AtHome, Descending, Touchdown, Navigating, Loitering}; 00808 enum FailStates { MonitoringRx, Aborting, Terminating, Terminated }; 00809 00810 extern real32 NavCorr[3], NavCorrp[3]; 00811 extern real32 NavE[3], NavEp[3], NavIntE[3]; 00812 extern int16 NavYCorrLimit; 00813 00814 extern int8 FailState; 00815 extern WayPoint WP; 00816 extern int8 CurrWP; 00817 extern int8 NoOfWayPoints; 00818 extern int16 WPAltitude; 00819 extern int32 WPLatitude, WPLongitude; 00820 00821 extern real32 WayHeading; 00822 extern real32 NavPolarRadius, NavNeutralRadius, NavProximityRadius, NavProximityAltitude; 00823 00824 extern int24 NavRTHTimeoutmS; 00825 extern int8 NavState; 00826 extern int16 NavSensitivity, RollPitchMax; 00827 extern int16 AltSum; 00828 00829 extern int16 EffNavSensitivity; 00830 extern int16 EastP, EastDiffSum, EastI, EastCorr, NorthP, NorthDiffSum, NorthI, NorthCorr; 00831 extern int24 EastD, EastDiffP, NorthD, NorthDiffP; 00832 00833 //______________________________________________________________________________________________ 00834 00835 // baro.c 00836 00837 #define BARO_INIT_RETRIES 10 // max number of initialisation retries 00838 00839 enum BaroTypes { BaroBMP085, BaroSMD500, BaroMPX4115, BaroUnknown }; 00840 00841 #define ADS7823_TIME_MS 50 // 20Hz 00842 #define ADS7823_MAX 4095 // 12 bits 00843 #define ADS7823_ID 0x90 // ADS7823 ADC 00844 #define ADS7823_WR ADS7823_ID // ADS7823 ADC 00845 #define ADS7823_RD (ADS7823_ID+1) // ADS7823 ADC 00846 #define ADS7823_CMD 0x00 00847 00848 extern uint8 MCP4725_ID_Actual; 00849 00850 #define MCP4725_MAX 4095 // 12 bits 00851 #define MCP4725_ID_0xC8 0xc8 00852 #define MCP4725_ID_0xCC 0xcc 00853 #define MCP4725_CMD 0x40 // write to DAC registor in next 2 bytes 00854 #define MCP4725_EPROM 0x60 // write to DAC registor and eprom 00855 00856 extern void SetFreescaleMCP4725(int16); 00857 extern void SetFreescaleOffset(void); 00858 extern void ReadFreescaleBaro(void); 00859 extern real32 FreescaleToDM(int24); 00860 extern void GetFreescaleBaroAltitude(void); 00861 extern boolean IsFreescaleBaroActive(void); 00862 extern boolean IdentifyMCP4725(void); 00863 extern void InitFreescaleBarometer(void); 00864 00865 #define BOSCH_ID_BMP085 0x55 00866 #define BOSCH_ID 0xee 00867 #define BOSCH_WR BOSCH_ID_BMP085 00868 #define BOSCH_RD (BOSCH_ID_BMP085+1) 00869 #define BOSCH_TEMP_BMP085 0x2e 00870 #define BOSCH_TEMP_SMD500 0x6e 00871 #define BOSCH_PRESS 0xf4 00872 #define BOSCH_CTL 0xf4 // OSRS=3 for BMP085 25.5mS, SMD500 34mS 00873 #define BOSCH_ADC_MSB 0xf6 00874 #define BOSCH_ADC_LSB 0xf7 00875 #define BOSCH_ADC_XLSB 0xf8 // BMP085 00876 #define BOSCH_TYPE 0xd0 00877 00878 extern void StartBoschBaroADC(boolean); 00879 extern void ReadBoschBaro(void); 00880 extern int24 CompensatedBoschPressure(uint16, uint16); 00881 extern void GetBoschBaroAltitude(void); 00882 extern boolean IsBoschBaroActive(void); 00883 extern void InitBoschBarometer(void); 00884 00885 extern void GetBaroAltitude(void); 00886 extern void InitBarometer(void); 00887 00888 extern void ShowBaroType(void); 00889 extern void BaroTest(void); 00890 00891 extern int32 OriginBaroPressure, CompBaroPressure; 00892 extern uint16 BaroPressure, BaroTemperature; 00893 extern boolean AcquiringPressure; 00894 extern real32 BaroRelAltitude, BaroRelAltitudeP; 00895 extern i16u BaroVal; 00896 extern int8 BaroType; 00897 extern int16 AltitudeUpdateRate; 00898 extern int8 BaroRetries; 00899 00900 extern real32 FakeBaroRelAltitude; 00901 00902 //______________________________________________________________________________________________ 00903 00904 // compass.c 00905 00906 enum CompassTypes { HMC5843, HMC6352, NoCompass }; 00907 00908 //#define SUPPRESS_COMPASS_FILTER 00909 00910 extern real32 AdaptiveCompassFreq(void); 00911 extern void ReadCompass(void); 00912 extern void GetHeading(void); 00913 extern real32 MinimumTurn(real32); 00914 extern void ShowCompassType(void); 00915 extern void DoCompassTest(void); 00916 extern void CalibrateCompass(void); 00917 extern void InitCompass(void); 00918 00919 // HMC5843 Compass 00920 00921 #define HMC5843_DR 6 // 50Hz 00922 #define HMC5843_UPDATE_S 0.02 00923 00924 //#define HMC5843_DR 5 // 20Hz 00925 //#define HMC5843_UPDATE_S 0.05 00926 00927 #define HMC5843_ID 0x3C // 0x1E 9DOF 00928 #define HMC5843_WR HMC5843_ID 00929 #define HMC5843_RD (HMC5843_ID+1) 00930 00931 extern void ReadHMC5843(void); 00932 extern void GetHMC5843Parameters(void); 00933 extern void DoHMC5843Test(void); 00934 extern void CalibrateHMC5843(void); 00935 extern void InitHMC5843(void); 00936 extern boolean IsHMC5843Active(void); 00937 00938 // HMC6352 00939 00940 #define HMC6352_UPDATE_S 0.05 // 20Hz 00941 00942 #define HMC6352_ID 0x42 00943 #define HMC6352_WR HMC6352_ID 00944 #define HMC6352_RD (HMC6352_ID+1) 00945 00946 extern void ReadHMC6352(void); 00947 extern uint8 WriteByteHMC6352(uint8); 00948 extern void GetHMC6352Parameters(void); 00949 extern void DoHMC6352Test(void); 00950 extern void CalibrateHMC6352(void); 00951 extern void InitHMC6352(void); 00952 extern boolean HMC6352Active(void); 00953 00954 typedef struct { 00955 real32 V; 00956 real32 Offset; 00957 } MagStruct; 00958 extern MagStruct Mag[3]; 00959 extern real32 MagDeviation, CompassOffset; 00960 extern real32 MagHeading, Heading, HeadingP, FakeHeading; 00961 extern real32 CompassMaxSlew; 00962 extern real32 HeadingSin, HeadingCos; 00963 extern uint8 CompassType; 00964 00965 //______________________________________________________________________________________________ 00966 00967 // control.c 00968 00969 extern void DoAltitudeHold(void); 00970 extern void UpdateAltitudeSource(void); 00971 extern real32 AltitudeCF( real32, real32); 00972 extern void AltitudeHold(void); 00973 00974 extern void LimitYawSum(void); 00975 extern void InertialDamping(void); 00976 extern void DoOrientationTransform(void); 00977 extern void DoControl(void); 00978 00979 extern void LightsAndSirens(void); 00980 extern void InitControl(void); 00981 00982 extern real32 Angle[3], Anglep[3], Rate[3], Ratep[3], YawRateEp; 00983 extern real32 AccAltComp, AltComp; 00984 extern real32 DescentComp; 00985 extern real32 Rl, Pl, Yl, Ylp; 00986 extern real32 GS; 00987 00988 extern int16 HoldYaw, YawSlewLimit; 00989 extern int16 CruiseThrottle, MaxCruiseThrottle, DesiredThrottle, IdleThrottle, InitialThrottle, StickThrottle; 00990 extern int16 DesiredRoll, DesiredPitch, DesiredYaw, DesiredCamPitchTrim; 00991 extern real32 DesiredHeading; 00992 extern real32 ControlRoll, ControlPitch, ControlRollP, ControlPitchP; 00993 extern real32 CameraRollAngle, CameraPitchAngle; 00994 extern int16 CurrMaxRollPitch; 00995 extern int16 Trim[3]; 00996 00997 extern real32 GRollKp, GRollKi, GRollKd, GPitchKp, GPitchKi, GPitchKd; 00998 00999 extern int16 AttitudeHoldResetCount; 01000 extern real32 AltDiffSum, AltD, AltDSum; 01001 extern real32 DesiredAltitude, Altitude, AltitudeP; 01002 extern real32 ROC; 01003 extern boolean FirstPass; 01004 01005 extern uint32 AltuSp; 01006 extern uint32 ControlUpdateTimeuS; 01007 extern int16 DescentLimiter; 01008 01009 extern int16 FakeDesiredPitch, FakeDesiredRoll, FakeDesiredYaw; 01010 01011 //______________________________________________________________________________________________ 01012 01013 // gps.c 01014 01015 extern void UpdateField(void); 01016 extern int32 ConvertGPSToM(int32); 01017 extern int32 ConvertMToGPS(int32); 01018 extern int24 ConvertInt(uint8, uint8); 01019 extern real32 ConvertReal(uint8, uint8); 01020 extern int32 ConvertLatLonM(uint8, uint8); 01021 extern void ConvertUTime(uint8, uint8); 01022 extern void ConvertUDate(uint8, uint8); 01023 extern void ParseGPGGASentence(void); 01024 extern void ParseGPRMCSentence(void); 01025 extern void SetGPSOrigin(void); 01026 extern void ParseGPSSentence(void); 01027 extern void RxGPSPacket(uint8); 01028 extern void SetGPSOrigin(void); 01029 extern void DoGPS(void); 01030 extern void GPSTest(void); 01031 extern void UpdateGPS(void); 01032 extern void InitGPS(void); 01033 01034 #define MAXTAGINDEX 4 01035 #define GPSRXBUFFLENGTH 80 01036 typedef struct { 01037 uint8 s[GPSRXBUFFLENGTH]; 01038 uint8 length; 01039 } NMEAStruct; 01040 01041 #define MAX_NMEA_SENTENCES 2 01042 #define NMEA_TAG_INDEX 4 01043 01044 enum GPSPackeType { GPGGAPacketTag, GPRMCPacketTag, GPSUnknownPacketTag }; 01045 extern NMEAStruct NMEA; 01046 extern const uint8 NMEATags[MAX_NMEA_SENTENCES][5]; 01047 01048 extern uint8 GPSPacketTag; 01049 extern tm GPSTime; 01050 extern int32 GPSStartTime, GPSSeconds; 01051 extern int32 GPSLatitude, GPSLongitude; 01052 extern int32 OriginLatitude, OriginLongitude; 01053 extern real32 GPSAltitude, GPSRelAltitude, GPSOriginAltitude; 01054 extern int32 DesiredLatitude, DesiredLongitude; 01055 extern int32 LatitudeP, LongitudeP, HoldLatitude, HoldLongitude; 01056 extern real32 GPSLongitudeCorrection; 01057 extern real32 GPSHeading, GPSMagHeading, GPSMagDeviation, GPSVel, GPSVelp, GPSROC; 01058 extern int8 GPSNoOfSats; 01059 extern int8 GPSFix; 01060 extern int16 GPSHDilute; 01061 01062 extern real32 GPSdT, GPSdTR; 01063 extern uint32 GPSuSp; 01064 01065 extern int32 FakeGPSLongitude, FakeGPSLatitude; 01066 01067 extern uint8 ll, tt, ss, RxCh; 01068 extern uint8 GPSCheckSumChar, GPSTxCheckSum; 01069 01070 //______________________________________________________________________________________________ 01071 01072 // gyro.c 01073 01074 enum GyroTypes { MLX90609Gyro, ADXRS150Gyro, IDG300Gyro, LY530Gyro, ADXRS300Gyro, ITG3200Gyro, 01075 IRSensors, UnknownGyro 01076 }; 01077 01078 extern void ReadGyros(void); 01079 extern void GetGyroRates(void); 01080 extern void CheckGyroFault(uint8, uint8, uint8); 01081 extern void ErectGyros(void); 01082 extern void GyroTest(void); 01083 extern void InitGyros(void); 01084 extern void ShowGyroType(void); 01085 01086 // Generic Analog Gyrso 01087 extern void ReadAnalogGyros(void); 01088 extern void InitAnalogGyros(void); 01089 extern void CheckAnalogGyroFault(uint8, uint8, uint8); 01090 extern void AnalogGyroTest(void); 01091 01092 // ITG3200 3 Axis Gyro 01093 01094 #define ITG3200_WHO 0x00 01095 #define ITG3200_SMPL 0x15 01096 #define ITG3200_DLPF 0x16 01097 #define ITG3200_INT_C 0x17 01098 #define ITG3200_TMP_H 0x18 01099 #define ITG3200_TMP_L 0x1C 01100 #define ITG3200_GX_H 0x1D 01101 #define ITG3200_GX_L 0x1E 01102 #define ITG3200_GY_H 0x1F 01103 #define ITG3200_GY_L 0x20 01104 #define ITG3200_GZ_H 0x21 01105 #define ITG3200_GZ_L 0x22 01106 #define ITG3200_PWR_M 0x3E 01107 01108 #ifdef SIX_DOF 01109 #define ITG3200_ID 0xD0 01110 #else 01111 #define ITG3200_ID 0xD2 01112 #endif // 6DOF 01113 01114 #define ITG3200_WR ITG3200_ID 01115 #define ITG3200_RD (ITG3200_ID+1) 01116 01117 extern void ReadITG3200Gyro(void); 01118 extern uint8 ReadByteITG3200(uint8); 01119 extern boolean WriteByteITG3200(uint8, uint8); 01120 extern void InitITG3200Gyro(void); 01121 extern void ITG3200Test(void); 01122 extern boolean ITG3200GyroActive(void); 01123 01124 extern const real32 GyroToRadian[]; 01125 extern real32 GyroADC[3], GyroADCp[3], GyroNoise[3], GyroNeutral[3], Gyrop[3], Gyro[3]; // Radians 01126 extern uint8 GyroType; 01127 01128 //______________________________________________________________________________________________ 01129 01130 // harness.c 01131 01132 extern void UpdateRTC(void); 01133 extern void InitHarness(void); 01134 01135 extern LocalFileSystem Flash; 01136 01137 extern uint8 I2C0SDAPin, I2C0SCLPin; 01138 01139 // 1 GND 01140 // 2 4.5-9V 01141 // 3 VBat 01142 // 4 NReset 01143 01144 //extern SPI SPI0; // 5 SPI MOSI, 6 SPI MOSO, 7 SPI CLK 01145 //extern DigitalOut SPICS; // 8 01146 extern SDFileSystem SDCard; 01147 01148 //extern I2C I2C1; // 9, 10 01149 extern SerialBuffered TelemetrySerial; 01150 extern DigitalIn Armed; // 11 SPI MOSI 01151 extern DigitalOut PWMCamPitch; // 12 SPI MOSO // 12 SPI MOSO 01152 extern Serial GPSSerial; // 13 Tx1 / SPI CLK, 14 Rx1 01153 01154 extern AnalogIn PitchADC; // 15 AN0 01155 extern AnalogIn RollADC; // 16 AN1 01156 extern AnalogIn YawADC; // 17 AN2 01157 01158 extern AnalogIn RangefinderADC; // 18 AN3 01159 extern AnalogIn BatteryCurrentADC; // 19 AN4 01160 extern AnalogIn BatteryVoltsADC; // 20 AN5 01161 01162 enum ADCValues { ADCPitch, ADCRoll, ADCYaw, ADCRangefinder, ADCBatteryCurrent, ADCBatteryVolts }; 01163 01164 extern PwmOut Out0; // 21 01165 extern PwmOut Out1; // 22 01166 extern PwmOut Out2; // 23 01167 extern PwmOut Out3; // 24 01168 01169 //extern PwmOut Out4; // 25 01170 //extern PwmOut Out5; // 26 01171 extern DigitalOut DebugPin; // 25 01172 01173 #ifdef SW_I2C 01174 01175 class MyI2C { 01176 01177 private: 01178 01179 boolean waitclock(void); 01180 01181 public: 01182 01183 void frequency(uint32 f); 01184 void start(void); 01185 void stop(void); 01186 uint8 blockread(uint8 r, char* b, uint8); 01187 uint8 read(uint8 r); 01188 boolean blockwrite(uint8 a, const char* b, uint8 l); 01189 uint8 write(uint8 d); 01190 }; 01191 01192 extern MyI2C I2C0; // 27, 28 01193 extern PortInOut I2C0SCL; 01194 extern PortInOut I2C0SDA; 01195 #else 01196 01197 extern I2C I2C0; // 27, 28 01198 #define blockread read 01199 #define blockwrite write 01200 01201 #endif // SW_I2C 01202 01203 extern DigitalIn RCIn; // 29 CAN 01204 extern InterruptIn RCInterrupt; 01205 01206 extern DigitalOut PWMCamRoll; // 30 CAN 01207 01208 //extern Serial TelemetrySerial; 01209 // 31 USB +, 32 USB - 01210 // 34 -37 Ethernet 01211 // 38 IF + 01212 // 39 IF - 01213 // 40 3.3V Out 01214 01215 extern DigitalOut BlueLED; 01216 extern DigitalOut GreenLED; 01217 extern DigitalOut RedLED; 01218 extern DigitalOut YellowLED; 01219 01220 extern char RTCString[], RTCLogfile[]; 01221 extern struct tm* RTCTime; 01222 01223 #define I2CTEMP I2C0 01224 #define I2CBARO I2C0 01225 #define I2CBAROAddressResponds I2C0AddressResponds 01226 #define I2CGYRO I2C0 01227 #define I2CGYROAddressResponds I2C0AddressResponds 01228 #define I2CACC I2C0 01229 #define I2CACCAddressResponds I2C0AddressResponds 01230 #define I2CCOMPASS I2C0 01231 #define I2CCOMPASSAddressResponds I2C0AddressResponds 01232 #define I2CESC I2C0 01233 #define I2CLED I2C0 01234 01235 #define SPIACC SPI0 01236 01237 #define mSClock timer.read_ms 01238 #define uSClock timer.read_us 01239 01240 //______________________________________________________________________________________________ 01241 01242 // irq.c 01243 01244 #define CONTROLS 7 01245 #define MAX_CONTROLS 12 // maximum Rx channels 01246 01247 #define RxFilter MediumFilterU 01248 //#define RxFilter SoftFilterU 01249 //#define RxFilter NoFilter 01250 01251 #define RC_GOOD_BUCKET_MAX 20 01252 #define RC_GOOD_RATIO 4 01253 01254 #define RC_MINIMUM 0 01255 01256 #define RC_MAXIMUM 238 01257 01258 #define RC_NEUTRAL ((RC_MAXIMUM-RC_MINIMUM+1)/2) 01259 01260 #define RC_MAX_ROLL_PITCH (170) 01261 01262 #define RC_THRES_STOP ((6L*RC_MAXIMUM)/100) 01263 #define RC_THRES_START ((10L*RC_MAXIMUM)/100) 01264 01265 #define RC_FRAME_TIMEOUT_MS 25 01266 #define RC_SIGNAL_TIMEOUT_MS (5L*RC_FRAME_TIMEOUT_MS) 01267 #define RC_THR_MAX RC_MAXIMUM 01268 01269 #define MAX_ROLL_PITCH RC_NEUTRAL // Rx stick units - rely on Tx Rate/Exp 01270 01271 #ifdef RX6CH 01272 #define RC_CONTROLS 5 01273 #else 01274 #define RC_CONTROLS CONTROLS 01275 #endif //RX6CH 01276 01277 extern void InitTimersAndInterrupts(void); 01278 01279 extern void enableTxIrq0(void); 01280 extern void disableTxIrq0(void); 01281 extern void enableTxIrq1(void); 01282 extern void disableTxIrq1(void); 01283 01284 extern void RCISR(void); 01285 extern void RCNullISR(void); 01286 extern void RCTimeoutISR(void); 01287 extern void GPSInISR(void); 01288 extern void GPSOutISR(void); 01289 extern void TelemetryInISR(void); 01290 extern void TelemetryOutISR(void); 01291 extern void RazorInISR(void); 01292 extern void RazorOutISR(void); 01293 01294 extern void TurnBeeperOff(void); 01295 extern void DoBeeperPulse1mS(int16); 01296 01297 enum { Clock, GeneralCountdown, UpdateTimeout, RCSignalTimeout, BeeperTimeout, ThrottleIdleTimeout, 01298 FailsafeTimeout, AbortTimeout, RxFailsafeTimeout, DescentUpdate, StickChangeUpdate, NavStateTimeout, LastValidRx, 01299 LastGPS, StartTime, GPSTimeout, LEDChaserUpdate, LastBattery, TelemetryUpdate, NavActiveTime, BeeperUpdate, 01300 ArmedTimeout, ThrottleUpdate, RazorUpdate, VerticalDampingUpdate, CamUpdate, BaroUpdate, CompassUpdate 01301 }; 01302 01303 enum WaitPacketStates { WaitSentinel, WaitTag, WaitBody, WaitCheckSum}; 01304 01305 extern uint32 mS[]; 01306 extern int16 PPM[]; 01307 extern int8 PPM_Index; 01308 extern uint32 PrevEdge, CurrEdge; 01309 extern uint8 Intersection, PrevPattern, CurrPattern; 01310 extern uint32 Width; 01311 extern uint8 RxState; 01312 extern boolean WaitingForSync; 01313 01314 extern int8 SignalCount; 01315 extern uint16 RCGlitches; 01316 01317 extern Timer timer; 01318 extern Timeout CamRollTimeout, CamPitchTimeout; 01319 extern Ticker CameraTicker; 01320 extern Timeout RCTimeout; 01321 01322 //______________________________________________________________________________________________ 01323 01324 // ir.c 01325 01326 extern void GetIRAttitude(void); 01327 extern void TrackIRMaxMin(uint8); 01328 extern void InitIRSensors(void); 01329 01330 extern real32 IR[3], IRMax, IRMin, IRSwing; 01331 01332 //______________________________________________________________________________________________ 01333 01334 // i2c.c 01335 01336 #define I2C_ACK true 01337 #define I2C_NACK false 01338 01339 extern boolean I2C0AddressResponds(uint8); 01340 #ifdef HAVE_I2C1 01341 extern boolean I2C1AddressResponds(uint8); 01342 #endif // HAVE_I2C1 01343 extern void TrackMinI2CRate(uint32); 01344 extern void ShowI2CDeviceName(uint8); 01345 extern uint8 ScanI2CBus(void); 01346 extern boolean ESCWaitClkHi(void); 01347 extern void ProgramSlaveAddress(uint8); 01348 extern void ConfigureESCs(void); 01349 extern void InitI2C(void); 01350 01351 extern uint32 MinI2CRate; 01352 extern uint16 I2CError[256]; 01353 01354 //______________________________________________________________________________________________ 01355 01356 // leds.c 01357 01358 #define PCA9551_ID 0xc0 01359 01360 #define DRV0M 0x0001 01361 #define DRV1M 0x0002 01362 #define DRV2M 0x0004 01363 #define DRV3M 0x0008 01364 01365 #define AUX0M 0x0010 01366 #define AUX1M 0x0020 01367 #define AUX2M 0x0040 01368 #define AUX3M 0x0080 01369 01370 #define BeeperM DRV0M 01371 01372 #define YellowM 0x0100 01373 #define RedM 0x0200 01374 #define GreenM 0x0400 01375 #define BlueM 0x0800 01376 01377 #define ALL_LEDS_ON LEDsOn(BlueM|RedM|GreenM|YellowM) 01378 #define ALL_LEDS_OFF LEDsOff(BlueM|RedM|GreenM|YellowM) 01379 01380 #define AUX_LEDS_ON LEDsOn(AUX0M|AUX1M|AUX2M|AUX3M) 01381 #define AUX_LEDS_OFF LEDsOff(AUX0M|AUX1M|AUX2M|AUX3M) 01382 01383 #define AUX_DRVS_ON LEDsOn(DRV0M|DRV1M|DRV2M|DRV3M) 01384 #define AUX_DRVS_OFF LEDsOff(DRV0M|DRV1M|DRV2M|DRV3M) 01385 01386 #define ALL_LEDS_ARE_OFF ( (LEDShadow&(BlueM|RedM|GreenM|YellowM))== (uint8)0 ) 01387 01388 #define BEEPER_IS_ON ( (LEDShadow & BeeperM) != (uint8)0 ) 01389 #define BEEPER_IS_OFF ( (LEDShadow & BeeperM) == (uint8)0 ) 01390 01391 #define LEDRed_ON LEDsOn(RedM) 01392 #define LEDBlue_ON LEDsOn(BlueM) 01393 #define LEDGreen_ON LEDsOn(GreenM) 01394 #define LEDYellow_ON LEDsOn(YellowM) 01395 #define LEDAUX1_ON LEDsOn(AUX1M) 01396 #define LEDAUX2_ON LEDsOn(AUX2M) 01397 #define LEDAUX3_ON LEDsOn(AUX3M) 01398 #define LEDRed_OFF LEDsOff(RedM) 01399 #define LEDBlue_OFF LEDsOff(BlueM) 01400 #define LEDGreen_OFF LEDsOff(GreenM) 01401 #define LEDYellow_OFF LEDsOff(YellowM) 01402 #define LEDYellow_TOG if( (LEDShadow&YellowM) == (uint8)0 ) LEDsOn(YellowM); else LEDsOff(YellowM) 01403 #define LEDRed_TOG if( (LEDShadow&RedM) == (uint8)0 ) LEDsOn(RedM); else LEDsOff(RedM) 01404 #define LEDBlue_TOG if( (LEDShadow&BlueM) == (uint8)0 ) LEDsOn(BlueM); else LEDsOff(BlueM) 01405 #define LEDGreen_TOG if( (LEDShadow&GreenM) == (uint8)0 ) LEDsOn(GreenM); else LEDsOff(GreenM) 01406 #define Beeper_OFF LEDsOff(BeeperM) 01407 #define Beeper_ON LEDsOn(BeeperM) 01408 #define Beeper_TOG if( (LEDShadow&BeeperM) == (uint8)0 ) LEDsOn(BeeperM); else LEDsOff(BeeperM) 01409 01410 extern void SendLEDs(void); 01411 extern void SaveLEDs(void); 01412 extern void RestoreLEDs(void); 01413 extern void LEDsOn(uint16); 01414 extern void LEDsOff(uint16); 01415 extern void LEDChaser(void); 01416 extern void DoLEDs(void); 01417 extern void PowerOutput(int8); 01418 extern void LEDsAndBuzzer(void); 01419 01420 extern void PCA9551Test(void); 01421 extern void WritePCA9551(uint8); 01422 extern boolean IsPCA9551Active(void); 01423 01424 extern void InitLEDs(void); 01425 01426 extern uint16 LEDShadow, PrevLEDShadow, SavedLEDs, LEDPattern; 01427 extern uint8 PrevPCA9551LEDShadow; 01428 01429 //______________________________________________________________________________________________ 01430 01431 // math.c 01432 01433 extern int16 SRS16(int16, uint8); 01434 extern int32 SRS32(int32, uint8); 01435 extern real32 Make2Pi(real32); 01436 extern real32 MakePi(real32); 01437 extern int16 Table16(int16, const int16 *); 01438 01439 extern real32 VDot(real32 v1[3], real32 v2[3]); 01440 extern void VCross(real32 VOut[3], real32 v1[3], real32 v2[3]); 01441 extern void VScale(real32 VOut[3], real32 v[3], real32 s); 01442 extern void VAdd(real32 VOut[3],real32 v1[3], real32 v2[3]); 01443 extern void VSub(real32 VOut[3],real32 v1[3], real32 v2[3]); 01444 01445 //______________________________________________________________________________________________ 01446 01447 // menu.c 01448 01449 extern void ShowPrompt(void); 01450 extern void ShowRxSetup(void); 01451 extern void ShowSetup(boolean); 01452 extern uint8 MakeUpper(uint8); 01453 extern void ProcessCommand(void); 01454 01455 extern const uint8 SerHello[]; 01456 extern const uint8 SerSetup[]; 01457 extern const uint8 SerPrompt[]; 01458 01459 extern const uint8 RxChMnem[]; 01460 01461 //______________________________________________________________________________________________ 01462 01463 // nonvolatiles.c 01464 01465 extern void CheckSDCardValid(void); 01466 01467 extern void CreateLogfile(void); 01468 extern void CloseLogfile(void); 01469 extern void TxLogChar(uint8); 01470 01471 extern void WritePXImagefile(void); 01472 extern boolean ReadPXImagefile(void); 01473 extern int8 ReadPX(uint16); 01474 extern int16 Read16PX(uint16); 01475 extern int32 Read32PX(uint16); 01476 extern void WritePX(uint16, int8); 01477 extern void Write16PX(uint16, int16); 01478 extern void Write32PX(uint16, int32); 01479 01480 extern FILE *pxfile; 01481 extern FILE *newpxfile; 01482 01483 extern const int PX_LENGTH; 01484 extern int8 PX[], PXNew[]; 01485 01486 //______________________________________________________________________________________________ 01487 01488 // NXP1768pins.c 01489 01490 extern boolean PinRead(uint8); 01491 extern void PinWrite(uint8, boolean); 01492 extern void PinSetOutput(uint8, boolean); 01493 01494 extern const uint8 mbed1768Pins[]; 01495 01496 //______________________________________________________________________________________________ 01497 01498 // outputs.c 01499 01500 #define OUT_MINIMUM 1.0 // Required for PPM timing loops 01501 #define OUT_MAXIMUM 200.0 // to reduce Rx capture and servo pulse output interaction 01502 #define OUT_NEUTRAL 105.0 // 1.503mS @ 105 16MHz 01503 #define OUT_HOLGER_MAXIMUM 225.0 01504 #define OUT_YGEI2C_MAXIMUM 240.0 01505 #define OUT_X3D_MAXIMUM 200.0 01506 01507 extern uint8 SaturInt(int16); 01508 extern void DoMulticopterMix(real32 CurrThrottle); 01509 extern void CheckDemand(real32 CurrThrottle); 01510 extern void MixAndLimitMotors(void); 01511 extern void MixAndLimitCam(void); 01512 extern void OutSignals(void); 01513 extern void InitI2CESCs(void); 01514 extern void StopMotors(void); 01515 extern void ExercisePWM(void); 01516 extern void InitMotors(void); 01517 01518 // Using clockwise numbering - NOT the same as UAVXPIC 01519 enum PWMCamTags { CamRollC = 6, CamPitchC = 7 }; 01520 enum PWMQuadTags {FrontC=0, RightC, BackC, LeftC }; // order is important for X3D & Holger ESCs 01521 enum PWMConvTags {ThrottleC=0, AileronC, ElevatorC, RudderC, RTHC }; 01522 enum PWMWingTags3 {RightElevonC=1, LeftElevonC=2}; 01523 enum PWMVTTags {FrontRightC=0, FrontLeftC}; 01524 enum PWMY6Tags {FrontTC=0, RightTC, LeftTC, FrontBC, RightBC, LeftBC }; 01525 enum PWMHexTags {FrontHC=0, FrontRightHC, BackRightHC, BackHC, BackLeftHC,FrontLeftHC }; 01526 01527 //#define NoOfPWMOutputs 4 01528 #ifdef HEXACOPTER 01529 #define NoOfI2CESCOutputs 6 01530 #else 01531 #define NoOfI2CESCOutputs 4 01532 #endif // HEXACOPTER 01533 01534 extern const real32 PWMScale; 01535 01536 extern real32 PWM[8]; 01537 extern real32 PWMSense[8]; 01538 extern int16 ESCI2CFail[6]; 01539 extern int16 CurrThrottle; 01540 extern int16 CamRollPulseWidth, CamPitchPulseWidth; 01541 extern int16 ESCMin, ESCMax; 01542 01543 //______________________________________________________________________________________________ 01544 01545 // params.c 01546 01547 extern void ReadParameters(void); 01548 extern void UseDefaultParameters(void); 01549 extern void UpdateParamSetChoice(void); 01550 extern boolean ParameterSanityCheck(void); 01551 extern void InitParameters(void); 01552 01553 enum TxRxTypes { 01554 FutabaCh3, FutabaCh2, FutabaDM8, JRPPM, JRDM9, JRDXS12, 01555 DX7AR7000, DX7AR6200, FutabaCh3_6_7, DX7AR6000, GraupnerMX16s, DX6iAR6200, FutabaCh3_R617FS, 01556 DX7aAR7000, ExternalDecoder, FrSkyDJT_D8R, UnknownTxRx, CustomTxRx 01557 }; 01558 enum RCControls {ThrottleRC, RollRC, PitchRC, YawRC, RTHRC, CamPitchRC, NavGainRC}; 01559 enum ESCTypes { ESCPPM, ESCHolger, ESCX3D, ESCYGEI2C }; 01560 enum AFs { QuadAF, TriAF, VTAF, Y6AF, HeliAF, ElevAF, AilAF }; 01561 01562 enum Params { // MAX 64 01563 RollKp, // 01 01564 RollKi, // 02 01565 RollKd, // 03 01566 Unused04, // 04c HorizDampKp 01567 RollIntLimit, // 05 01568 PitchKp, // 06 01569 PitchKi, // 07 01570 PitchKd, // 08 01571 AltKp, // 09c 01572 PitchIntLimit, // 10 01573 01574 YawKp, // 11 01575 YawKi, // 12 01576 Unused13, // 13 YawKd 01577 YawLimit, // 14 01578 YawIntLimit, // 15 01579 ConfigBits, // 16c 01580 Unused17 , // 17 TimeSlots 01581 LowVoltThres, // 18c 01582 CamRollKp, // 19 01583 PercentCruiseThr, // 20c 01584 01585 VertDamp, // 21c 01586 MiddleUD, // 22c 01587 PercentIdleThr, // 23c 01588 MiddleLR, // 24c 01589 MiddleBF, // 25c 01590 CamPitchKp, // 26 01591 CompassKp, // 27 01592 AltKi, // 28c 01593 Unused29 , // 29 NavRadius 01594 NavKi, // 30 01595 01596 GSThrottle, // 31 01597 Acro, // 32 01598 NavRTHAlt, // 33 01599 NavMagVar, // 34c 01600 GyroRollPitchType, // 35 01601 ESCType, // 36 01602 TxRxType, // 37 01603 NeutralRadius, // 38 01604 PercentNavSens6Ch, // 39 01605 CamRollTrim, // 40 01606 NavKd, // 41 01607 Unused42 , // 42 VertDampDecay 01608 Unused43, // 43 HorizDampDecay 01609 BaroScale, // 44 01610 TelemetryType, // 45 01611 MaxDescentRateDmpS, // 46 01612 DescentDelayS, // 47 01613 NavIntLimit, // 48 01614 AltIntLimit, // 49 01615 Unused50, // 50 GravComp 01616 Unused51 , // 51 CompSteps 01617 ServoSense, // 52 01618 CompassOffsetQtr, // 53 01619 BatteryCapacity, // 54 01620 Unused55, // 55 GyroYawType 01621 AltKd, // 56 01622 Orient, // 57 01623 NavYawLimit, // 58 01624 Balance // 59 01625 01626 // 56 - 64 unused currently 01627 }; 01628 01629 //#define FlyXMode 0 01630 //#define FlyAltOrientationMask 0x01 01631 01632 #define UsePositionHoldLock 0 01633 #define UsePositionHoldLockMask 0x01 01634 01635 #define UseRTHDescend 1 01636 #define UseRTHDescendMask 0x02 01637 01638 #define TxMode2 2 01639 #define TxMode2Mask 0x04 01640 01641 #define RxSerialPPM 3 01642 #define RxSerialPPMMask 0x08 01643 01644 #define RFInches 4 01645 #define RFInchesMask 0x10 01646 01647 // bit 4 is pulse polarity for 3.15 01648 01649 #define UseUseAngleControl 5 01650 #define UseAngleControlMask 0x20 01651 01652 #define UsePolar 6 01653 #define UsePolarMask 0x40 01654 01655 // bit 7 unusable in UAVPSet 01656 01657 extern const int8 DefaultParams[MAX_PARAMETERS][2]; 01658 01659 extern const uint8 ESCLimits []; 01660 01661 extern real32 OSin[], OCos[]; 01662 extern uint8 Orientation, PolarOrientation; 01663 01664 extern uint8 ParamSet; 01665 extern boolean ParametersChanged, SaveAllowTurnToWP; 01666 extern int8 P[]; 01667 extern real32 K[MAX_PARAMETERS]; // Arm rescaled legacy parameters as appropriate 01668 01669 extern uint8 UAVXAirframe; 01670 01671 //__________________________________________________________________________________________ 01672 01673 // rc.c 01674 01675 #define RC_INIT_FRAMES 32 // number of initial RC frames to allow filters to settle 01676 01677 #define RC_MIN_WIDTH_US 1000 // temporarily to prevent wraparound 900 01678 #define RC_MAX_WIDTH_US 2100 01679 01680 #define RC_NO_CHANGE_TIMEOUT_MS 20000L 01681 01682 extern void DoRxPolarity(void); 01683 extern void InitRC(void); 01684 extern void MapRC(void); 01685 extern void CheckSticksHaveChanged(void); 01686 extern void UpdateControls(void); 01687 extern void CaptureTrims(void); 01688 extern void CheckThrottleMoved(void); 01689 extern void ReceiverTest(void); 01690 01691 extern const boolean PPMPosPolarity[]; 01692 extern const uint8 Map[CustomTxRx+1][CONTROLS]; 01693 extern int8 RMap[]; 01694 01695 #define PPMQMASK 3 01696 extern int16 PPMQSum[]; 01697 extern int16x8x4Q PPMQ; 01698 extern boolean RCPositiveEdge; 01699 extern int16 RC[], RCp[]; 01700 extern int16 ThrLow, ThrNeutral, ThrHigh; 01701 01702 //__________________________________________________________________________________________ 01703 01704 // serial.c 01705 01706 extern void TxString(const uint8*); 01707 extern void TxChar(uint8); 01708 extern void TxValU(uint8); 01709 extern void TxValS(int8); 01710 extern void TxBin8(uint8); 01711 extern void TxNextLine(void); 01712 extern void TxNibble(uint8); 01713 extern void TxValH( uint8); 01714 extern void TxValH16(uint16); 01715 extern uint8 RxChar(void); 01716 extern uint8 PollRxChar(void); 01717 extern uint8 RxNumU(void); 01718 extern int8 RxNumS(void); 01719 extern void TxVal32(int32, int8, uint8); 01720 extern void TxChar(uint8); 01721 extern void TxESCu8(uint8); 01722 extern void Sendi16(int16); 01723 extern void TxESCi8(int8); 01724 extern void TxESCi16(int16); 01725 extern void TxESCi24(int24); 01726 extern void TxESCi32(int32); 01727 01728 //______________________________________________________________________________________________ 01729 01730 // stats.c 01731 01732 extern void ZeroStats(void); 01733 extern void ReadStatsPX(void); 01734 extern void WriteStatsPX(void); 01735 extern void ShowStats(void); 01736 01737 enum Statistics { 01738 GPSAltitudeS, BaroRelAltitudeS, ESCI2CFailS, GPSMinSatsS, MinROCS, MaxROCS, GPSVelS, 01739 AccFailS, CompassFailS, BaroFailS, GPSInvalidS, GPSMaxSatsS, NavValidS, 01740 MinHDiluteS, MaxHDiluteS, RCGlitchesS, GPSBaroScaleS, GyroFailS, RCFailsafesS, I2CFailS, MinTempS, MaxTempS, BadS, BadNumS }; // NO MORE THAN 32 or 64 bytes 01741 01742 extern int16 Stats[]; 01743 01744 //______________________________________________________________________________________________ 01745 01746 // telemetry.c 01747 01748 extern void RxTelemetryPacket(uint8); 01749 extern void InitTelemetryPacket(void); 01750 extern void BuildTelemetryPacket(uint8); 01751 01752 extern void SendPacketHeader(void); 01753 extern void SendPacketTrailer(void); 01754 01755 extern void SendTelemetry(void); 01756 extern void SendUAVX(void); 01757 extern void SendUAVXControl(void); 01758 extern void SendFlightPacket(void); 01759 extern void SendNavPacket(void); 01760 extern void SendControlPacket(void); 01761 extern void SendStatsPacket(void); 01762 extern void SendParamPacket(uint8, uint8); 01763 extern void SendParameters(uint8); 01764 extern void SendMinPacket(void); 01765 extern void SendArduStation(void); 01766 extern void SendPIDTuning(void); 01767 extern void SendCustom(void); 01768 extern void SensorTrace(void); 01769 extern void CheckTelemetry(void); 01770 01771 enum TelemetryStates { WaitRxSentinel, WaitRxESC, WaitRxBody }; 01772 01773 01774 enum PacketTags {UnknownPacketTag = 0, LevPacketTag, NavPacketTag, MicropilotPacketTag, WayPacketTag, 01775 AirframePacketTag, NavUpdatePacketTag, BasicPacketTag, RestartPacketTag, TrimblePacketTag, 01776 MessagePacketTag, EnvironmentPacketTag, BeaconPacketTag, UAVXFlightPacketTag, 01777 UAVXNavPacketTag, UAVXStatsPacketTag, UAVXControlPacketTag, UAVXParamPacketTag, UAVXMinPacketTag, 01778 UAVXArmParamPacketTag, UAVXStickPacketTag, UAVXCustomPacketTag, FrSkyPacketTag = 99 01779 }; 01780 01781 enum TelemetryTypes { NoTelemetry, GPSTelemetry, UAVXTelemetry, UAVXControlTelemetry, UAVXMinTelemetry, 01782 ArduStationTelemetry, CustomTelemetry 01783 }; 01784 01785 extern uint8 UAVXCurrPacketTag; 01786 extern uint8 RxPacketLength, RxPacketByteCount; 01787 extern uint8 RxCheckSum; 01788 extern uint8 RxPacketTag, ReceivedPacketTag; 01789 extern uint8 PacketRxState; 01790 extern boolean CheckSumError, TelemetryPacketReceived; 01791 01792 extern int16 RxLengthErrors, RxTypeErrors, RxCheckSumErrors; 01793 01794 extern uint8 TxCheckSum; 01795 01796 extern FILE *logfile; 01797 extern boolean EchoToLogFile, LogfileIsOpen; 01798 extern uint32 LogChars; 01799 01800 //______________________________________________________________________________________________ 01801 01802 // temperature.c 01803 01804 #define TMP100_MAX_ADC 4095 // 12 bits 01805 #define TMP100_ID 0x96 01806 #define TMP100_WR 0x96 // Write 01807 #define TMP100_RD 0x97 // Read 01808 #define TMP100_TMP 0x00 // Temperature 01809 #define TMP100_CMD 0x01 01810 #define TMP100_LOW 0x02 // Alarm low limit 01811 #define TMP100_HI 0x03 // Alarm high limit 01812 #define TMP100_CFG 0 // 0.5 deg resolution continuous 01813 01814 extern void GetTemperature(void); 01815 extern void InitTemperature(void); 01816 01817 extern i16u AmbientTemperature; 01818 01819 //______________________________________________________________________________________________ 01820 01821 // utils.c 01822 01823 extern void InitMisc(void); 01824 extern void Delay1mS(int16); 01825 extern void Delay100mS(int16); 01826 extern void DoBeep100mS(uint8, uint8); 01827 extern void DoStartingBeeps(uint8); 01828 extern real32 SlewLimit(real32, real32, real32); 01829 extern real32 DecayX(real32, real32); 01830 extern real32 LPFilter(real32, real32, real32); 01831 extern void CheckAlarms(void); 01832 extern void Timing(uint8, uint32); 01833 01834 typedef struct { 01835 uint32 T; 01836 uint32 Count; 01837 } TimingRec; 01838 01839 extern uint32 BeeperOnTime, BeeperOffTime; 01840 01841 enum Timed { GetAttitudeT , UnknownT }; 01842 extern TimingRec Times[]; 01843 01844 #define TimeS uint32 TStart;TStart=timer.read_us(); 01845 #define TimeF(w, tf) Time(w, tf) 01846 01847 //______________________________________________________________________________________________ 01848 01849 01850 // Sanity checks 01851 01852 #if (( defined TRICOPTER + defined QUADROCOPTER + defined VTCOPTER + defined Y6COPTER + defined HELICOPTER + defined AILERON + defined ELEVON ) != 1) 01853 #error None or more than one aircraft configuration defined ! 01854 #endif
Generated on Wed Jul 13 2022 01:50:20 by
