From cbd117d216ef8facbd6b6bdaa8b180bb538c24ba Mon Sep 17 00:00:00 2001 From: AvSquirrel Date: Tue, 7 Jun 2016 13:03:25 +0000 Subject: [PATCH 01/17] Initial implementation of GPS attitude on v0.9 codebase. Needs debug. --- main/gen_gdl90.go | 14 ++ main/ry835ai.go | 532 +++++++++++++++++++++++++++++++++++++++++++++- 2 files changed, 540 insertions(+), 6 deletions(-) diff --git a/main/gen_gdl90.go b/main/gen_gdl90.go index 6a65665c7..5ba0d3c76 100644 --- a/main/gen_gdl90.go +++ b/main/gen_gdl90.go @@ -75,6 +75,15 @@ const ( LON_LAT_RESOLUTION = float32(180.0 / 8388608.0) TRACK_RESOLUTION = float32(360.0 / 256.0) + + GPS_TYPE_NMEA = 0x01 + GPS_TYPE_UBX = 0x02 + GPS_TYPE_SIRF = 0x03 + GPS_TYPE_MEDIATEK = 0x04 + GPS_TYPE_FLARM = 0x05 + GPS_TYPE_GARMIN = 0x06 + // other GPS types to be defined as needed + ) var usage *du.DiskUsage @@ -953,6 +962,8 @@ type settings struct { PPM int OwnshipModeS string WatchList string + AHRS_GDL90_Enabled bool + GPSAttitude_Enabled bool } type status struct { @@ -971,6 +982,7 @@ type status struct { GPS_satellites_tracked uint16 GPS_connected bool GPS_solution string + GPS_detected_type uint RY835AI_connected bool Uptime int64 Clock time.Time @@ -1004,6 +1016,8 @@ func defaultSettings() { globalSettings.DisplayTrafficSource = false globalSettings.ReplayLog = false //TODO: 'true' for debug builds. globalSettings.OwnshipModeS = "F00000" + globalSettings.AHRS_GDL90_Enabled = false + globalSettings.GPSAttitude_Enabled = false } func readSettings() { diff --git a/main/ry835ai.go b/main/ry835ai.go index 582d3a278..4007d5e9d 100644 --- a/main/ry835ai.go +++ b/main/ry835ai.go @@ -12,6 +12,7 @@ package main import ( "fmt" "log" + "math" "strconv" "strings" "sync" @@ -53,8 +54,8 @@ type SatelliteInfo struct { } type SituationData struct { - mu_GPS *sync.Mutex - + mu_GPS *sync.Mutex + mu_GPSPerf *sync.Mutex // From GPS. LastFixSinceMidnightUTC float32 Lat float32 @@ -72,6 +73,7 @@ type SituationData struct { GPSVertVel float32 // GPS vertical velocity, feet per second LastFixLocalTime time.Time TrueCourse float32 + GPSTurnRate float64 // calculated GPS rate of turn, degrees per second GroundSpeed uint16 LastGroundTrackTime time.Time GPSTime time.Time @@ -93,6 +95,26 @@ type SituationData struct { LastAttitudeTime time.Time } +/* +myGPSPerfStats used to track short-term position / velocity trends, used to feed dynamic AHRS model. Use floats for better resolution of calculated data. +*/ +type gpsPerfStats struct { + stratuxTime uint64 // time since Stratux start, msec + nmeaTime float32 // timestamp from NMEA message + msgType string // NMEA message type + gsf float32 // knots + coursef float32 // true course [degrees] + alt float32 // gps altitude, ft msl + vv float32 // vertical velocity, ft/sec + gpsTurnRate float64 // calculated turn rate, deg/sec. Right turn is positive. + gpsPitch float64 // estimated pitch angle, deg. Calculated from gps ground speed and VV. Equal to flight path angle. + gpsRoll float64 // estimated roll angle from turn rate and groundspeed, deg. Assumes airplane in coordinated turns. + gpsLoadFactor float64 // estimated load factor from turn rate and groundspeed, "gee". Assumes airplane in coordinated turns. +} + +var gpsPerf gpsPerfStats +var myGPSPerfStats []gpsPerfStats + var serialConfig *serial.Config var serialPort *serial.Port @@ -117,6 +139,13 @@ p.109 CFG-NAV5 (0x06 0x24) Poll Navigation Engine Settings */ +/* + chksumUBX() + returns the two-byte Fletcher algorithm checksum of byte array msg. + This is used in configuration messages for the u-blox GPS. See p. 97 of the + u-blox M8 Receiver Description. +*/ + func chksumUBX(msg []byte) []byte { ret := make([]byte, 2) for i := 0; i < len(msg); i++ { @@ -126,7 +155,12 @@ func chksumUBX(msg []byte) []byte { return ret } -// p.62 +/* + makeUBXCFG() + creates a UBX-formatted package consisting of two sync characters, + class, ID, payload length in bytes (2-byte little endian), payload, and checksum. + See p. 95 of the u-blox M8 Receiver Description. +*/ func makeUBXCFG(class, id byte, msglen uint16, msg []byte) []byte { ret := make([]byte, 6) ret[0] = 0xB5 @@ -154,6 +188,7 @@ func initGPSSerial() bool { var device string baudrate := int(9600) isSirfIV := bool(false) + globalStatus.GPS_detected_type = 0 // reset detected type on each initialization if _, err := os.Stat("/dev/ublox8"); err == nil { // u-blox 8 (RY83xAI over USB). device = "/dev/ublox8" @@ -436,6 +471,360 @@ func setTrueCourse(groundSpeed uint16, trueCourse float64) { } } +/* +calcGPSAttitude estimates turn rate, pitch, and roll based on recent GPS groundspeed, track, and altitude / vertical speed. + +Method uses stored performance statistics from myGPSPerfStats[]. Ideally, calculation is based on most recent 1.5 seconds of data, +assuming 10 Hz sampling frequency. Lower frequency sample rates will increase calculation window for smoother response, at the +cost of slightly increased lag. + +(c) 2016 AvSquirrel (https://github.com/AvSquirrel) . All rights reserved. +Distributable under the terms of the "BSD-New" License that can be found in +the LICENSE file, herein included as part of this header. +*/ + +func calcGPSAttitude() bool { + // check slice length. Return error if empty set or set zero values + mySituation.mu_GPSPerf.Lock() + defer mySituation.mu_GPSPerf.Unlock() + length := len(myGPSPerfStats) + index := length - 1 + + if length == 0 { + log.Printf("GPS attitude: No data received yet. Not calculating attitude.\n") + return false + } else if length == 1 { + //log.Printf("myGPSPerfStats has one data point. Setting statistics to zero.\n") + myGPSPerfStats[index].gpsTurnRate = 0 + myGPSPerfStats[index].gpsPitch = 0 + myGPSPerfStats[index].gpsRoll = 0 + return false + } + + // check if GPS data was put in the structure more than three seconds ago -- this shouldn't happen unless something is wrong. + if (stratuxClock.Milliseconds - myGPSPerfStats[index].stratuxTime) > 3000 { + myGPSPerfStats[index].gpsTurnRate = 0 + myGPSPerfStats[index].gpsPitch = 0 + myGPSPerfStats[index].gpsRoll = 0 + log.Printf("GPS attitude: GPS data is more than three seconds old. Setting attitude to zero.\n") + return false + } + + // check time interval between samples + t1 := myGPSPerfStats[index].nmeaTime + t0 := myGPSPerfStats[index-1].nmeaTime + dt := t1 - t0 + + // first time error case: index is more than three seconds ahead of index-1 + if dt > 3 { + log.Printf("GPS attitude: Can't calculate GPS attitude. Reference data is old. dt = %v\n", dt) + return false + } + + // second case: index is behind index-1. This could be result of day rollover. If time is within n seconds of UTC, + // we rebase to the previous day, and will re-rebase the entire slice forward to the current day once all values roll over. + // TO-DO: Validate by testing at 0000Z + if dt < 0 { + log.Printf("GPS attitude: Current GPS time (%.2f) is older than last GPS time (%.2f). Checking for 0000Z rollover.\n", t1, t0) + if myGPSPerfStats[index-1].nmeaTime > 86300 && myGPSPerfStats[index].nmeaTime < 100 { // be generous with the time window at rollover + myGPSPerfStats[index].nmeaTime += 86400 + } else { + // time decreased, but not due to a recent rollover. Something odd is going on. + log.Printf("GPS attitude: Time isn't near 0000Z. Unknown reason for offset. Can't calculate GPS attitude.\n") + return false + } + + // check time array to see if all timestamps are > 86401 seconds since midnight + var tempTime []float64 + tempTime = make([]float64, length, length) + for i := 0; i < length; i++ { + tempTime[i] = float64(myGPSPerfStats[i].nmeaTime) + } + minTime, _ := arrayMin(tempTime) + if minTime > 86401.0 { + log.Printf("GPS attitude: Rebasing GPS time since midnight to current day.\n") + for i := 0; i < length; i++ { + myGPSPerfStats[i].nmeaTime -= 86400 + } + } + + // Verify adjustment + dt = myGPSPerfStats[index].nmeaTime - myGPSPerfStats[index-1].nmeaTime + log.Printf("GPS attitude: New dt = %f\n", dt) + if dt > 3 { + log.Printf("GPS attitude: Can't calculate GPS attitude. Reference data is old. dt = %v\n", dt) + return false + } else if dt < 0 { + log.Printf("GPS attitude: Something went wrong rebasing the time.\n") + return false + } + + } + + // If all of the bounds checks pass, begin processing the GPS data. + + // local variables + var headingAvg, dh, v_x, v_z, a_c, omega, slope, intercept, dt_avg float64 + var tempHdg, tempHdgUnwrapped, tempHdgTime, tempSpeed, tempVV, tempSpeedTime, tempRegWeights []float64 // temporary arrays for regression calculation + var valid bool + var lengthHeading, lengthSpeed int + + center := float64(myGPSPerfStats[index].nmeaTime) // current time for calculating regression weights + halfwidth := float64(2.0) // width of regression evaluation window. Default of 2.0 seconds for 5 Hz sampling; can increase to 5 sec @ 1 Hz + + // frequency detection + tempSpeedTime = make([]float64, 0) + for i := 1; i < length; i++ { + dt = myGPSPerfStats[i].nmeaTime - myGPSPerfStats[i-1].nmeaTime + if dt > 0.05 { // avoid double counting messages with same / similar timestamps + tempSpeedTime = append(tempSpeedTime, float64(dt)) + } + } + //log.Printf("Delta time array is %v.\n",tempSpeedTime) + dt_avg, valid = mean(tempSpeedTime) + if valid && dt_avg > 0 { + if globalSettings.DEBUG { + log.Printf("GPS attitude: Average delta time is %.2f s (%.1f Hz)\n", dt_avg, 1/dt_avg) + } + halfwidth = 10 * dt_avg + } else { + if globalSettings.DEBUG { + log.Printf("GPS attitude: Couldn't determine sample rate\n") + } + halfwidth = 3.0 + } + + if halfwidth > 5 { + halfwidth = 5 // limit calculation window to 5 seconds of data for 2 Hz or slower samples + } + + if globalStatus.GPS_detected_type == GPS_TYPE_UBX { // UBX reports vertical speed, so we can just walk through all of the PUBX messages in order + // Speed and VV. Use all values in myGPSPerfStats; perform regression. + tempSpeedTime = make([]float64, length, length) // all are length of original slice + tempSpeed = make([]float64, length, length) + tempVV = make([]float64, length, length) + tempRegWeights = make([]float64, length, length) + + for i := 0; i < length; i++ { + tempSpeed[i] = float64(myGPSPerfStats[i].gsf) + tempVV[i] = float64(myGPSPerfStats[i].vv) + tempSpeedTime[i] = float64(myGPSPerfStats[i].nmeaTime) + tempRegWeights[i] = triCubeWeight(center, halfwidth, tempSpeedTime[i]) + } + + // Groundspeed regression estimate. + slope, intercept, valid = linRegWeighted(tempSpeedTime, tempSpeed, tempRegWeights) + if !valid { + log.Printf("GPS attitude: Error calculating speed regression from UBX position messages") + return false + } else { + v_x = (slope*float64(myGPSPerfStats[index].nmeaTime) + intercept) * 1.687810 // units are knots, converted to feet/sec + } + + // Vertical speed regression estimate. + slope, intercept, valid = linRegWeighted(tempSpeedTime, tempVV, tempRegWeights) + if !valid { + log.Printf("GPS attitude: Error calculating vertical speed regression from UBX position messages") + return false + } else { + v_z = (slope*float64(myGPSPerfStats[index].nmeaTime) + intercept) // units are feet per sec; no conversion needed + } + + } else { // If we need to parse standard NMEA messages, determine if it's RMC or GGA, then fill the temporary slices accordingly. Need to pull from multiple message types since GGA doesn't do course or speed; VTG / RMC don't do altitude, etc. Grrr. + + //v_x = float64(myGPSPerfStats[index].gsf * 1.687810) + //v_z = 0 + + // first, parse groundspeed from RMC messages. + tempSpeedTime = make([]float64, 0) + tempSpeed = make([]float64, 0) + tempRegWeights = make([]float64, 0) + + for i := 0; i < length; i++ { + if myGPSPerfStats[i].msgType == "GPRMC" || myGPSPerfStats[i].msgType == "GNRMC" { + tempSpeed = append(tempSpeed, float64(myGPSPerfStats[i].gsf)) + tempSpeedTime = append(tempSpeedTime, float64(myGPSPerfStats[i].nmeaTime)) + tempRegWeights = append(tempRegWeights, triCubeWeight(center, halfwidth, float64(myGPSPerfStats[i].nmeaTime))) + } + } + lengthSpeed = len(tempSpeed) + if lengthSpeed == 0 { + log.Printf("GPS Attitude: No groundspeed data could be parsed from NMEA RMC messages\n") + return false + } else if lengthSpeed == 1 { + v_x = tempSpeed[0] * 1.687810 + } else { + slope, intercept, valid = linRegWeighted(tempSpeedTime, tempSpeed, tempRegWeights) + if !valid { + log.Printf("GPS attitude: Error calculating speed regression from NMEA RMC position messages") + return false + } else { + v_x = (slope*float64(myGPSPerfStats[index].nmeaTime) + intercept) * 1.687810 // units are knots, converted to feet/sec + } + } + + // next, calculate vertical velocity from GGA altitude data. + tempSpeedTime = make([]float64, 0) + tempVV = make([]float64, 0) + tempRegWeights = make([]float64, 0) + + for i := 0; i < length; i++ { + if myGPSPerfStats[i].msgType == "GPGGA" || myGPSPerfStats[i].msgType == "GNGGA" { + tempVV = append(tempVV, float64(myGPSPerfStats[i].alt)) + tempSpeedTime = append(tempSpeedTime, float64(myGPSPerfStats[i].nmeaTime)) + tempRegWeights = append(tempRegWeights, triCubeWeight(center, halfwidth, float64(myGPSPerfStats[i].nmeaTime))) + } + } + lengthSpeed = len(tempVV) + if lengthSpeed < 2 { + log.Printf("GPS Attitude: Not enough points to calculate vertical speed from NMEA GGA messages\n") + return false + } else { + slope, _, valid = linRegWeighted(tempSpeedTime, tempVV, tempRegWeights) + if !valid { + log.Printf("GPS attitude: Error calculating vertical speed regression from NMEA GGA messages") + return false + } else { + v_z = slope // units are feet/sec + + } + } + + } + + // If we're going too slow for processNMEALine() to give us valid heading data, there's no sense in trying to parse it. + // However, we need to return a valid level attitude so we don't get the "red X of death" on our AHRS display. + // This will also eliminate most of the nuisance error message from the turn rate calculation. + if v_x < 6 { // ~3.55 knots + + myGPSPerfStats[index].gpsPitch = 0 + myGPSPerfStats[index].gpsRoll = 0 + myGPSPerfStats[index].gpsTurnRate = 0 + myGPSPerfStats[index].gpsLoadFactor = 1.0 + mySituation.GPSTurnRate = 0 + + // Output format:GPSAtttiude,seconds,nmeaTime,msg_type,GS,Course,Alt,VV,filtered_GS,filtered_course,turn rate,filtered_vv,pitch, roll,load_factor + buf := fmt.Sprintf("GPSAttitude,%.1f,%.2f,%s,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f\n", float64(stratuxClock.Milliseconds)/1000, myGPSPerfStats[index].nmeaTime, myGPSPerfStats[index].msgType, myGPSPerfStats[index].gsf, myGPSPerfStats[index].coursef, myGPSPerfStats[index].alt, myGPSPerfStats[index].vv, v_x/1.687810, headingAvg, myGPSPerfStats[index].gpsTurnRate, v_z, myGPSPerfStats[index].gpsPitch, myGPSPerfStats[index].gpsRoll, myGPSPerfStats[index].gpsLoadFactor) + if globalSettings.DEBUG { + log.Printf("%s", buf) // FIXME. Send to sqlite log or other file? + } + //replayLog(buf, MSGCLASS_AHRS) + + return true + } + + // Heading. Same method used for UBX and generic. + // First, walk through the PerfStats and parse only valid heading data. + //log.Printf("Raw heading data:") + for i := 0; i < length; i++ { + //log.Printf("%.1f,",myGPSPerfStats[i].coursef) + if myGPSPerfStats[i].coursef >= 0 { // negative values are used to flag invalid / unavailable course + tempHdg = append(tempHdg, float64(myGPSPerfStats[i].coursef)) + tempHdgTime = append(tempHdgTime, float64(myGPSPerfStats[i].nmeaTime)) + } + } + //log.Printf("\n") + //log.Printf("tempHdg: %v\n", tempHdg) + + // Next, unwrap the heading so we don't mess up the regression by fitting a line across the 0/360 deg discontinutiy + lengthHeading = len(tempHdg) + tempHdgUnwrapped = make([]float64, lengthHeading, lengthHeading) + tempRegWeights = make([]float64, lengthHeading, lengthHeading) + + if lengthHeading > 1 { + tempHdgUnwrapped[0] = tempHdg[0] + tempRegWeights[0] = triCubeWeight(center, halfwidth, tempHdgTime[0]) + for i := 1; i < lengthHeading; i++ { + tempRegWeights[i] = triCubeWeight(center, halfwidth, tempHdgTime[i]) + if math.Abs(tempHdg[i]-tempHdg[i-1]) < 180 { // case 1: if angle change is less than 180 degrees, use the same reference system + tempHdgUnwrapped[i] = tempHdgUnwrapped[i-1] + tempHdg[i] - tempHdg[i-1] + } else if tempHdg[i] > tempHdg[i-1] { // case 2: heading has wrapped around from NE to NW. Subtract 360 to keep consistent with previous data. + tempHdgUnwrapped[i] = tempHdgUnwrapped[i-1] + tempHdg[i] - tempHdg[i-1] - 360 + } else { // case 3: heading has wrapped around from NW to NE. Add 360 to keep consistent with previous data. + tempHdgUnwrapped[i] = tempHdgUnwrapped[i-1] + tempHdg[i] - tempHdg[i-1] + 360 + } + } + } else { // + if globalSettings.DEBUG { + log.Printf("GPS attitude: Can't calculate turn rate with less than two points.\n") + } + return false + } + + // Finally, calculate turn rate as the slope of the weighted linear regression of unwrapped heading. + slope, intercept, valid = linRegWeighted(tempHdgTime, tempHdgUnwrapped, tempRegWeights) + + if !valid { + log.Printf("GPS attitude: Regression error calculating turn rate") + return false + } else { + headingAvg = slope*float64(myGPSPerfStats[index].nmeaTime) + intercept + dh = slope // units are deg per sec; no conversion needed here + //log.Printf("Calculated heading and turn rate: %.3f degrees, %.3f deg/sec\n",headingAvg,dh) + } + + myGPSPerfStats[index].gpsTurnRate = dh + mySituation.GPSTurnRate = dh + + // pitch angle -- or to be more pedantic, glide / climb angle, since we're just looking a rise-over-run. + // roll angle, based on turn rate and ground speed. Only valid for coordinated flight. Differences between airspeed and groundspeed will trip this up. + if v_x > 20 { // reduce nuisance 'bounce' at low speeds. 20 ft/sec = 11.9 knots. + myGPSPerfStats[index].gpsPitch = math.Atan2(v_z, v_x) * 180.0 / math.Pi + + /* + Governing equations for roll calculations + + Physics tells us that + a_z = g (in steady-state flight -- climbing, descending, or level -- this is gravity. 9.81 m/s^2 or 32.2 ft/s^2) + a_c = v^2/r (centripetal acceleration) + + We don't know r. However, we do know the tangential velocity (v) and angular velocity (omega). Express omega in radians per unit time, and + + v = omega*r + + By substituting and rearranging terms: + + a_c = v^2 / (v / omega) + a_c = v*omega + + Free body diagram time! + + /| + a_r / | a_z + /__| + X a_c + \_________________ [For the purpose of this comment, " X" is an airplane in a 20 degree bank. Use your imagination, mkay?) + + Resultant acceleration a_r is what the wings feel; a_r/a_z = load factor. Anyway, trig out the bank angle: + + bank angle = atan(a_c/a_z) + = atan(v*omega/g) + + wing loading = sqrt(a_c^2 + a_z^2) / g + + */ + + g := 32.174 // ft-s^-2 + omega = radians(myGPSPerfStats[index].gpsTurnRate) // need radians/sec + a_c = v_x * omega + myGPSPerfStats[index].gpsRoll = math.Atan2(a_c, g) * 180 / math.Pi // output is degrees + myGPSPerfStats[index].gpsLoadFactor = math.Sqrt(a_c*a_c+g*g) / g + } else { + myGPSPerfStats[index].gpsPitch = 0 + myGPSPerfStats[index].gpsRoll = 0 + myGPSPerfStats[index].gpsLoadFactor = 1 + } + + // Output format:GPSAtttiude,seconds,nmeaTime,msg_type,GS,Course,Alt,VV,filtered_GS,filtered_course,turn rate,filtered_vv,pitch, roll,load_factor + buf := fmt.Sprintf("GPSAttitude,%.1f,%.2f,%s,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f,%0.3f\n", float64(stratuxClock.Milliseconds)/1000, myGPSPerfStats[index].nmeaTime, myGPSPerfStats[index].msgType, myGPSPerfStats[index].gsf, myGPSPerfStats[index].coursef, myGPSPerfStats[index].alt, myGPSPerfStats[index].vv, v_x/1.687810, headingAvg, myGPSPerfStats[index].gpsTurnRate, v_z, myGPSPerfStats[index].gpsPitch, myGPSPerfStats[index].gpsRoll, myGPSPerfStats[index].gpsLoadFactor) + if globalSettings.DEBUG { + log.Printf("%s", buf) // FIXME. Send to sqlite log or other file? + } + + //replayLog(buf, MSGCLASS_AHRS) + return true +} + func calculateNACp(accuracy float32) uint8 { ret := uint8(0) @@ -477,6 +866,12 @@ func processNMEALine(l string) (sentenceUsed bool) { mySituation.mu_GPS.Unlock() }() + // Local variables for GPS attitude estimation + thisGpsPerf := gpsPerf // write to myGPSPerfStats at end of function IFF + thisGpsPerf.coursef = -999.9 // default value of -999.9 indicates invalid heading to regression calculation + thisGpsPerf.stratuxTime = stratuxClock.Milliseconds // used for gross indexing + updateGPSPerf := false // change to true when position or vector info is read + l_valid, validNMEAcs := validateNMEAChecksum(l) if !validNMEAcs { log.Printf("GPS error. Invalid NMEA string: %s\n", l_valid) // remove log message once validation complete @@ -493,6 +888,15 @@ func processNMEALine(l string) (sentenceUsed bool) { return false } + // set the global GPS type to UBX as soon as we see our first (valid length) + // PUBX,01 position message, even if we don't have a fix + if globalStatus.GPS_detected_type != GPS_TYPE_UBX { + globalStatus.GPS_detected_type = GPS_TYPE_UBX + log.Printf("GPS detected: u-blox NMEA position message seen.\n") + } + + thisGpsPerf.msgType = x[0] + x[1] + tmpSituation := mySituation // If we decide to not use the data in this message, then don't make incomplete changes in mySituation. // Do the accuracy / quality fields first to prevent invalid position etc. from being sent downstream @@ -541,6 +945,7 @@ func processNMEALine(l string) (sentenceUsed bool) { } tmpSituation.LastFixSinceMidnightUTC = float32(3600*hr+60*min) + float32(sec) + thisGpsPerf.nmeaTime = tmpSituation.LastFixSinceMidnightUTC // field 3-4 = lat if len(x[3]) < 10 { @@ -582,6 +987,7 @@ func processNMEALine(l string) (sentenceUsed bool) { alt := float32(hae*3.28084) - tmpSituation.GeoidSep // convert to feet and offset by geoid separation tmpSituation.HeightAboveEllipsoid = float32(hae * 3.28084) // feet tmpSituation.Alt = alt + thisGpsPerf.alt = alt tmpSituation.LastFixLocalTime = stratuxClock.Time @@ -592,6 +998,7 @@ func processNMEALine(l string) (sentenceUsed bool) { } groundspeed = groundspeed * 0.540003 // convert to knots tmpSituation.GroundSpeed = uint16(groundspeed) + thisGpsPerf.gsf = float32(groundspeed) // field 12 = track, deg trueCourse := float32(0.0) @@ -603,7 +1010,9 @@ func processNMEALine(l string) (sentenceUsed bool) { trueCourse = float32(tc) setTrueCourse(uint16(groundspeed), tc) tmpSituation.TrueCourse = trueCourse + thisGpsPerf.coursef = float32(tc) } else { + thisGpsPerf.coursef = -999.9 // regression will skip negative values // Negligible movement. Don't update course, but do use the slow speed. // TO-DO: use average course over last n seconds? } @@ -615,6 +1024,7 @@ func processNMEALine(l string) (sentenceUsed bool) { return false } tmpSituation.GPSVertVel = float32(vv * -3.28084) // convert to ft/sec and positive = up + thisGpsPerf.vv = tmpSituation.GPSVertVel // field 14 = age of diff corrections @@ -627,6 +1037,19 @@ func processNMEALine(l string) (sentenceUsed bool) { // We've made it this far, so that means we've processed "everything" and can now make the change to mySituation. mySituation = tmpSituation + updateGPSPerf = true + if updateGPSPerf { + mySituation.mu_GPSPerf.Lock() + myGPSPerfStats = append(myGPSPerfStats, thisGpsPerf) + lenGPSPerfStats := len(myGPSPerfStats) + // log.Printf("GPSPerf array has %n elements. Contents are: %v\n",lenGPSPerfStats,myGPSPerfStats) + if lenGPSPerfStats > 299 { //30 seconds @ 10 Hz for UBX, 30 seconds @ 5 Hz for MTK or SIRF with 2x messages per 200 ms) + myGPSPerfStats = myGPSPerfStats[(lenGPSPerfStats - 299):] // remove the first n entries if more than 300 in the slice + } + + mySituation.mu_GPSPerf.Unlock() + } + return true } else if x[1] == "03" { // satellite status message. Only the first 20 satellites will be reported in this message for UBX firmware older than v3.0. Order seems to be GPS, then SBAS, then GLONASS. @@ -856,6 +1279,11 @@ func processNMEALine(l string) (sentenceUsed bool) { return false } + // use RMC / GGA message detection to sense "NMEA" type. + if globalStatus.GPS_detected_type == 0 { + globalStatus.GPS_detected_type = GPS_TYPE_NMEA + } + // Quality indicator. q, err1 := strconv.Atoi(x[6]) if err1 != nil { @@ -875,6 +1303,9 @@ func processNMEALine(l string) (sentenceUsed bool) { } tmpSituation.LastFixSinceMidnightUTC = float32(3600*hr+60*min) + float32(sec) + if globalStatus.GPS_detected_type != GPS_TYPE_UBX { + thisGpsPerf.nmeaTime = tmpSituation.LastFixSinceMidnightUTC + } // Latitude. if len(x[2]) < 4 { @@ -913,6 +1344,9 @@ func processNMEALine(l string) (sentenceUsed bool) { return false } tmpSituation.Alt = float32(alt * 3.28084) // Convert to feet. + if globalStatus.GPS_detected_type != GPS_TYPE_UBX { + thisGpsPerf.alt = float32(tmpSituation.Alt) + } // Geoid separation (Sep = HAE - MSL) // (needed for proper MSL offset on PUBX,00 altitudes) @@ -927,11 +1361,28 @@ func processNMEALine(l string) (sentenceUsed bool) { // Timestamp. tmpSituation.LastFixLocalTime = stratuxClock.Time + if globalStatus.GPS_detected_type != GPS_TYPE_UBX { + updateGPSPerf = true + thisGpsPerf.msgType = x[0] + } + // We've made it this far, so that means we've processed "everything" and can now make the change to mySituation. mySituation = tmpSituation + + if updateGPSPerf { + mySituation.mu_GPSPerf.Lock() + myGPSPerfStats = append(myGPSPerfStats, thisGpsPerf) + lenGPSPerfStats := len(myGPSPerfStats) + // log.Printf("GPSPerf array has %n elements. Contents are: %v\n",lenGPSPerfStats,myGPSPerfStats) + if lenGPSPerfStats > 299 { //30 seconds @ 10 Hz for UBX, 30 seconds @ 5 Hz for MTK or SIRF with 2x messages per 200 ms) + myGPSPerfStats = myGPSPerfStats[(lenGPSPerfStats - 299):] // remove the first n entries if more than 300 in the slice + } + mySituation.mu_GPSPerf.Unlock() + } + return true - } else if (x[0] == "GNRMC") || (x[0] == "GPRMC") { // Recommended Minimum data. FIXME: Is this needed anymore? + } else if (x[0] == "GNRMC") || (x[0] == "GPRMC") { // Recommended Minimum data. tmpSituation := mySituation // If we decide to not use the data in this message, then don't make incomplete changes in mySituation. //$GPRMC,123519,A,4807.038,N,01131.000,E,022.4,084.4,230394,003.1,W*6A @@ -953,6 +1404,11 @@ func processNMEALine(l string) (sentenceUsed bool) { return false } + // use RMC / GGA message detection to sense "NMEA" type. + if globalStatus.GPS_detected_type == 0 { + globalStatus.GPS_detected_type = GPS_TYPE_NMEA + } + if x[2] != "A" { // invalid fix tmpSituation.Quality = 0 // Just a note. return false @@ -969,6 +1425,9 @@ func processNMEALine(l string) (sentenceUsed bool) { return false } tmpSituation.LastFixSinceMidnightUTC = float32(3600*hr+60*min) + float32(sec) + if globalStatus.GPS_detected_type != GPS_TYPE_UBX { + thisGpsPerf.nmeaTime = tmpSituation.LastFixSinceMidnightUTC + } if len(x[9]) == 6 { // Date of Fix, i.e 191115 = 19 November 2015 UTC field 9 @@ -1024,26 +1483,50 @@ func processNMEALine(l string) (sentenceUsed bool) { return false } tmpSituation.GroundSpeed = uint16(groundspeed) + if globalStatus.GPS_detected_type != GPS_TYPE_UBX { + thisGpsPerf.gsf = float32(groundspeed) + } // ground track "True" (field 8) trueCourse := float32(0) tc, err := strconv.ParseFloat(x[8], 32) - if err != nil { + if err != nil && groundspeed > 3 { // some receivers return null COG at low speeds. Need to ignore this condition. return false } if groundspeed > 3 { // TO-DO: use average groundspeed over last n seconds to avoid random "jumps" trueCourse = float32(tc) setTrueCourse(uint16(groundspeed), tc) tmpSituation.TrueCourse = trueCourse + if globalStatus.GPS_detected_type != GPS_TYPE_UBX { + thisGpsPerf.coursef = float32(tc) + } } else { + if globalStatus.GPS_detected_type != GPS_TYPE_UBX { + thisGpsPerf.coursef = -999.9 + } // Negligible movement. Don't update course, but do use the slow speed. // TO-DO: use average course over last n seconds? } - + if globalStatus.GPS_detected_type != GPS_TYPE_UBX { + updateGPSPerf = true + thisGpsPerf.msgType = x[0] + } tmpSituation.LastGroundTrackTime = stratuxClock.Time // We've made it this far, so that means we've processed "everything" and can now make the change to mySituation. mySituation = tmpSituation + + if updateGPSPerf { + mySituation.mu_GPSPerf.Lock() + myGPSPerfStats = append(myGPSPerfStats, thisGpsPerf) + lenGPSPerfStats := len(myGPSPerfStats) + // log.Printf("GPSPerf array has %n elements. Contents are: %v\n",lenGPSPerfStats,myGPSPerfStats) + if lenGPSPerfStats > 299 { //30 seconds @ 10 Hz for UBX, 30 seconds @ 5 Hz for MTK or SIRF with 2x messages per 200 ms) + myGPSPerfStats = myGPSPerfStats[(lenGPSPerfStats - 299):] // remove the first n entries if more than 300 in the slice + } + mySituation.mu_GPSPerf.Unlock() + } + setDataLogTimeWithGPS(mySituation) return true @@ -1438,6 +1921,39 @@ func makeAHRSGDL90Report() { sendMsg(prepareMessage(msg), NETWORK_AHRS_GDL90, false) } +func gpsAttitudeSender() { + timer := time.NewTicker(100 * time.Millisecond) // ~10Hz update. + for { + <-timer.C + myGPSPerfStats = make([]gpsPerfStats, 0) // reinitialize statistics on disconnect / reconnect + for globalSettings.GPS_Enabled && globalStatus.GPS_connected /*&& globalSettings.GPSAttitude_Enabled*/ && !(globalSettings.AHRS_Enabled) { + <-timer.C + + if mySituation.Quality == 0 || !calcGPSAttitude() { + if globalSettings.DEBUG { + log.Printf("Could'nt calculate GPS-based attitude statistics\n") + } + } else { + mySituation.mu_GPSPerf.Lock() + index := len(myGPSPerfStats) - 1 + if index > 1 { + mySituation.Pitch = myGPSPerfStats[index].gpsPitch + mySituation.Roll = myGPSPerfStats[index].gpsRoll + mySituation.Gyro_heading = float64(mySituation.TrueCourse) + mySituation.LastAttitudeTime = stratuxClock.Time + //if globalSettings.ForeFlightSimMode == true { + // globalSettings.AHRS_GDL90_Enabled = false // both can't be simultaneously active + // makeFFAHRSSimReport() + //} else if globalSettings.AHRS_GDL90_Enabled == true { + //globalSettings.ForeFlightSimMode = false // both can't be simultaneoussly active + makeAHRSGDL90Report() + //} + } + mySituation.mu_GPSPerf.Unlock() + } + } + } +} func attitudeReaderSender() { timer := time.NewTicker(100 * time.Millisecond) // ~10Hz update. for globalStatus.RY835AI_connected && globalSettings.AHRS_Enabled { @@ -1462,7 +1978,9 @@ func attitudeReaderSender() { // if isGPSGroundTrackValid(), etc. // makeFFAHRSSimReport() // simultaneous use of GDL90 and FFSIM not supported in FF 7.5.1 or later. Function definition will be kept for AHRS debugging and future workarounds. + //if globalSettings.AHRS_GDL90_Enabled == true { makeAHRSGDL90Report() + //} mySituation.mu_Attitude.Unlock() } @@ -1563,6 +2081,7 @@ func initAHRS() error { func pollRY835AI() { readyToInitGPS = true //TO-DO: Implement more robust method (channel control) to kill zombie serial readers timer := time.NewTicker(4 * time.Second) + go gpsAttitudeSender() for { <-timer.C // GPS enabled, was not connected previously? @@ -1585,6 +2104,7 @@ func pollRY835AI() { func initRY835AI() { mySituation.mu_GPS = &sync.Mutex{} + mySituation.mu_GPSPerf = &sync.Mutex{} mySituation.mu_Attitude = &sync.Mutex{} satelliteMutex = &sync.Mutex{} Satellites = make(map[string]SatelliteInfo) From 3d4dec80a4a6ef73882835cbbe1316a9a968c61c Mon Sep 17 00:00:00 2001 From: AvSquirrel Date: Wed, 8 Jun 2016 00:10:17 +0000 Subject: [PATCH 02/17] Add GPS attitude logging to sqlite log --- main/datalog.go | 7 +++++++ main/gen_gdl90.go | 3 +++ main/ry835ai.go | 10 ++++++---- 3 files changed, 16 insertions(+), 4 deletions(-) diff --git a/main/datalog.go b/main/datalog.go index eda48cd50..621400fa5 100644 --- a/main/datalog.go +++ b/main/datalog.go @@ -474,6 +474,7 @@ func dataLog() { makeTable(msg{}, "messages", db) makeTable(esmsg{}, "es_messages", db) makeTable(Dump1090TermMessage{}, "dump1090_terminal", db) + makeTable(gpsPerfStats{}, "gps_attitude", db) makeTable(StratuxStartup{}, "startup", db) } @@ -567,6 +568,12 @@ func logESMsg(m esmsg) { } } +func logGPSAttitude(gpsPerf gpsPerfStats) { + if globalSettings.ReplayLog && isDataLogReady() { + dataLogChan <- DataLogRow{tbl: "gps_attitude", data: gpsPerf} + } +} + func logDump1090TermMessage(m Dump1090TermMessage) { if globalSettings.DEBUG && globalSettings.ReplayLog && isDataLogReady() { dataLogChan <- DataLogRow{tbl: "dump1090_terminal", data: m} diff --git a/main/gen_gdl90.go b/main/gen_gdl90.go index 5ba0d3c76..dfdd1ea0e 100644 --- a/main/gen_gdl90.go +++ b/main/gen_gdl90.go @@ -1218,6 +1218,9 @@ func main() { globalStatus.HardwareBuild = "FlightBox" debugLogf = debugLog_FB dataLogFilef = dataLogFile_FB + } else { + debugLogf = debugLog + dataLogFilef = dataLogFile } // replayESFilename := flag.String("eslog", "none", "ES Log filename") diff --git a/main/ry835ai.go b/main/ry835ai.go index 4007d5e9d..f0c3af4cd 100644 --- a/main/ry835ai.go +++ b/main/ry835ai.go @@ -659,7 +659,8 @@ func calcGPSAttitude() bool { log.Printf("GPS attitude: Error calculating speed regression from NMEA RMC position messages") return false } else { - v_x = (slope*float64(myGPSPerfStats[index].nmeaTime) + intercept) * 1.687810 // units are knots, converted to feet/sec + v_x = (slope*float64(myGPSPerfStats[index].nmeaTime) + intercept) * 1.687810 // units are knots, converted to feet/sec + log.Printf("Avg speed %f calculated from %d RMC messages\n", v_x, lengthSpeed) // FIXME } } @@ -685,8 +686,8 @@ func calcGPSAttitude() bool { log.Printf("GPS attitude: Error calculating vertical speed regression from NMEA GGA messages") return false } else { - v_z = slope // units are feet/sec - + v_z = slope // units are feet/sec + log.Printf("Avg VV %f calculated from %d GGA messages\n", v_z, lengthSpeed) // FIXME } } @@ -708,6 +709,7 @@ func calcGPSAttitude() bool { if globalSettings.DEBUG { log.Printf("%s", buf) // FIXME. Send to sqlite log or other file? } + logGPSAttitude(myGPSPerfStats[index]) //replayLog(buf, MSGCLASS_AHRS) return true @@ -820,7 +822,7 @@ func calcGPSAttitude() bool { if globalSettings.DEBUG { log.Printf("%s", buf) // FIXME. Send to sqlite log or other file? } - + logGPSAttitude(myGPSPerfStats[index]) //replayLog(buf, MSGCLASS_AHRS) return true } From 065836ef4cea4fd84b98bba2aab10b18b84d325e Mon Sep 17 00:00:00 2001 From: AvSquirrel Date: Wed, 8 Jun 2016 01:47:19 +0000 Subject: [PATCH 03/17] Tweak filter width. Comment out a couple of debug messages --- main/ry835ai.go | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/main/ry835ai.go b/main/ry835ai.go index f0c3af4cd..fb1e4fd65 100644 --- a/main/ry835ai.go +++ b/main/ry835ai.go @@ -570,7 +570,7 @@ func calcGPSAttitude() bool { var lengthHeading, lengthSpeed int center := float64(myGPSPerfStats[index].nmeaTime) // current time for calculating regression weights - halfwidth := float64(2.0) // width of regression evaluation window. Default of 2.0 seconds for 5 Hz sampling; can increase to 5 sec @ 1 Hz + halfwidth := float64(1.4) // width of regression evaluation window. Default of 1.4 seconds for 5 Hz sampling; can increase to 3.5 sec @ 1 Hz // frequency detection tempSpeedTime = make([]float64, 0) @@ -586,16 +586,16 @@ func calcGPSAttitude() bool { if globalSettings.DEBUG { log.Printf("GPS attitude: Average delta time is %.2f s (%.1f Hz)\n", dt_avg, 1/dt_avg) } - halfwidth = 10 * dt_avg + halfwidth = 7 * dt_avg } else { if globalSettings.DEBUG { log.Printf("GPS attitude: Couldn't determine sample rate\n") } - halfwidth = 3.0 + halfwidth = 3.5 } - if halfwidth > 5 { - halfwidth = 5 // limit calculation window to 5 seconds of data for 2 Hz or slower samples + if halfwidth > 3.5 { + halfwidth = 3.5 // limit calculation window to 3.5 seconds of data for 1 Hz or slower samples } if globalStatus.GPS_detected_type == GPS_TYPE_UBX { // UBX reports vertical speed, so we can just walk through all of the PUBX messages in order @@ -659,8 +659,8 @@ func calcGPSAttitude() bool { log.Printf("GPS attitude: Error calculating speed regression from NMEA RMC position messages") return false } else { - v_x = (slope*float64(myGPSPerfStats[index].nmeaTime) + intercept) * 1.687810 // units are knots, converted to feet/sec - log.Printf("Avg speed %f calculated from %d RMC messages\n", v_x, lengthSpeed) // FIXME + v_x = (slope*float64(myGPSPerfStats[index].nmeaTime) + intercept) * 1.687810 // units are knots, converted to feet/sec + //log.Printf("Avg speed %f calculated from %d RMC messages\n", v_x, lengthSpeed) // DEBUG } } @@ -686,8 +686,8 @@ func calcGPSAttitude() bool { log.Printf("GPS attitude: Error calculating vertical speed regression from NMEA GGA messages") return false } else { - v_z = slope // units are feet/sec - log.Printf("Avg VV %f calculated from %d GGA messages\n", v_z, lengthSpeed) // FIXME + v_z = slope // units are feet/sec + //log.Printf("Avg VV %f calculated from %d GGA messages\n", v_z, lengthSpeed) // DEBUG } } From fbc2ee16d33deff4946ec6d3b05115c3a2c9d0aa Mon Sep 17 00:00:00 2001 From: AvSquirrel Date: Wed, 8 Jun 2016 02:52:00 +0000 Subject: [PATCH 04/17] Add toggle for GDL90 AHRS output. Use GDL90 AHRS toggle for FF compatibility instead of disabling AHRS hardware. --- main/managementinterface.go | 2 ++ main/network.go | 8 +++--- main/ry835ai.go | 12 ++++++--- web/plates/settings.html | 52 ++++++++++++++++++++++++++++++++++++- 4 files changed, 65 insertions(+), 9 deletions(-) diff --git a/main/managementinterface.go b/main/managementinterface.go index 5900fe19d..bcf1b623a 100644 --- a/main/managementinterface.go +++ b/main/managementinterface.go @@ -219,6 +219,8 @@ func handleSettingsSetRequest(w http.ResponseWriter, r *http.Request) { globalSettings.GPS_Enabled = val.(bool) case "AHRS_Enabled": globalSettings.AHRS_Enabled = val.(bool) + case "AHRS_GDL90_Enabled": + globalSettings.AHRS_GDL90_Enabled = val.(bool) case "DEBUG": globalSettings.DEBUG = val.(bool) case "DisplayTrafficSource": diff --git a/main/network.go b/main/network.go index b327d9cc5..eaf02e116 100644 --- a/main/network.go +++ b/main/network.go @@ -457,7 +457,7 @@ func networkStatsCounter() { /* ffMonitor(). Watches for "i-want-to-play-ffm-udp", "i-can-play-ffm-udp", and "i-cannot-play-ffm-udp" UDP messages broadcasted on - port 50113. Tags the client, issues a warning, and disables AHRS. + port 50113. Tags the client, issues a warning, and disables AHRS GDL90 output. */ @@ -496,10 +496,10 @@ func ffMonitor() { } if strings.HasPrefix(s, "i-want-to-play-ffm-udp") || strings.HasPrefix(s, "i-can-play-ffm-udp") || strings.HasPrefix(s, "i-cannot-play-ffm-udp") { p.FFCrippled = true - //FIXME: AHRS doesn't need to be disabled globally, just messages need to be filtered. - globalSettings.AHRS_Enabled = false + //FIXME: AHRS output doesn't need to be disabled globally, just on the ForeFlight client IPs. + globalSettings.AHRS_GDL90_Enabled = false if !ff_warned { - e := errors.New("Stratux is not supported by your EFB app. Your EFB app is known to regularly make changes that cause compatibility issues with Stratux. See the README for a list of apps that officially support Stratux.") + e := errors.New("Stratux AHRS is not currently supported by ForeFlight, and AHRS output has been disabled for all connected clients. See the README for a list of apps that officially support Stratux.") addSystemError(e) ff_warned = true } diff --git a/main/ry835ai.go b/main/ry835ai.go index fb1e4fd65..373eca6c3 100644 --- a/main/ry835ai.go +++ b/main/ry835ai.go @@ -1948,8 +1948,12 @@ func gpsAttitudeSender() { // makeFFAHRSSimReport() //} else if globalSettings.AHRS_GDL90_Enabled == true { //globalSettings.ForeFlightSimMode = false // both can't be simultaneoussly active - makeAHRSGDL90Report() + //makeAHRSGDL90Report() //} + + if globalSettings.AHRS_GDL90_Enabled == true { + makeAHRSGDL90Report() + } } mySituation.mu_GPSPerf.Unlock() } @@ -1980,9 +1984,9 @@ func attitudeReaderSender() { // if isGPSGroundTrackValid(), etc. // makeFFAHRSSimReport() // simultaneous use of GDL90 and FFSIM not supported in FF 7.5.1 or later. Function definition will be kept for AHRS debugging and future workarounds. - //if globalSettings.AHRS_GDL90_Enabled == true { - makeAHRSGDL90Report() - //} + if globalSettings.AHRS_GDL90_Enabled == true { + makeAHRSGDL90Report() + } mySituation.mu_Attitude.Unlock() } diff --git a/web/plates/settings.html b/web/plates/settings.html index 40922d925..15a1736b3 100755 --- a/web/plates/settings.html +++ b/web/plates/settings.html @@ -23,7 +23,7 @@
- +
@@ -64,6 +64,12 @@
Configuration
+
+ +
+ +
+
@@ -188,6 +194,50 @@
+ + + +
From c34c107f2316612df383644b371fcd7c68cbde00 Mon Sep 17 00:00:00 2001 From: AvSquirrel Date: Wed, 8 Jun 2016 03:20:43 +0000 Subject: [PATCH 05/17] Comment cleanup. Remove bloat from UI status page. --- main/gen_gdl90.go | 4 +--- web/plates/status.html | 34 ++++++++++++++++++++++------------ 2 files changed, 23 insertions(+), 15 deletions(-) diff --git a/main/gen_gdl90.go b/main/gen_gdl90.go index dfdd1ea0e..60e91ac90 100644 --- a/main/gen_gdl90.go +++ b/main/gen_gdl90.go @@ -963,7 +963,6 @@ type settings struct { OwnshipModeS string WatchList string AHRS_GDL90_Enabled bool - GPSAttitude_Enabled bool } type status struct { @@ -1017,7 +1016,6 @@ func defaultSettings() { globalSettings.ReplayLog = false //TODO: 'true' for debug builds. globalSettings.OwnshipModeS = "F00000" globalSettings.AHRS_GDL90_Enabled = false - globalSettings.GPSAttitude_Enabled = false } func readSettings() { @@ -1218,7 +1216,7 @@ func main() { globalStatus.HardwareBuild = "FlightBox" debugLogf = debugLog_FB dataLogFilef = dataLogFile_FB - } else { + } else { // if not using the FlightBox config, use "normal" log file locations debugLogf = debugLog dataLogFilef = dataLogFile } diff --git a/web/plates/status.html b/web/plates/status.html index aadf4f9e0..186f051ff 100755 --- a/web/plates/status.html +++ b/web/plates/status.html @@ -3,16 +3,6 @@

Version: {{Version}} ({{Build}})

-
- Errors -
-
-
    -
  • - {{err}} -
  • -
-
Status {{ConnectState}} @@ -93,8 +83,8 @@ {{CPUTemp}}
- -
+ + + + + + +
+
+ Errors
+
+
    +
  • + {{err}} +
  • +
+
+ + + + + From 7b02ff0b705cd40fb6a8c5d2afec1f04cf68a15b Mon Sep 17 00:00:00 2001 From: AvSquirrel Date: Wed, 8 Jun 2016 03:38:45 +0000 Subject: [PATCH 06/17] Update settings.js for AHRS GDL90 toggle --- web/plates/js/settings.js | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/web/plates/js/settings.js b/web/plates/js/settings.js index ef82097c6..698c80287 100755 --- a/web/plates/js/settings.js +++ b/web/plates/js/settings.js @@ -6,7 +6,7 @@ function SettingsCtrl($rootScope, $scope, $state, $location, $window, $http) { $scope.$parent.helppage = 'plates/settings-help.html'; - var toggles = ['UAT_Enabled', 'ES_Enabled', 'GPS_Enabled', 'AHRS_Enabled', 'DisplayTrafficSource', 'DEBUG', 'ReplayLog']; + var toggles = ['UAT_Enabled', 'ES_Enabled', 'GPS_Enabled', 'AHRS_Enabled', 'AHRS_GDL90_Enabled', 'DisplayTrafficSource', 'DEBUG', 'ReplayLog']; var settings = {}; for (i = 0; i < toggles.length; i++) { settings[toggles[i]] = undefined; @@ -21,6 +21,7 @@ function SettingsCtrl($rootScope, $scope, $state, $location, $window, $http) { $scope.ES_Enabled = settings.ES_Enabled; $scope.GPS_Enabled = settings.GPS_Enabled; $scope.AHRS_Enabled = settings.AHRS_Enabled; + $scope.AHRS_GDL90_Enabled = settings.AHRS_GDL90_Enabled; $scope.DisplayTrafficSource = settings.DisplayTrafficSource; $scope.DEBUG = settings.DEBUG; $scope.ReplayLog = settings.ReplayLog; From c5f2193b8728d0fce060a1cfd93b1bca6e690b12 Mon Sep 17 00:00:00 2001 From: AvSquirrel Date: Sun, 19 Jun 2016 03:12:43 +0000 Subject: [PATCH 07/17] Change FF error message back per cyoung request --- main/network.go | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/main/network.go b/main/network.go index eaf02e116..835385e51 100644 --- a/main/network.go +++ b/main/network.go @@ -499,7 +499,7 @@ func ffMonitor() { //FIXME: AHRS output doesn't need to be disabled globally, just on the ForeFlight client IPs. globalSettings.AHRS_GDL90_Enabled = false if !ff_warned { - e := errors.New("Stratux AHRS is not currently supported by ForeFlight, and AHRS output has been disabled for all connected clients. See the README for a list of apps that officially support Stratux.") + e := errors.New("Stratux is not supported by your EFB app. Your EFB app is known to regularly make changes that cause compatibility issues with Stratux. See the README for a list of apps that officially support Stratux.") addSystemError(e) ff_warned = true } From 6c50a963473e869b1c39ab06428348e451468b3d Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Thu, 17 Nov 2016 18:18:16 -0500 Subject: [PATCH 08/17] Remove 'AHRS_GDL90_Enabled' option. --- main/gen_gdl90.go | 2 -- main/managementinterface.go | 2 -- main/network.go | 1 - main/ry835ai.go | 18 ++++-------------- web/plates/js/settings.js | 3 +-- web/plates/settings.html | 6 ------ 6 files changed, 5 insertions(+), 27 deletions(-) diff --git a/main/gen_gdl90.go b/main/gen_gdl90.go index d6fc3d155..a9cac821e 100755 --- a/main/gen_gdl90.go +++ b/main/gen_gdl90.go @@ -1001,7 +1001,6 @@ type settings struct { OwnshipModeS string WatchList string DeveloperMode bool - AHRS_GDL90_Enabled bool } type status struct { @@ -1066,7 +1065,6 @@ func defaultSettings() { globalSettings.ReplayLog = false //TODO: 'true' for debug builds. globalSettings.OwnshipModeS = "F00000" globalSettings.DeveloperMode = false - globalSettings.AHRS_GDL90_Enabled = false } func readSettings() { diff --git a/main/managementinterface.go b/main/managementinterface.go index 770451300..6aa28f82c 100755 --- a/main/managementinterface.go +++ b/main/managementinterface.go @@ -276,8 +276,6 @@ func handleSettingsSetRequest(w http.ResponseWriter, r *http.Request) { globalSettings.GPS_Enabled = val.(bool) case "AHRS_Enabled": globalSettings.AHRS_Enabled = val.(bool) - case "AHRS_GDL90_Enabled": - globalSettings.AHRS_GDL90_Enabled = val.(bool) case "DEBUG": globalSettings.DEBUG = val.(bool) case "DisplayTrafficSource": diff --git a/main/network.go b/main/network.go index 289170005..d33b7e0fb 100644 --- a/main/network.go +++ b/main/network.go @@ -597,7 +597,6 @@ func ffMonitor() { if strings.HasPrefix(s, "i-want-to-play-ffm-udp") || strings.HasPrefix(s, "i-can-play-ffm-udp") || strings.HasPrefix(s, "i-cannot-play-ffm-udp") { p.FFCrippled = true //FIXME: AHRS output doesn't need to be disabled globally, just on the ForeFlight client IPs. - globalSettings.AHRS_GDL90_Enabled = false if !ff_warned { e := errors.New("Stratux is not supported by your EFB app. Your EFB app is known to regularly make changes that cause compatibility issues with Stratux. See the README for a list of apps that officially support Stratux.") addSystemError(e) diff --git a/main/ry835ai.go b/main/ry835ai.go index ab5c7ebb4..19f21fee2 100644 --- a/main/ry835ai.go +++ b/main/ry835ai.go @@ -1966,23 +1966,15 @@ func gpsAttitudeSender() { mySituation.Roll = myGPSPerfStats[index].gpsRoll mySituation.Gyro_heading = float64(mySituation.TrueCourse) mySituation.LastAttitudeTime = stratuxClock.Time - //if globalSettings.ForeFlightSimMode == true { - // globalSettings.AHRS_GDL90_Enabled = false // both can't be simultaneously active - // makeFFAHRSSimReport() - //} else if globalSettings.AHRS_GDL90_Enabled == true { - //globalSettings.ForeFlightSimMode = false // both can't be simultaneoussly active - //makeAHRSGDL90Report() - //} - - if globalSettings.AHRS_GDL90_Enabled == true { - makeAHRSGDL90Report() - } + + makeAHRSGDL90Report() } mySituation.mu_GPSPerf.Unlock() } } } } + func attitudeReaderSender() { timer := time.NewTicker(100 * time.Millisecond) // ~10Hz update. for globalStatus.RY835AI_connected && globalSettings.AHRS_Enabled { @@ -2007,9 +1999,7 @@ func attitudeReaderSender() { // if isGPSGroundTrackValid(), etc. // makeFFAHRSSimReport() // simultaneous use of GDL90 and FFSIM not supported in FF 7.5.1 or later. Function definition will be kept for AHRS debugging and future workarounds. - if globalSettings.AHRS_GDL90_Enabled == true { - makeAHRSGDL90Report() - } + makeAHRSGDL90Report() mySituation.mu_Attitude.Unlock() } diff --git a/web/plates/js/settings.js b/web/plates/js/settings.js index c974cb7ce..52b180995 100755 --- a/web/plates/js/settings.js +++ b/web/plates/js/settings.js @@ -6,7 +6,7 @@ function SettingsCtrl($rootScope, $scope, $state, $location, $window, $http) { $scope.$parent.helppage = 'plates/settings-help.html'; - var toggles = ['UAT_Enabled', 'ES_Enabled', 'Ping_Enabled', 'GPS_Enabled', 'AHRS_GDL90_Enabled', 'AHRS_Enabled', 'DisplayTrafficSource', 'DEBUG', 'ReplayLog']; + var toggles = ['UAT_Enabled', 'ES_Enabled', 'Ping_Enabled', 'GPS_Enabled', 'AHRS_Enabled', 'DisplayTrafficSource', 'DEBUG', 'ReplayLog']; var settings = {}; for (i = 0; i < toggles.length; i++) { settings[toggles[i]] = undefined; @@ -27,7 +27,6 @@ function SettingsCtrl($rootScope, $scope, $state, $location, $window, $http) { $scope.Ping_Enabled = settings.Ping_Enabled; $scope.GPS_Enabled = settings.GPS_Enabled; $scope.AHRS_Enabled = settings.AHRS_Enabled; - $scope.AHRS_GDL90_Enabled = settings.AHRS_GDL90_Enabled; $scope.DisplayTrafficSource = settings.DisplayTrafficSource; $scope.DEBUG = settings.DEBUG; $scope.ReplayLog = settings.ReplayLog; diff --git a/web/plates/settings.html b/web/plates/settings.html index 76803c372..ef3c2a888 100755 --- a/web/plates/settings.html +++ b/web/plates/settings.html @@ -70,12 +70,6 @@
Configuration
-
- -
- -
-
From eaea0178c2691b98cc5e939371a3b737c40fa551 Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Thu, 17 Nov 2016 18:19:00 -0500 Subject: [PATCH 09/17] Remove outdated FF compatibility warning. --- web/plates/settings.html | 20 -------------------- 1 file changed, 20 deletions(-) diff --git a/web/plates/settings.html b/web/plates/settings.html index ef3c2a888..5387c4a7a 100755 --- a/web/plates/settings.html +++ b/web/plates/settings.html @@ -237,26 +237,6 @@
-
From a47b1483c7be52de1d13fa900b56f2ec15d85e48 Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Thu, 17 Nov 2016 18:26:13 -0500 Subject: [PATCH 10/17] Remove linux-mpu9150 submodule. --- .gitmodules | 3 --- 1 file changed, 3 deletions(-) diff --git a/.gitmodules b/.gitmodules index a89fd9951..13a52a3c2 100644 --- a/.gitmodules +++ b/.gitmodules @@ -1,6 +1,3 @@ -[submodule "linux-mpu9150"] - path = linux-mpu9150 - url = git://github.com/cyoung/linux-mpu9150 [submodule "dump1090"] path = dump1090 url = https://github.com/AvSquirrel/dump1090 From bc830b0a4e2c929545c71330ff4977b676e00adb Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Thu, 17 Nov 2016 18:49:18 -0500 Subject: [PATCH 11/17] Remove mpu6050 references. --- Makefile | 8 +- main/gen_gdl90.go | 7 +- main/ry835ai.go | 69 ++---------- mpu6050/mpu6050.go | 183 -------------------------------- notes/app-vendor-integration.md | 1 - test/sensortest.go | 36 ------- 6 files changed, 13 insertions(+), 291 deletions(-) delete mode 100644 mpu6050/mpu6050.go delete mode 100644 test/sensortest.go diff --git a/Makefile b/Makefile index cfa218fb5..2ec2e2e8c 100644 --- a/Makefile +++ b/Makefile @@ -9,11 +9,10 @@ endif all: make xdump978 make xdump1090 - make xlinux-mpu9150 make xgen_gdl90 xgen_gdl90: - go get -t -d -v ./main ./test ./linux-mpu9150/mpu ./godump978 ./mpu6050 ./uatparse + go get -t -d -v ./main ./test ./godump978 ./mpu6050 ./uatparse go build $(BUILDINFO) -p 4 main/gen_gdl90.go main/traffic.go main/ry835ai.go main/network.go main/managementinterface.go main/sdr.go main/ping.go main/uibroadcast.go main/monotonic.go main/datalog.go main/equations.go xdump1090: @@ -24,10 +23,6 @@ xdump978: cd dump978 && make lib sudo cp -f ./libdump978.so /usr/lib/libdump978.so -xlinux-mpu9150: - git submodule update --init - cd linux-mpu9150 && make -f Makefile-native-shared - .PHONY: test test: make -C test @@ -53,4 +48,3 @@ clean: rm -f gen_gdl90 libdump978.so cd dump1090 && make clean cd dump978 && make clean - rm -f linux-mpu9150/*.o linux-mpu9150/*.so diff --git a/main/gen_gdl90.go b/main/gen_gdl90.go index a9cac821e..9f5c140af 100755 --- a/main/gen_gdl90.go +++ b/main/gen_gdl90.go @@ -438,10 +438,8 @@ func makeStratuxStatus() []byte { // Connected hardware: number of radios. msg[15] = msg[15] | (byte(globalStatus.Devices) & 0x3) - // Connected hardware: RY835AI. - if globalStatus.RY835AI_connected { - msg[15] = msg[15] | (1 << 2) - } + // Connected hardware. + // RY835AI: msg[15] = msg[15] | (1 << 2) // Number of GPS satellites locked. msg[16] = byte(globalStatus.GPS_satellites_locked) @@ -1024,7 +1022,6 @@ type status struct { GPS_connected bool GPS_solution string GPS_detected_type uint - RY835AI_connected bool Uptime int64 UptimeClock time.Time CPUTemp float32 diff --git a/main/ry835ai.go b/main/ry835ai.go index 19f21fee2..04de5ae01 100644 --- a/main/ry835ai.go +++ b/main/ry835ai.go @@ -27,8 +27,6 @@ import ( "os" "os/exec" - - "../mpu6050" ) const ( @@ -88,7 +86,7 @@ type SituationData struct { Pressure_alt float64 LastTempPressTime time.Time - // From MPU6050 accel/gyro. + // From AHRS source. Pitch float64 Roll float64 Gyro_heading float64 @@ -464,10 +462,11 @@ func validateNMEAChecksum(s string) (string, bool) { //TODO: Some more robust checking above current and last speed. //TODO: Dynamic adjust for gain based on groundspeed func setTrueCourse(groundSpeed uint16, trueCourse float64) { - if myMPU6050 != nil && globalStatus.RY835AI_connected && globalSettings.AHRS_Enabled { - if mySituation.GroundSpeed >= 7 && groundSpeed >= 7 { - myMPU6050.ResetHeading(trueCourse, 0.10) - } + if mySituation.GroundSpeed >= 7 && groundSpeed >= 7 { + // This was previously used to filter small ground speed spikes caused by GPS position drift. + // It was passed to the previous AHRS heading calculator. Currently unused, maybe in the future it will be. + _ = trueCourse + _ = groundSpeed } } @@ -1844,7 +1843,6 @@ func gpsSerialReader() { var i2cbus embd.I2CBus var myBMP180 *bmp180.BMP180 -var myMPU6050 *mpu6050.MPU6050 func readBMP180() (float64, float64, error) { // ºCelsius, Meters temp, err := myBMP180.Temperature() @@ -1859,21 +1857,11 @@ func readBMP180() (float64, float64, error) { // ºCelsius, Meters return temp, altitude, nil } -func readMPU6050() (float64, float64, error) { //TODO: error checking. - pitch, roll := myMPU6050.PitchAndRoll() - return pitch, roll, nil -} - func initBMP180() error { myBMP180 = bmp180.New(i2cbus) //TODO: error checking. return nil } -func initMPU6050() error { - myMPU6050 = mpu6050.New() //TODO: error checking. - return nil -} - func initI2C() error { i2cbus = embd.NewI2CBus(1) //TODO: error checking. return nil @@ -1975,37 +1963,6 @@ func gpsAttitudeSender() { } } -func attitudeReaderSender() { - timer := time.NewTicker(100 * time.Millisecond) // ~10Hz update. - for globalStatus.RY835AI_connected && globalSettings.AHRS_Enabled { - <-timer.C - // Read pitch and roll. - pitch, roll, err_mpu6050 := readMPU6050() - - if err_mpu6050 != nil { - log.Printf("readMPU6050(): %s\n", err_mpu6050.Error()) - globalStatus.RY835AI_connected = false - break - } - - mySituation.mu_Attitude.Lock() - - mySituation.Pitch = pitch - mySituation.Roll = roll - mySituation.Gyro_heading = myMPU6050.Heading() //FIXME. Experimental. - mySituation.LastAttitudeTime = stratuxClock.Time - - // Send, if valid. - // if isGPSGroundTrackValid(), etc. - - // makeFFAHRSSimReport() // simultaneous use of GDL90 and FFSIM not supported in FF 7.5.1 or later. Function definition will be kept for AHRS debugging and future workarounds. - makeAHRSGDL90Report() - - mySituation.mu_Attitude.Unlock() - } - globalStatus.RY835AI_connected = false -} - /* updateConstellation(): Periodic cleanup and statistics calculation for 'Satellites' data structure. Calling functions must protect this in a satelliteMutex. @@ -2081,18 +2038,12 @@ func initAHRS() error { if err := initI2C(); err != nil { // I2C bus. return err } - if err := initBMP180(); err != nil { // I2C temperature and pressure altitude. - i2cbus.Close() - return err - } - if err := initMPU6050(); err != nil { // I2C accel/gyro. - i2cbus.Close() - myBMP180.Close() + + if err := initBMP180(); err == nil { // I2C temperature and pressure altitude. + go tempAndPressureReader() + } else { return err } - globalStatus.RY835AI_connected = true - go attitudeReaderSender() - go tempAndPressureReader() return nil } diff --git a/mpu6050/mpu6050.go b/mpu6050/mpu6050.go deleted file mode 100644 index 1661899b2..000000000 --- a/mpu6050/mpu6050.go +++ /dev/null @@ -1,183 +0,0 @@ -// Package mpu6050 allows interfacing with InvenSense mpu6050 barometric pressure sensor. This sensor -// has the ability to provided compensated temperature and pressure readings. -package mpu6050 - -import ( - "../linux-mpu9150/mpu" - "log" - "math" - "time" -) - -//https://www.olimex.com/Products/Modules/Sensors/MOD-MPU6050/resources/RM-MPU-60xxA_rev_4.pdf -const ( - pollDelay = 98 * time.Millisecond // ~10Hz -) - -// MPU6050 represents a InvenSense MPU6050 sensor. -type MPU6050 struct { - Poll time.Duration - - started bool - - pitch float64 - roll float64 - - // Calibration variables. - calibrated bool - pitch_history []float64 - roll_history []float64 - pitch_resting float64 - roll_resting float64 - - // For tracking heading (mixing GPS track and the gyro output). - heading float64 // Current heading. - gps_track float64 // Last reading directly from the gyro for comparison with current heading. - gps_track_valid bool - heading_correction float64 - - quit chan struct{} -} - -// New returns a handle to a MPU6050 sensor. -func New() *MPU6050 { - n := &MPU6050{Poll: pollDelay} - n.StartUp() - return n -} - -func (d *MPU6050) StartUp() error { - mpu_sample_rate := 10 // 10 Hz read rate of hardware IMU - yaw_mix_factor := 0 // must be zero if no magnetometer - mpu.InitMPU(mpu_sample_rate, yaw_mix_factor) - - d.pitch_history = make([]float64, 0) - d.roll_history = make([]float64, 0) - - d.started = true - d.Run() - - return nil -} - -/* - -func (d *MPU6050) calibrate() { - //TODO: Error checking to make sure that the histories are extensive enough to be significant. - //TODO: Error checking to do continuous calibrations. - pitch_adjust := float64(0) - for _, v := range d.pitch_history { - pitch_adjust = pitch_adjust + v - } - pitch_adjust = pitch_adjust / float64(len(d.pitch_history)) - d.pitch_resting = pitch_adjust - - roll_adjust := float64(0) - for _, v := range d.roll_history { - roll_adjust = roll_adjust + v - } - roll_adjust = roll_adjust / float64(len(d.roll_history)) - d.roll_resting = roll_adjust - log.Printf("calibrate: pitch %f, roll %f\n", pitch_adjust, roll_adjust) - d.calibrated = true -} - -*/ - -func normalizeHeading(h float64) float64 { - for h < float64(0.0) { - h = h + float64(360.0) - } - for h >= float64(360.0) { - h = h - float64(360.0) - } - return h -} - -func (d *MPU6050) getMPUData() { - pr, rr, hr, err := mpu.ReadMPU() - - // Convert from radians to degrees. - pitch := float64(pr) * (float64(180.0) / math.Pi) - roll := float64(-rr) * (float64(180.0) / math.Pi) - heading := float64(hr) * (float64(180.0) / math.Pi) - if heading < float64(0.0) { - heading = float64(360.0) + heading - } - - if err == nil { - d.pitch = pitch - d.roll = roll - - // Heading is raw value off the IMU. Without mag compass fusion, need to apply correction bias. - // Amount of correction is set by ResetHeading() -- doesn't necessarily have to be based off GPS. - d.heading = normalizeHeading((heading - d.heading_correction)) - - } else { - // log.Printf("mpu6050.calculatePitchAndRoll(): mpu.ReadMPU() err: %s\n", err.Error()) - } -} - -// Temperature returns the current temperature reading. -func (d *MPU6050) PitchAndRoll() (float64, float64) { - return (d.pitch - d.pitch_resting), (d.roll - d.roll_resting) -} - -func (d *MPU6050) Heading() float64 { - return d.heading -} - -func (d *MPU6050) Run() { - time.Sleep(d.Poll) - go func() { - d.quit = make(chan struct{}) - timer := time.NewTicker(d.Poll) - // calibrateTimer := time.NewTicker(1 * time.Minute) - for { - select { - case <-timer.C: - d.getMPUData() - // case <-calibrateTimer.C: - // d.calibrate() - // calibrateTimer.Stop() - case <-d.quit: - mpu.CloseMPU() - return - } - } - }() - return -} - -// Set heading from a known value (usually GPS true heading). -func (d *MPU6050) ResetHeading(newHeading float64, gain float64) { - if gain < 0.001 { // sanitize our inputs! - gain = 0.001 - } else if gain > 1 { - gain = 1 - } - - old_hdg := d.heading // only used for debug log report - //newHeading = float64(30*time.Now().Minute()) // demo input for testing - newHeading = normalizeHeading(newHeading) // sanitize the inputs - - // By applying gain factor, this becomes a 1st order function that slowly converges on solution. - // Time constant is poll rate over gain. With gain of 0.1, convergence to +/-2 deg on a 180 correction difference is about 4 sec; 0.01 converges in 45 sec. - - hdg_corr_bias := float64(d.heading - newHeading) // desired adjustment to heading_correction - if hdg_corr_bias > 180 { - hdg_corr_bias = hdg_corr_bias - 360 - } else if hdg_corr_bias < -180 { - hdg_corr_bias = hdg_corr_bias + 360 - } - hdg_corr_bias = hdg_corr_bias * gain - d.heading_correction = normalizeHeading(d.heading_correction + hdg_corr_bias) - log.Printf("Adjusted heading. Old: %f Desired: %f Adjustment: %f New: %f\n", old_hdg, newHeading, hdg_corr_bias, d.heading-hdg_corr_bias) -} - -// Close. -func (d *MPU6050) Close() { - if d.quit != nil { - d.quit <- struct{}{} - } -} diff --git a/notes/app-vendor-integration.md b/notes/app-vendor-integration.md index a0a4ce9e3..67c52eb25 100644 --- a/notes/app-vendor-integration.md +++ b/notes/app-vendor-integration.md @@ -103,7 +103,6 @@ Stratux makes available a webserver to retrieve statistics which may be useful t "GPS_satellites_locked": 0, // Number of GPS satellites used in last GPS lock. "GPS_connected": true, // GPS unit connected and functioning. "GPS_solution": "", // "DGPS (WAAS)", "3D GPS", "N/A", or "" when GPS not connected/enabled. - "RY835AI_connected": false, // GPS/AHRS unit - use only for debugging (this will be removed). "Uptime": 227068, // Device uptime (in milliseconds). "CPUTemp": 42.236 // CPU temperature (in ºC). } diff --git a/test/sensortest.go b/test/sensortest.go deleted file mode 100644 index 11aff6c52..000000000 --- a/test/sensortest.go +++ /dev/null @@ -1,36 +0,0 @@ -package main - -import ( - "../mpu6050" - "fmt" - "net" - "time" -) - -var attSensor *mpu6050.MPU6050 - -func readMPU6050() (float64, float64) { - pitch, roll := attSensor.PitchAndRoll() - - return pitch, roll -} - -func initMPU6050() { - attSensor = mpu6050.New() -} - -func main() { - initMPU6050() - addr, err := net.ResolveUDPAddr("udp", "192.168.1.255:49002") - if err != nil { - panic(err) - } - outConn, err := net.DialUDP("udp", nil, addr) - for { - pitch, roll := readMPU6050() - s := fmt.Sprintf("XATTMy Sim,%f,%f,%f", attSensor.Heading(), pitch, roll) - fmt.Printf("%f, %f\n", pitch, roll) - outConn.Write([]byte(s)) - time.Sleep(50 * time.Millisecond) - } -} From d60248b660439ccee63fa2d353b27980cd2d6ad9 Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Thu, 17 Nov 2016 18:56:15 -0500 Subject: [PATCH 12/17] Remove globalStatus.RY835AI_connected. --- Makefile | 2 +- linux-mpu9150 | 1 - main/ry835ai.go | 21 +++++++-------------- web/plates/js/status.js | 1 - web/plates/status.html | 6 ------ 5 files changed, 8 insertions(+), 23 deletions(-) delete mode 160000 linux-mpu9150 diff --git a/Makefile b/Makefile index 2ec2e2e8c..d79980dee 100644 --- a/Makefile +++ b/Makefile @@ -12,7 +12,7 @@ all: make xgen_gdl90 xgen_gdl90: - go get -t -d -v ./main ./test ./godump978 ./mpu6050 ./uatparse + go get -t -d -v ./main ./test ./godump978 ./uatparse go build $(BUILDINFO) -p 4 main/gen_gdl90.go main/traffic.go main/ry835ai.go main/network.go main/managementinterface.go main/sdr.go main/ping.go main/uibroadcast.go main/monotonic.go main/datalog.go main/equations.go xdump1090: diff --git a/linux-mpu9150 b/linux-mpu9150 deleted file mode 160000 index 56658ffe8..000000000 --- a/linux-mpu9150 +++ /dev/null @@ -1 +0,0 @@ -Subproject commit 56658ffe83c23fde04fccc8e747bf9b7c1e184ea diff --git a/main/ry835ai.go b/main/ry835ai.go index 04de5ae01..a582dac0e 100644 --- a/main/ry835ai.go +++ b/main/ry835ai.go @@ -1870,21 +1870,20 @@ func initI2C() error { // Unused at the moment. 5 second update, since read functions in bmp180 are slow. func tempAndPressureReader() { timer := time.NewTicker(5 * time.Second) - for globalStatus.RY835AI_connected && globalSettings.AHRS_Enabled { + for { <-timer.C // Read temperature and pressure altitude. temp, alt, err_bmp180 := readBMP180() // Process. if err_bmp180 != nil { log.Printf("readBMP180(): %s\n", err_bmp180.Error()) - globalStatus.RY835AI_connected = false + return } else { mySituation.Temp = temp mySituation.Pressure_alt = alt mySituation.LastTempPressTime = stratuxClock.Time } } - globalStatus.RY835AI_connected = false } func makeFFAHRSSimReport() { @@ -2034,7 +2033,7 @@ func isTempPressValid() bool { return stratuxClock.Since(mySituation.LastTempPressTime) < 15*time.Second } -func initAHRS() error { +func initI2CSensors() error { if err := initI2C(); err != nil { // I2C bus. return err } @@ -2048,7 +2047,7 @@ func initAHRS() error { return nil } -func pollRY835AI() { +func pollGPS() { readyToInitGPS = true //TO-DO: Implement more robust method (channel control) to kill zombie serial readers timer := time.NewTicker(4 * time.Second) go gpsAttitudeSender() @@ -2061,14 +2060,6 @@ func pollRY835AI() { go gpsSerialReader() } } - // RY835AI I2C enabled, was not connected previously? - if globalSettings.AHRS_Enabled && !globalStatus.RY835AI_connected { - err := initAHRS() - if err != nil { - log.Printf("initAHRS(): %s\ndisabling AHRS sensors.\n", err.Error()) - globalStatus.RY835AI_connected = false - } - } } } @@ -2079,5 +2070,7 @@ func initRY835AI() { satelliteMutex = &sync.Mutex{} Satellites = make(map[string]SatelliteInfo) - go pollRY835AI() + initI2CSensors() + + go pollGPS() } diff --git a/web/plates/js/status.js b/web/plates/js/status.js index debb3ce80..e71be5f7e 100644 --- a/web/plates/js/status.js +++ b/web/plates/js/status.js @@ -55,7 +55,6 @@ function StatusCtrl($rootScope, $scope, $state, $http, $interval) { $scope.GPS_satellites_seen = status.GPS_satellites_seen; $scope.GPS_solution = status.GPS_solution; $scope.GPS_position_accuracy = String(status.GPS_solution ? ", " + status.GPS_position_accuracy.toFixed(1) + " m" : " "); - $scope.RY835AI_connected = status.RY835AI_connected; $scope.UAT_METAR_total = status.UAT_METAR_total; $scope.UAT_TAF_total = status.UAT_TAF_total; $scope.UAT_NEXRAD_total = status.UAT_NEXRAD_total; diff --git a/web/plates/status.html b/web/plates/status.html index 6a57eec19..b56ebb2bb 100644 --- a/web/plates/status.html +++ b/web/plates/status.html @@ -72,12 +72,6 @@ {{GPS_satellites_locked}} in solution; {{GPS_satellites_seen}} seen; {{GPS_satellites_tracked}} tracked -
- -
-
-
-
 
From 0ed4c0bfb74590c453be41c975bc54b2e69bf07a Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Thu, 17 Nov 2016 19:01:03 -0500 Subject: [PATCH 13/17] Remove globalSettings.AHRS_Enabled. --- main/gen_gdl90.go | 6 +----- main/managementinterface.go | 2 -- main/ry835ai.go | 2 +- notes/app-vendor-integration.md | 1 - web/plates/js/settings.js | 3 +-- web/plates/js/status.js | 1 - web/plates/settings.html | 31 ------------------------------- 7 files changed, 3 insertions(+), 43 deletions(-) diff --git a/main/gen_gdl90.go b/main/gen_gdl90.go index 9f5c140af..7b54bf1b0 100755 --- a/main/gen_gdl90.go +++ b/main/gen_gdl90.go @@ -430,9 +430,7 @@ func makeStratuxStatus() []byte { } // Valid/Enabled: AHRS Enabled portion. - if globalSettings.AHRS_Enabled { - msg[12] = 1 << 0 - } + // msg[12] = 1 << 0 // Valid/Enabled: last bit unused. @@ -991,7 +989,6 @@ type settings struct { GPS_Enabled bool NetworkOutputs []networkConnection SerialOutputs map[string]serialConnection - AHRS_Enabled bool DisplayTrafficSource bool DEBUG bool ReplayLog bool @@ -1056,7 +1053,6 @@ func defaultSettings() { {Conn: nil, Ip: "", Port: 4000, Capability: NETWORK_GDL90_STANDARD | NETWORK_AHRS_GDL90}, // {Conn: nil, Ip: "", Port: 49002, Capability: NETWORK_AHRS_FFSIM}, } - globalSettings.AHRS_Enabled = false globalSettings.DEBUG = false globalSettings.DisplayTrafficSource = false globalSettings.ReplayLog = false //TODO: 'true' for debug builds. diff --git a/main/managementinterface.go b/main/managementinterface.go index 6aa28f82c..134739284 100755 --- a/main/managementinterface.go +++ b/main/managementinterface.go @@ -274,8 +274,6 @@ func handleSettingsSetRequest(w http.ResponseWriter, r *http.Request) { globalSettings.Ping_Enabled = val.(bool) case "GPS_Enabled": globalSettings.GPS_Enabled = val.(bool) - case "AHRS_Enabled": - globalSettings.AHRS_Enabled = val.(bool) case "DEBUG": globalSettings.DEBUG = val.(bool) case "DisplayTrafficSource": diff --git a/main/ry835ai.go b/main/ry835ai.go index a582dac0e..a9db11ff4 100644 --- a/main/ry835ai.go +++ b/main/ry835ai.go @@ -1938,7 +1938,7 @@ func gpsAttitudeSender() { for { <-timer.C myGPSPerfStats = make([]gpsPerfStats, 0) // reinitialize statistics on disconnect / reconnect - for globalSettings.GPS_Enabled && globalStatus.GPS_connected /*&& globalSettings.GPSAttitude_Enabled*/ && !(globalSettings.AHRS_Enabled) { + for globalSettings.GPS_Enabled && globalStatus.GPS_connected { <-timer.C if mySituation.Quality == 0 || !calcGPSAttitude() { diff --git a/notes/app-vendor-integration.md b/notes/app-vendor-integration.md index 67c52eb25..2f49f78ec 100644 --- a/notes/app-vendor-integration.md +++ b/notes/app-vendor-integration.md @@ -130,7 +130,6 @@ Stratux makes available a webserver to retrieve statistics which may be useful t "Capability": 2 } ], - "AHRS_Enabled": false, "DEBUG": false, "ReplayLog": true, "PPM": 0, diff --git a/web/plates/js/settings.js b/web/plates/js/settings.js index 52b180995..135f6a096 100755 --- a/web/plates/js/settings.js +++ b/web/plates/js/settings.js @@ -6,7 +6,7 @@ function SettingsCtrl($rootScope, $scope, $state, $location, $window, $http) { $scope.$parent.helppage = 'plates/settings-help.html'; - var toggles = ['UAT_Enabled', 'ES_Enabled', 'Ping_Enabled', 'GPS_Enabled', 'AHRS_Enabled', 'DisplayTrafficSource', 'DEBUG', 'ReplayLog']; + var toggles = ['UAT_Enabled', 'ES_Enabled', 'Ping_Enabled', 'GPS_Enabled', 'DisplayTrafficSource', 'DEBUG', 'ReplayLog']; var settings = {}; for (i = 0; i < toggles.length; i++) { settings[toggles[i]] = undefined; @@ -26,7 +26,6 @@ function SettingsCtrl($rootScope, $scope, $state, $location, $window, $http) { $scope.ES_Enabled = settings.ES_Enabled; $scope.Ping_Enabled = settings.Ping_Enabled; $scope.GPS_Enabled = settings.GPS_Enabled; - $scope.AHRS_Enabled = settings.AHRS_Enabled; $scope.DisplayTrafficSource = settings.DisplayTrafficSource; $scope.DEBUG = settings.DEBUG; $scope.ReplayLog = settings.ReplayLog; diff --git a/web/plates/js/status.js b/web/plates/js/status.js index e71be5f7e..a8e0aaccc 100644 --- a/web/plates/js/status.js +++ b/web/plates/js/status.js @@ -109,7 +109,6 @@ function StatusCtrl($rootScope, $scope, $state, $http, $interval) { $scope.visible_es = true; } $scope.visible_gps = settings.GPS_Enabled; - $scope.visible_ahrs = settings.AHRS_Enabled; }, function (response) { // nop }); diff --git a/web/plates/settings.html b/web/plates/settings.html index 5387c4a7a..52d5dc778 100755 --- a/web/plates/settings.html +++ b/web/plates/settings.html @@ -28,12 +28,6 @@
-
- -
- -
-
@@ -214,30 +208,5 @@ - - - - - From d7498169edd3050005817e0338e0cedbef246e07 Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Thu, 17 Nov 2016 19:02:55 -0500 Subject: [PATCH 14/17] Misc cleanup. --- main/ry835ai.go | 3 --- 1 file changed, 3 deletions(-) diff --git a/main/ry835ai.go b/main/ry835ai.go index a9db11ff4..0aaa7b6a0 100644 --- a/main/ry835ai.go +++ b/main/ry835ai.go @@ -79,8 +79,6 @@ type SituationData struct { LastValidNMEAMessageTime time.Time // time valid NMEA message last seen LastValidNMEAMessage string // last NMEA message processed. - mu_Attitude *sync.Mutex - // From BMP180 pressure sensor. Temp float64 Pressure_alt float64 @@ -2066,7 +2064,6 @@ func pollGPS() { func initRY835AI() { mySituation.mu_GPS = &sync.Mutex{} mySituation.mu_GPSPerf = &sync.Mutex{} - mySituation.mu_Attitude = &sync.Mutex{} satelliteMutex = &sync.Mutex{} Satellites = make(map[string]SatelliteInfo) From 360845b454454dd49b705bd09a5d94eb39db7f76 Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Thu, 17 Nov 2016 19:10:59 -0500 Subject: [PATCH 15/17] Misc cleanup. --- main/ry835ai.go | 88 ++++++++++--------------------------------------- 1 file changed, 18 insertions(+), 70 deletions(-) diff --git a/main/ry835ai.go b/main/ry835ai.go index 0aaa7b6a0..ce688d187 100644 --- a/main/ry835ai.go +++ b/main/ry835ai.go @@ -114,7 +114,7 @@ var myGPSPerfStats []gpsPerfStats var serialConfig *serial.Config var serialPort *serial.Port -var readyToInitGPS bool // TO-DO: replace with channel control to terminate goroutine when complete +var readyToInitGPS bool //TODO: replace with channel control to terminate goroutine when complete var satelliteMutex *sync.Mutex var Satellites map[string]SatelliteInfo @@ -207,54 +207,6 @@ func initGPSSerial() bool { log.Printf("Using %s for GPS\n", device) } - /* Developer option -- uncomment to allow "hot" configuration of GPS (assuming 38.4 kpbs on warm start) - serialConfig = &serial.Config{Name: device, Baud: 38400} - p, err := serial.OpenPort(serialConfig) - if err != nil { - log.Printf("serial port err: %s\n", err.Error()) - return false - } else { // reset port to 9600 baud for configuration - cfg1 := make([]byte, 20) - cfg1[0] = 0x01 // portID. - cfg1[1] = 0x00 // res0. - cfg1[2] = 0x00 // res1. - cfg1[3] = 0x00 // res1. - - // [ 7 ] [ 6 ] [ 5 ] [ 4 ] - // 0000 0000 0000 0000 1000 0000 1100 0000 - // UART mode. 0 stop bits, no parity, 8 data bits. Little endian order. - cfg1[4] = 0xC0 - cfg1[5] = 0x08 - cfg1[6] = 0x00 - cfg1[7] = 0x00 - - // Baud rate. Little endian order. - bdrt1 := uint32(9600) - cfg1[11] = byte((bdrt1 >> 24) & 0xFF) - cfg1[10] = byte((bdrt1 >> 16) & 0xFF) - cfg1[9] = byte((bdrt1 >> 8) & 0xFF) - cfg1[8] = byte(bdrt1 & 0xFF) - - // inProtoMask. NMEA and UBX. Little endian. - cfg1[12] = 0x03 - cfg1[13] = 0x00 - - // outProtoMask. NMEA. Little endian. - cfg1[14] = 0x02 - cfg1[15] = 0x00 - - cfg1[16] = 0x00 // flags. - cfg1[17] = 0x00 // flags. - - cfg1[18] = 0x00 //pad. - cfg1[19] = 0x00 //pad. - - p.Write(makeUBXCFG(0x06, 0x00, 20, cfg1)) - p.Close() - } - - -- End developer option */ - // Open port at default baud for config. serialConfig = &serial.Config{Name: device, Baud: baudrate} p, err := serial.OpenPort(serialConfig) @@ -520,7 +472,7 @@ func calcGPSAttitude() bool { // second case: index is behind index-1. This could be result of day rollover. If time is within n seconds of UTC, // we rebase to the previous day, and will re-rebase the entire slice forward to the current day once all values roll over. - // TO-DO: Validate by testing at 0000Z + //TODO: Validate by testing at 0000Z if dt < 0 { log.Printf("GPS attitude: Current GPS time (%.2f) is older than last GPS time (%.2f). Checking for 0000Z rollover.\n", t1, t0) if myGPSPerfStats[index-1].nmeaTime > 86300 && myGPSPerfStats[index].nmeaTime < 100 { // be generous with the time window at rollover @@ -1024,7 +976,7 @@ func processNMEALine(l string) (sentenceUsed bool) { if err != nil { return false } - if groundspeed > 3 { // TO-DO: use average groundspeed over last n seconds to avoid random "jumps" + if groundspeed > 3 { //TODO: use average groundspeed over last n seconds to avoid random "jumps" trueCourse = float32(tc) setTrueCourse(uint16(groundspeed), tc) tmpSituation.TrueCourse = trueCourse @@ -1032,7 +984,7 @@ func processNMEALine(l string) (sentenceUsed bool) { } else { thisGpsPerf.coursef = -999.9 // regression will skip negative values // Negligible movement. Don't update course, but do use the slow speed. - // TO-DO: use average course over last n seconds? + //TODO: use average course over last n seconds? } tmpSituation.LastGroundTrackTime = stratuxClock.Time @@ -1131,7 +1083,7 @@ func processNMEALine(l string) (sentenceUsed bool) { svType = SAT_TYPE_SBAS svStr = fmt.Sprintf("S%d", sv) sv -= 87 // subtract 87 to convert to NMEA from PRN. - } else { // TO-DO: Galileo + } else { //TODO: Galileo svType = SAT_TYPE_UNKNOWN svStr = fmt.Sprintf("U%d", sv) } @@ -1218,9 +1170,7 @@ func processNMEALine(l string) (sentenceUsed bool) { log.Printf("GPS week # %v out of scope; not setting time and date\n", utcWeek) } return false - } /* else { - log.Printf("GPS week # %v valid; evaluate time and date\n", utcWeek) //debug option - } */ + } // field 2 is UTC time if len(x[2]) < 7 { @@ -1279,13 +1229,13 @@ func processNMEALine(l string) (sentenceUsed bool) { if err != nil { return false } - if groundspeed > 3 { // TO-DO: use average groundspeed over last n seconds to avoid random "jumps" + if groundspeed > 3 { //TODO: use average groundspeed over last n seconds to avoid random "jumps" trueCourse = float32(tc) setTrueCourse(uint16(groundspeed), tc) tmpSituation.TrueCourse = trueCourse } else { // Negligible movement. Don't update course, but do use the slow speed. - // TO-DO: use average course over last n seconds? + //TODO: use average course over last n seconds? } tmpSituation.LastGroundTrackTime = stratuxClock.Time @@ -1515,7 +1465,7 @@ func processNMEALine(l string) (sentenceUsed bool) { if err != nil && groundspeed > 3 { // some receivers return null COG at low speeds. Need to ignore this condition. return false } - if groundspeed > 3 { // TO-DO: use average groundspeed over last n seconds to avoid random "jumps" + if groundspeed > 3 { //TODO: use average groundspeed over last n seconds to avoid random "jumps" trueCourse = float32(tc) setTrueCourse(uint16(groundspeed), tc) tmpSituation.TrueCourse = trueCourse @@ -1527,7 +1477,7 @@ func processNMEALine(l string) (sentenceUsed bool) { thisGpsPerf.coursef = -999.9 } // Negligible movement. Don't update course, but do use the slow speed. - // TO-DO: use average course over last n seconds? + //TODO: use average course over last n seconds? } if globalStatus.GPS_detected_type != GPS_TYPE_UBX { updateGPSPerf = true @@ -1600,7 +1550,7 @@ func processNMEALine(l string) (sentenceUsed bool) { svType = SAT_TYPE_GLONASS svStr = fmt.Sprintf("R%d", sv-64) // subtract 64 to convert from NMEA to PRN. svGLONASS = true - } else { // TO-DO: Galileo + } else { //TODO: Galileo svType = SAT_TYPE_UNKNOWN svStr = fmt.Sprintf("U%d", sv) } @@ -1638,7 +1588,6 @@ func processNMEALine(l string) (sentenceUsed bool) { tmpSituation.Satellites++ } } - //log.Printf("There are %d satellites in solution from this GSA message\n", sat) // TESTING - DEBUG // field 16: HDOP // Accuracy estimate @@ -1725,7 +1674,7 @@ func processNMEALine(l string) (sentenceUsed bool) { } else if sv < 97 { // GLONASS svType = SAT_TYPE_GLONASS svStr = fmt.Sprintf("R%d", sv-64) // subtract 64 to convert from NMEA to PRN. - } else { // TO-DO: Galileo + } else { //TODO: Galileo svType = SAT_TYPE_UNKNOWN svStr = fmt.Sprintf("U%d", sv) } @@ -1803,13 +1752,13 @@ func processNMEALine(l string) (sentenceUsed bool) { return true } - // if we've gotten this far, the message isn't one that we want to parse + // If we've gotten this far, the message isn't one that we can use. return false } func gpsSerialReader() { defer serialPort.Close() - readyToInitGPS = false // TO-DO: replace with channel control to terminate goroutine when complete + readyToInitGPS = false //TODO: replace with channel control to terminate goroutine when complete i := 0 //debug monitor scanner := bufio.NewScanner(serialPort) @@ -1835,7 +1784,7 @@ func gpsSerialReader() { log.Printf("Exiting gpsSerialReader() after i=%d loops\n", i) // debug monitor } globalStatus.GPS_connected = false - readyToInitGPS = true // TO-DO: replace with channel control to terminate goroutine when complete + readyToInitGPS = true //TODO: replace with channel control to terminate goroutine when complete return } @@ -1986,8 +1935,7 @@ func updateConstellation() { // do any other calculations needed for this satellite } } - //log.Printf("Satellite counts: %d tracking channels, %d with >0 dB-Hz signal\n", tracked, seen) // DEBUG - REMOVE - //log.Printf("Satellite struct: %v\n", Satellites) // DEBUG - REMOVE + mySituation.Satellites = uint16(sats) mySituation.SatellitesTracked = uint16(tracked) mySituation.SatellitesSeen = uint16(seen) @@ -2046,13 +1994,13 @@ func initI2CSensors() error { } func pollGPS() { - readyToInitGPS = true //TO-DO: Implement more robust method (channel control) to kill zombie serial readers + readyToInitGPS = true //TODO: Implement more robust method (channel control) to kill zombie serial readers timer := time.NewTicker(4 * time.Second) go gpsAttitudeSender() for { <-timer.C // GPS enabled, was not connected previously? - if globalSettings.GPS_Enabled && !globalStatus.GPS_connected && readyToInitGPS { //TO-DO: Implement more robust method (channel control) to kill zombie serial readers + if globalSettings.GPS_Enabled && !globalStatus.GPS_connected && readyToInitGPS { //TODO: Implement more robust method (channel control) to kill zombie serial readers globalStatus.GPS_connected = initGPSSerial() if globalStatus.GPS_connected { go gpsSerialReader() From ebfb67114213d10a3e25709f997861cf52d1065c Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Thu, 17 Nov 2016 19:14:33 -0500 Subject: [PATCH 16/17] Rename ry835ai.go to gps.go. --- Makefile | 2 +- main/gen_gdl90.go | 5 +++-- main/{ry835ai.go => gps.go} | 4 ++-- web/plates/status-help.html | 1 - 4 files changed, 6 insertions(+), 6 deletions(-) rename main/{ry835ai.go => gps.go} (99%) diff --git a/Makefile b/Makefile index d79980dee..57261b924 100644 --- a/Makefile +++ b/Makefile @@ -13,7 +13,7 @@ all: xgen_gdl90: go get -t -d -v ./main ./test ./godump978 ./uatparse - go build $(BUILDINFO) -p 4 main/gen_gdl90.go main/traffic.go main/ry835ai.go main/network.go main/managementinterface.go main/sdr.go main/ping.go main/uibroadcast.go main/monotonic.go main/datalog.go main/equations.go + go build $(BUILDINFO) -p 4 main/gen_gdl90.go main/traffic.go main/gps.go main/network.go main/managementinterface.go main/sdr.go main/ping.go main/uibroadcast.go main/monotonic.go main/datalog.go main/equations.go xdump1090: git submodule update --init diff --git a/main/gen_gdl90.go b/main/gen_gdl90.go index 7b54bf1b0..fc46f4048 100755 --- a/main/gen_gdl90.go +++ b/main/gen_gdl90.go @@ -257,7 +257,7 @@ func makeOwnshipReport() bool { msg[12] = msg[12] | 0x09 // "Airborne" + "True Track" } - msg[13] = byte(0x80 | (mySituation.NACp & 0x0F)) //Set NIC = 8 and use NACp from ry835ai.go. + msg[13] = byte(0x80 | (mySituation.NACp & 0x0F)) //Set NIC = 8 and use NACp from gps.go. gdSpeed := uint16(0) // 1kt resolution. if isGPSGroundTrackValid() { @@ -1342,7 +1342,8 @@ func main() { //FIXME: Only do this if data logging is enabled. initDataLog() - initRY835AI() + // Start the GPS external sensor monitoring. + initGPS() // Start the heartbeat message loop in the background, once per second. go heartBeatSender() diff --git a/main/ry835ai.go b/main/gps.go similarity index 99% rename from main/ry835ai.go rename to main/gps.go index ce688d187..d0ee90eb3 100644 --- a/main/ry835ai.go +++ b/main/gps.go @@ -4,7 +4,7 @@ that can be found in the LICENSE file, herein included as part of this header. - ry835ai.go: GPS functions, GPS init, AHRS status messages, other external sensor monitoring. + gps.go: GPS functions, GPS init, AHRS status messages, other external sensor monitoring. */ package main @@ -2009,7 +2009,7 @@ func pollGPS() { } } -func initRY835AI() { +func initGPS() { mySituation.mu_GPS = &sync.Mutex{} mySituation.mu_GPSPerf = &sync.Mutex{} satelliteMutex = &sync.Mutex{} diff --git a/web/plates/status-help.html b/web/plates/status-help.html index 8ec44d6dc..01207d095 100755 --- a/web/plates/status-help.html +++ b/web/plates/status-help.html @@ -6,7 +6,6 @@
  • Messages is the number of messages received by the UAT (978 MHz) and 1090 MHz radios. "Current" is the 60-second rolling total for each receiver; "Peak" is the maximum 60-second total. The 1090 total includes all 1090 MHz Mode S messages received, including all-call and TCAS interrogations that do not carry ADS-B position information. If a UAT radio is receiving uplinks from one or more ground-based transceivers (GBT), this will be indicated under UAT Towers, with more details available on the Towers page.
  • GPS indicates the connection status of any attached GPS receivers. Reported data includes the type of position solution, the number of satellites used in that solution, the number of satellites being received, and the number of satellites tracked in the GPS almanac data. Position and accuracy details can be viewed on the GPS/AHRS page.
  • -
  • AHRS indicates whether the pressure sensor and gyro on an RY835AI or similar 10-axis module are connected and enabled. If connected, attitude and pressure altitude can be viewed on the GPS/AHRS page.

Devices must be manually enabled on the Settings page.

From c19d32353f774969d29aa9cbcc785f617d765eee Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Sun, 27 Nov 2016 14:46:26 -0500 Subject: [PATCH 17/17] Typo. --- main/gps.go | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/main/gps.go b/main/gps.go index d0ee90eb3..65aca8e73 100644 --- a/main/gps.go +++ b/main/gps.go @@ -1890,7 +1890,7 @@ func gpsAttitudeSender() { if mySituation.Quality == 0 || !calcGPSAttitude() { if globalSettings.DEBUG { - log.Printf("Could'nt calculate GPS-based attitude statistics\n") + log.Printf("Couldn't calculate GPS-based attitude statistics\n") } } else { mySituation.mu_GPSPerf.Lock()