From cbd117d216ef8facbd6b6bdaa8b180bb538c24ba Mon Sep 17 00:00:00 2001 From: AvSquirrel Date: Tue, 7 Jun 2016 13:03:25 +0000 Subject: [PATCH 001/128] 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 6a65665c..5ba0d3c7 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 582d3a27..4007d5e9 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 002/128] 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 eda48cd5..621400fa 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 5ba0d3c7..dfdd1ea0 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 4007d5e9..f0c3af4c 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 003/128] 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 f0c3af4c..fb1e4fd6 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 004/128] 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 5900fe19..bcf1b623 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 b327d9cc..eaf02e11 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 fb1e4fd6..373eca6c 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 40922d92..15a1736b 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 005/128] Comment cleanup. Remove bloat from UI status page. --- main/gen_gdl90.go | 4 +--- web/plates/status.html | 36 +++++++++++++++++++++++------------- 2 files changed, 24 insertions(+), 16 deletions(-) diff --git a/main/gen_gdl90.go b/main/gen_gdl90.go index dfdd1ea0..60e91ac9 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 aadf4f9e..186f051f 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 006/128] 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 ef82097c..698c8028 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 007/128] 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 eaf02e11..835385e5 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 3cd58d20d888b270c2ad68d4e8208be68351cad9 Mon Sep 17 00:00:00 2001 From: "Ryan C. Braun" Date: Tue, 9 Aug 2016 14:36:01 -0500 Subject: [PATCH 008/128] Disable logging of Ping data reception --- main/ping.go | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/main/ping.go b/main/ping.go index 2493a45e..d254ef44 100644 --- a/main/ping.go +++ b/main/ping.go @@ -148,8 +148,8 @@ func pingSerialReader() { s := scanner.Text() // Trimspace removes newlines as well as whitespace s = strings.TrimSpace(s) - logString := fmt.Sprintf("Ping received: %s", s) - log.Println(logString) + //logString := fmt.Sprintf("Ping received: %s", s) + //log.Println(logString) if s[0] == '*' { // 1090ES report // Ping appends a signal strength at the end of the message From 04e4454bb7e8f2fb4b4e0a88cda9baee58132b40 Mon Sep 17 00:00:00 2001 From: Jim Jacobsen Date: Thu, 11 Aug 2016 21:12:38 -0500 Subject: [PATCH 009/128] Added modification to udev rule to support replacement uAvionix device received --- image/99-uavionix.rules | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/image/99-uavionix.rules b/image/99-uavionix.rules index 6f6703aa..71ac7440 100644 --- a/image/99-uavionix.rules +++ b/image/99-uavionix.rules @@ -4,3 +4,7 @@ ATTRS{idProduct}=="74f0", ATTRS{idVendor}=="0403", RUN+="/sbin/modprobe -q ftdi_ # uAvionix Ping Raw ATTRS{idProduct}=="74f1", ATTRS{idVendor}=="0403", RUN+="/sbin/modprobe -q ftdi_sio" RUN+="/bin/sh -c 'echo 0403 74f1 > /sys/bus/usb-serial/drivers/ftdi_sio/new_id'", OWNER="root", MODE="0666", SYMLINK+="ping" +# added for replacement PingUSB + +ATTRS{idProduct}=="6015", ATTRS{idVendor}=="0403", RUN+="/sbin/modprobe -q ftdi_sio" RUN+="/bin/sh -c 'echo 0403 6015 > /sys/bus/usb-serial/drivers/ftdi_sio/new_id'", OWNER="root", MODE="0666", SYMLINK+="ping" + From e93b90197cd7c3e0bce41c025bd76f0babde6856 Mon Sep 17 00:00:00 2001 From: "Ryan C. Braun" Date: Sat, 20 Aug 2016 15:05:35 -0500 Subject: [PATCH 010/128] Remove unused fmt from imports --- main/ping.go | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/main/ping.go b/main/ping.go index d254ef44..b491b9d7 100644 --- a/main/ping.go +++ b/main/ping.go @@ -11,7 +11,7 @@ package main import ( "bufio" - "fmt" + //"fmt" "log" "os" "strings" From 03f3957a0d347f00f0e8b244b4b71deb2cdd8136 Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Sun, 11 Sep 2016 16:58:37 -0400 Subject: [PATCH 011/128] Change paths for OLED screen addition. Add OLED script install into mkimg.sh. --- image/mkimg.sh | 11 ++++++++--- test/screen/screen.py | 4 ++-- test/screen/{logo.bmp => stratux-logo-64x64.bmp} | Bin 3 files changed, 10 insertions(+), 5 deletions(-) rename test/screen/{logo.bmp => stratux-logo-64x64.bmp} (100%) diff --git a/image/mkimg.sh b/image/mkimg.sh index 9ab5ae69..2bb412f8 100755 --- a/image/mkimg.sh +++ b/image/mkimg.sh @@ -126,6 +126,11 @@ sed -i /etc/default/keyboard -e "/^XKBLAYOUT/s/\".*\"/\"us\"/" cp -f config.txt mnt/boot/ #external OLED screen -#apt-get install -y libjpeg-dev i2c-tools python-smbus python-pip python-dev python-pil screen -#git clone https://github.com/rm-hull/ssd1306 -#cd ssd1306 && python setup.py install +apt-get install -y libjpeg-dev i2c-tools python-smbus python-pip python-dev python-pil screen +git clone https://github.com/rm-hull/ssd1306 +cd ssd1306 && python setup.py install +cp /root/stratux/test/screen/screen.py /usr/bin/stratux-screen.py +mkdir -p /etc/stratux-screen/ +cp -f /root/stratux/test/screen/stratux-logo-64x64.bmp /etc/stratux-screen/stratux-logo-64x64.bmp +cp -f /root/stratux/test/screen/CnC_Red_Alert.ttf /etc/stratux-screen/CnC_Red_Alert.ttf + diff --git a/test/screen/screen.py b/test/screen/screen.py index 8acc3307..2efaf428 100755 --- a/test/screen/screen.py +++ b/test/screen/screen.py @@ -9,11 +9,11 @@ import urllib2 import json import time -font2 = ImageFont.truetype('/root/stratux/test/screen/CnC_Red_Alert.ttf', 12) +font2 = ImageFont.truetype('/etc/stratux-screen/CnC_Red_Alert.ttf', 12) oled = ssd1306(port=1, address=0x3C) with canvas(oled) as draw: - logo = Image.open('/root/stratux/test/screen/logo.bmp') + logo = Image.open('/etc/stratux-screen/stratux-logo-64x64.bmp') draw.bitmap((32, 0), logo, fill=1) time.sleep(10) diff --git a/test/screen/logo.bmp b/test/screen/stratux-logo-64x64.bmp similarity index 100% rename from test/screen/logo.bmp rename to test/screen/stratux-logo-64x64.bmp From 333bb6c3cefb77e6dbb3b96ae33dd3b4d8e0f2ba Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Sun, 11 Sep 2016 17:06:06 -0400 Subject: [PATCH 012/128] Add "post start" script to start fan control and screen controllers. --- __lib__systemd__system__stratux.service | 1 + __root__stratux-post-start.sh | 4 ++++ image/mkimg.sh | 4 ++++ 3 files changed, 9 insertions(+) create mode 100755 __root__stratux-post-start.sh diff --git a/__lib__systemd__system__stratux.service b/__lib__systemd__system__stratux.service index 7353a517..5095287a 100644 --- a/__lib__systemd__system__stratux.service +++ b/__lib__systemd__system__stratux.service @@ -4,6 +4,7 @@ After=network.target [Service] ExecStartPre=/root/stratux-pre-start.sh +ExecStartPost=/root/stratux-post-start.sh ExecStart=/usr/bin/gen_gdl90 ExecStop=pkill dump1090 KillMode=process diff --git a/__root__stratux-post-start.sh b/__root__stratux-post-start.sh new file mode 100755 index 00000000..d3901d88 --- /dev/null +++ b/__root__stratux-post-start.sh @@ -0,0 +1,4 @@ +#!/bin/bash + +/usr/bin/stratux-screen.py +/usr/bin/fancontrol.py diff --git a/image/mkimg.sh b/image/mkimg.sh index 2bb412f8..2b142adb 100755 --- a/image/mkimg.sh +++ b/image/mkimg.sh @@ -134,3 +134,7 @@ mkdir -p /etc/stratux-screen/ cp -f /root/stratux/test/screen/stratux-logo-64x64.bmp /etc/stratux-screen/stratux-logo-64x64.bmp cp -f /root/stratux/test/screen/CnC_Red_Alert.ttf /etc/stratux-screen/CnC_Red_Alert.ttf +#startup scripts +cp -f __lib__systemd__system__stratux.service /lib/systemd/system/stratux.service +cp -f __root__stratux-pre-start.sh /root/stratux-pre-start.sh +cp -f __root__stratux-post-start.sh /root/stratux-post-start.sh From 0588f8b0e76b1a1db145c7434a2afbe78bf211a9 Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Sun, 11 Sep 2016 17:24:01 -0400 Subject: [PATCH 013/128] Daemonize stratux-screen.py and fancontrol.py. --- __root__stratux-post-start.sh | 4 +- image/fancontrol.py | 51 ++++++++----- image/mkimg.sh | 2 +- test/screen/screen.py | 133 ++++++++++++++++++---------------- 4 files changed, 106 insertions(+), 84 deletions(-) mode change 100644 => 100755 image/fancontrol.py diff --git a/__root__stratux-post-start.sh b/__root__stratux-post-start.sh index d3901d88..a3a53522 100755 --- a/__root__stratux-post-start.sh +++ b/__root__stratux-post-start.sh @@ -1,4 +1,4 @@ #!/bin/bash -/usr/bin/stratux-screen.py -/usr/bin/fancontrol.py +/usr/bin/stratux-screen.py start +/usr/bin/fancontrol.py start diff --git a/image/fancontrol.py b/image/fancontrol.py old mode 100644 new mode 100755 index 9b11be04..c8529381 --- a/image/fancontrol.py +++ b/image/fancontrol.py @@ -9,26 +9,37 @@ import RPi.GPIO as GPIO import time import os -# Return CPU temperature as float -def getCPUtemp(): - cTemp = os.popen('vcgencmd measure_temp').readline() - return float(cTemp.replace("temp=","").replace("'C\n","")) +from daemon import runner -GPIO.setmode(GPIO.BOARD) -GPIO.setup(11,GPIO.OUT) -GPIO.setwarnings(False) -p=GPIO.PWM(11,1000) -PWM = 50 +class FanControl(): + # Return CPU temperature as float + def getCPUtemp(self): + cTemp = os.popen('vcgencmd measure_temp').readline() + return float(cTemp.replace("temp=","").replace("'C\n","")) -while True: + def __init__(self): + self.stdin_path = '/dev/null' + self.stdout_path = '/dev/tty' + self.stderr_path = '/dev/tty' + self.pidfile_path = '/var/run/fancontrol.pid' + self.pidfile_timeout = 5 + def run(self): + GPIO.setmode(GPIO.BOARD) + GPIO.setup(11,GPIO.OUT) + GPIO.setwarnings(False) + p=GPIO.PWM(11,1000) + PWM = 50 + while True: + CPU_temp = self.getCPUtemp() + if CPU_temp > 40.5: + PWM = min(max(PWM + 1, 0), 100) + p.start(PWM) + elif CPU_temp < 39.5: + PWM = min(max(PWM - 1, 0), 100) + p.start(PWM) + time.sleep(5) + GPIO.cleanup() - CPU_temp = getCPUtemp() - if CPU_temp > 40.5: - PWM = min(max(PWM + 1, 0), 100) - p.start(PWM) - elif CPU_temp < 39.5: - PWM = min(max(PWM - 1, 0), 100) - p.start(PWM) - time.sleep(5) - -GPIO.cleanup() +fancontrol = FanControl() +daemon_runner = runner.DaemonRunner(fancontrol) +daemon_runner.do_action() diff --git a/image/mkimg.sh b/image/mkimg.sh index 2b142adb..10e820c2 100755 --- a/image/mkimg.sh +++ b/image/mkimg.sh @@ -126,7 +126,7 @@ sed -i /etc/default/keyboard -e "/^XKBLAYOUT/s/\".*\"/\"us\"/" cp -f config.txt mnt/boot/ #external OLED screen -apt-get install -y libjpeg-dev i2c-tools python-smbus python-pip python-dev python-pil screen +apt-get install -y libjpeg-dev i2c-tools python-smbus python-pip python-dev python-pil python-daemon screen git clone https://github.com/rm-hull/ssd1306 cd ssd1306 && python setup.py install cp /root/stratux/test/screen/screen.py /usr/bin/stratux-screen.py diff --git a/test/screen/screen.py b/test/screen/screen.py index 2efaf428..7b18c0ad 100755 --- a/test/screen/screen.py +++ b/test/screen/screen.py @@ -9,69 +9,80 @@ import urllib2 import json import time -font2 = ImageFont.truetype('/etc/stratux-screen/CnC_Red_Alert.ttf', 12) -oled = ssd1306(port=1, address=0x3C) +from daemon import runner -with canvas(oled) as draw: - logo = Image.open('/etc/stratux-screen/stratux-logo-64x64.bmp') - draw.bitmap((32, 0), logo, fill=1) +class StratuxScreen(): + def __init__(self): + self.stdin_path = '/dev/null' + self.stdout_path = '/dev/tty' + self.stderr_path = '/dev/tty' + self.pidfile_path = '/var/run/fancontrol.pid' + self.pidfile_timeout = 5 + def run(self): + font2 = ImageFont.truetype('/etc/stratux-screen/CnC_Red_Alert.ttf', 12) + oled = ssd1306(port=1, address=0x3C) -time.sleep(10) + with canvas(oled) as draw: + logo = Image.open('/etc/stratux-screen/stratux-logo-64x64.bmp') + draw.bitmap((32, 0), logo, fill=1) -n = 0 + time.sleep(10) + n = 0 -while 1: - time.sleep(1) - response = urllib2.urlopen('http://localhost/getStatus') - getStatusHTML = response.read() - getStatusData = json.loads(getStatusHTML) - CPUTemp = getStatusData["CPUTemp"] - uat_current = getStatusData["UAT_messages_last_minute"] - uat_max = getStatusData["UAT_messages_max"] - es_current = getStatusData["ES_messages_last_minute"] - es_max = getStatusData["ES_messages_max"] + while 1: + time.sleep(1) + response = urllib2.urlopen('http://localhost/getStatus') + getStatusHTML = response.read() + getStatusData = json.loads(getStatusHTML) + CPUTemp = getStatusData["CPUTemp"] + uat_current = getStatusData["UAT_messages_last_minute"] + uat_max = getStatusData["UAT_messages_max"] + es_current = getStatusData["ES_messages_last_minute"] + es_max = getStatusData["ES_messages_max"] - response = urllib2.urlopen('http://localhost/getTowers') - getTowersHTML = response.read() - getTowersData = json.loads(getTowersHTML) - NumTowers = len(getTowersData) - - - - - with canvas(oled) as draw: - pad = 2 # Two pixels on the left and right. - text_margin = 25 - # UAT status. - draw.text((50, 0), "UAT", font=font2, fill=255) - # "Status bar", 2 pixels high. - status_bar_width_max = oled.width - (2 * pad) - (2 * text_margin) - status_bar_width = 0 - if uat_max > 0: - status_bar_width = int((float(uat_current) / uat_max) * status_bar_width_max) - draw.rectangle((pad + text_margin, 14, pad + text_margin + status_bar_width, 20), outline=255, fill=255) # Top left, bottom right. - # Draw the current (left) and max (right) numbers. - draw.text((pad, 14), str(uat_current), font=font2, fill=255) - draw.text(((2*pad) + text_margin + status_bar_width_max, 14), str(uat_max), font=font2, fill=255) - # ES status. - draw.text((44, 24), "1090ES", font=font2, fill=255) - status_bar_width = 0 - if es_max > 0: - status_bar_width = int((float(es_current) / es_max) * status_bar_width_max) - draw.rectangle((pad + text_margin, 34, pad + text_margin + status_bar_width, 40), outline=255, fill=255) # Top left, bottom right. - # Draw the current (left) and max (right) numbers. - draw.text((pad, 34), str(es_current), font=font2, fill=255) - draw.text(((2*pad) + text_margin + status_bar_width_max, 34), str(es_max), font=font2, fill=255) - # Other stats. - seq = (n / 5) % 2 - t = "" - if seq == 0: - t = "CPU: %0.1fC, Towers: %d" % (CPUTemp, NumTowers) - if seq == 1: - t = "GPS Sat: %d/%d/%d" % (getStatusData["GPS_satellites_locked"], getStatusData["GPS_satellites_seen"], getStatusData["GPS_satellites_tracked"]) - if getStatusData["GPS_solution"] == "GPS + SBAS (WAAS / EGNOS)": - t = t + " (WAAS)" - print t - draw.text((pad, 45), t, font=font2, fill=255) - - n = n+1 \ No newline at end of file + response = urllib2.urlopen('http://localhost/getTowers') + getTowersHTML = response.read() + getTowersData = json.loads(getTowersHTML) + NumTowers = len(getTowersData) + + with canvas(oled) as draw: + pad = 2 # Two pixels on the left and right. + text_margin = 25 + # UAT status. + draw.text((50, 0), "UAT", font=font2, fill=255) + # "Status bar", 2 pixels high. + status_bar_width_max = oled.width - (2 * pad) - (2 * text_margin) + status_bar_width = 0 + if uat_max > 0: + status_bar_width = int((float(uat_current) / uat_max) * status_bar_width_max) + draw.rectangle((pad + text_margin, 14, pad + text_margin + status_bar_width, 20), outline=255, fill=255) # Top left, bottom right. + # Draw the current (left) and max (right) numbers. + draw.text((pad, 14), str(uat_current), font=font2, fill=255) + draw.text(((2*pad) + text_margin + status_bar_width_max, 14), str(uat_max), font=font2, fill=255) + # ES status. + draw.text((44, 24), "1090ES", font=font2, fill=255) + status_bar_width = 0 + if es_max > 0: + status_bar_width = int((float(es_current) / es_max) * status_bar_width_max) + draw.rectangle((pad + text_margin, 34, pad + text_margin + status_bar_width, 40), outline=255, fill=255) # Top left, bottom right. + # Draw the current (left) and max (right) numbers. + draw.text((pad, 34), str(es_current), font=font2, fill=255) + draw.text(((2*pad) + text_margin + status_bar_width_max, 34), str(es_max), font=font2, fill=255) + # Other stats. + seq = (n / 5) % 2 + t = "" + if seq == 0: + t = "CPU: %0.1fC, Towers: %d" % (CPUTemp, NumTowers) + if seq == 1: + t = "GPS Sat: %d/%d/%d" % (getStatusData["GPS_satellites_locked"], getStatusData["GPS_satellites_seen"], getStatusData["GPS_satellites_tracked"]) + if getStatusData["GPS_solution"] == "GPS + SBAS (WAAS / EGNOS)": + t = t + " (WAAS)" + #print t + draw.text((pad, 45), t, font=font2, fill=255) + + n = n+1 + + +stratuxscreen = StratuxScreen() +daemon_runner = runner.DaemonRunner(stratuxscreen) +daemon_runner.do_action() From e4916a9de6be7c29083a3a832120dddf11e06ec6 Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Sun, 11 Sep 2016 18:48:56 -0400 Subject: [PATCH 014/128] Add back DHCP default route. Fixes some issues with Android. Cellular no longer usable on iPad when connected. --- image/dhcpd.conf | 1 + 1 file changed, 1 insertion(+) diff --git a/image/dhcpd.conf b/image/dhcpd.conf index 83939f18..fc267f2a 100644 --- a/image/dhcpd.conf +++ b/image/dhcpd.conf @@ -110,6 +110,7 @@ log-facility local7; subnet 192.168.10.0 netmask 255.255.255.0 { range 192.168.10.10 192.168.10.50; option broadcast-address 192.168.10.255; + option routers 192.168.10.1; default-lease-time 12000; max-lease-time 12000; option domain-name "stratux.local"; From 89c82762b71f7cfc488e5e3f755c0d2fc70199b2 Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Sun, 11 Sep 2016 18:49:01 -0400 Subject: [PATCH 015/128] Change paths. --- image/mkimg.sh | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/image/mkimg.sh b/image/mkimg.sh index 10e820c2..14e9dc4c 100755 --- a/image/mkimg.sh +++ b/image/mkimg.sh @@ -127,6 +127,7 @@ cp -f config.txt mnt/boot/ #external OLED screen apt-get install -y libjpeg-dev i2c-tools python-smbus python-pip python-dev python-pil python-daemon screen +cd /root git clone https://github.com/rm-hull/ssd1306 cd ssd1306 && python setup.py install cp /root/stratux/test/screen/screen.py /usr/bin/stratux-screen.py @@ -135,6 +136,6 @@ cp -f /root/stratux/test/screen/stratux-logo-64x64.bmp /etc/stratux-screen/strat cp -f /root/stratux/test/screen/CnC_Red_Alert.ttf /etc/stratux-screen/CnC_Red_Alert.ttf #startup scripts -cp -f __lib__systemd__system__stratux.service /lib/systemd/system/stratux.service -cp -f __root__stratux-pre-start.sh /root/stratux-pre-start.sh -cp -f __root__stratux-post-start.sh /root/stratux-post-start.sh +cp -f ../__lib__systemd__system__stratux.service mnt/lib/systemd/system/stratux.service +cp -f ../__root__stratux-pre-start.sh mnt/root/stratux-pre-start.sh +cp -f ../__root__stratux-post-start.sh mnt/root/stratux-post-start.sh From 95c1c3669e7f00af98fbabf1f098009aebd8dc38 Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Mon, 12 Sep 2016 14:43:56 -0400 Subject: [PATCH 016/128] Remove stratux-post-start.sh. Start fancontrol and screen controller from rc.local. --- __root__stratux-post-start.sh | 4 ---- image/fancontrol.py | 4 ++-- image/mkimg.sh | 4 +++- image/rc.local | 25 +++++++++++++++++++++++++ test/screen/screen.py | 6 +++--- 5 files changed, 33 insertions(+), 10 deletions(-) delete mode 100755 __root__stratux-post-start.sh create mode 100755 image/rc.local diff --git a/__root__stratux-post-start.sh b/__root__stratux-post-start.sh deleted file mode 100755 index a3a53522..00000000 --- a/__root__stratux-post-start.sh +++ /dev/null @@ -1,4 +0,0 @@ -#!/bin/bash - -/usr/bin/stratux-screen.py start -/usr/bin/fancontrol.py start diff --git a/image/fancontrol.py b/image/fancontrol.py index c8529381..5e8b9a32 100755 --- a/image/fancontrol.py +++ b/image/fancontrol.py @@ -19,8 +19,8 @@ class FanControl(): def __init__(self): self.stdin_path = '/dev/null' - self.stdout_path = '/dev/tty' - self.stderr_path = '/dev/tty' + self.stdout_path = '/var/log/fancontrol.log' + self.stderr_path = '/var/log/fancontrol.log' self.pidfile_path = '/var/run/fancontrol.pid' self.pidfile_timeout = 5 def run(self): diff --git a/image/mkimg.sh b/image/mkimg.sh index 14e9dc4c..d8b82626 100755 --- a/image/mkimg.sh +++ b/image/mkimg.sh @@ -127,6 +127,8 @@ cp -f config.txt mnt/boot/ #external OLED screen apt-get install -y libjpeg-dev i2c-tools python-smbus python-pip python-dev python-pil python-daemon screen +#for fancontrol.py: +pip install wiringpi cd /root git clone https://github.com/rm-hull/ssd1306 cd ssd1306 && python setup.py install @@ -138,4 +140,4 @@ cp -f /root/stratux/test/screen/CnC_Red_Alert.ttf /etc/stratux-screen/CnC_Red_Al #startup scripts cp -f ../__lib__systemd__system__stratux.service mnt/lib/systemd/system/stratux.service cp -f ../__root__stratux-pre-start.sh mnt/root/stratux-pre-start.sh -cp -f ../__root__stratux-post-start.sh mnt/root/stratux-post-start.sh +cp -f rc.local mnt/etc/rc.local diff --git a/image/rc.local b/image/rc.local new file mode 100755 index 00000000..6161d6c5 --- /dev/null +++ b/image/rc.local @@ -0,0 +1,25 @@ +#!/bin/sh -e +# +# rc.local +# +# This script is executed at the end of each multiuser runlevel. +# Make sure that the script will "exit 0" on success or any other +# value on error. +# +# In order to enable or disable this script just change the execution +# bits. +# +# By default this script does nothing. + +# Print the IP address +_IP=$(hostname -I) || true +if [ "$_IP" ]; then + printf "My IP address is %s\n" "$_IP" +fi + + +/usr/bin/fancontrol.py start +/usr/bin/stratux-screen.py start + + +exit 0 diff --git a/test/screen/screen.py b/test/screen/screen.py index 7b18c0ad..148cd92a 100755 --- a/test/screen/screen.py +++ b/test/screen/screen.py @@ -14,9 +14,9 @@ from daemon import runner class StratuxScreen(): def __init__(self): self.stdin_path = '/dev/null' - self.stdout_path = '/dev/tty' - self.stderr_path = '/dev/tty' - self.pidfile_path = '/var/run/fancontrol.pid' + self.stdout_path = '/var/log/stratux-screen.log' + self.stderr_path = '/var/log/stratux-screen.log' + self.pidfile_path = '/var/run/stratux-screen.pid' self.pidfile_timeout = 5 def run(self): font2 = ImageFont.truetype('/etc/stratux-screen/CnC_Red_Alert.ttf', 12) From 0d404a19bc54b0ac3f1eba7b2975adc08f08ee87 Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Mon, 12 Sep 2016 14:44:28 -0400 Subject: [PATCH 017/128] Remove stratux-post-start.sh. --- __lib__systemd__system__stratux.service | 1 - 1 file changed, 1 deletion(-) diff --git a/__lib__systemd__system__stratux.service b/__lib__systemd__system__stratux.service index 5095287a..7353a517 100644 --- a/__lib__systemd__system__stratux.service +++ b/__lib__systemd__system__stratux.service @@ -4,7 +4,6 @@ After=network.target [Service] ExecStartPre=/root/stratux-pre-start.sh -ExecStartPost=/root/stratux-post-start.sh ExecStart=/usr/bin/gen_gdl90 ExecStop=pkill dump1090 KillMode=process From 4659e03dbd1629675d16a8afa377f4ad8d62aeab Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Mon, 12 Sep 2016 15:25:53 -0400 Subject: [PATCH 018/128] Use Pin 12 (GPIO 18) for fancontrol. --- image/fancontrol.py | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/image/fancontrol.py b/image/fancontrol.py index 5e8b9a32..d3c09aeb 100755 --- a/image/fancontrol.py +++ b/image/fancontrol.py @@ -5,7 +5,7 @@ # # It expects a fan that's externally powered, and uses GPIO pin 11 for control. -import RPi.GPIO as GPIO +import RPi.GPIO as GPIO`` import time import os @@ -25,9 +25,9 @@ class FanControl(): self.pidfile_timeout = 5 def run(self): GPIO.setmode(GPIO.BOARD) - GPIO.setup(11,GPIO.OUT) + GPIO.setup(12, GPIO.OUT) GPIO.setwarnings(False) - p=GPIO.PWM(11,1000) + p=GPIO.PWM(12, 1000) PWM = 50 while True: CPU_temp = self.getCPUtemp() From 85d73964c74960cc1fd9284ea775166f2d3fa734 Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Wed, 14 Sep 2016 22:23:17 -0400 Subject: [PATCH 019/128] Typo. --- image/fancontrol.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/image/fancontrol.py b/image/fancontrol.py index d3c09aeb..584ffc98 100755 --- a/image/fancontrol.py +++ b/image/fancontrol.py @@ -5,7 +5,7 @@ # # It expects a fan that's externally powered, and uses GPIO pin 11 for control. -import RPi.GPIO as GPIO`` +import RPi.GPIO as GPIO import time import os From 9939ba986af0c48173221746371e6b74f75b226f Mon Sep 17 00:00:00 2001 From: Keith Tschohl Date: Sat, 17 Sep 2016 03:56:22 +0000 Subject: [PATCH 020/128] Ignore PUBX,00 'HAE' field if it is equal to 0 --- main/ry835ai.go | 16 +++++++++++++--- 1 file changed, 13 insertions(+), 3 deletions(-) diff --git a/main/ry835ai.go b/main/ry835ai.go index 69f30cf1..123613cf 100644 --- a/main/ry835ai.go +++ b/main/ry835ai.go @@ -579,9 +579,19 @@ func processNMEALine(l string) (sentenceUsed bool) { if err1 != nil { return false } - 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 + + // the next 'if' statement is a workaround for a ubx7 firmware bug: + // PUBX,00 reports HAE with a floor of zero (i.e. negative altitudes are set to zero). This causes GPS altitude to never read lower than -GeoidSep, + // placing minimum GPS altitude at about +80' MSL over most of North America. + // + // This does not affect GGA messages, so we can just rely on GGA to set altitude in these cases. It's a slower (1 Hz vs 5 Hz / 10 Hz), less precise + // (0.1 vs 0.001 mm resolution) report, but in practice the accuracy never gets anywhere near this resolution, so this should be an acceptable tradeoff + + if hae != 0 { + 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 + } tmpSituation.LastFixLocalTime = stratuxClock.Time From 30fe7295c47a730dc0778d72a4beb8f66fb0fd19 Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Mon, 19 Sep 2016 12:21:39 -0400 Subject: [PATCH 021/128] Add automatic serialout when /dev/serialout0 is present. /dev/serialout0 created by either inserting a CP2102-based USB-to-Serial dongle or by symlink. --- main/gen_gdl90.go | 1 + main/managementinterface.go | 16 ++++++++ main/network.go | 73 +++++++++++++++++++++++++++++++++++++ web/plates/js/settings.js | 17 ++++++++- web/plates/settings.html | 7 ++++ 5 files changed, 113 insertions(+), 1 deletion(-) diff --git a/main/gen_gdl90.go b/main/gen_gdl90.go index 96950d49..cf20526b 100644 --- a/main/gen_gdl90.go +++ b/main/gen_gdl90.go @@ -959,6 +959,7 @@ type settings struct { Ping_Enabled bool GPS_Enabled bool NetworkOutputs []networkConnection + SerialOutputs map[string]serialConnection AHRS_Enabled bool DisplayTrafficSource bool DEBUG bool diff --git a/main/managementinterface.go b/main/managementinterface.go index b0b654cf..b3741f8b 100644 --- a/main/managementinterface.go +++ b/main/managementinterface.go @@ -232,6 +232,22 @@ func handleSettingsSetRequest(w http.ResponseWriter, r *http.Request) { } case "PPM": globalSettings.PPM = int(val.(float64)) + case "Baud": + if serialOut, ok := globalSettings.SerialOutputs["/dev/serialout0"]; ok { //FIXME: Only one device for now. + newBaud := int(val.(float64)) + if newBaud == serialOut.Baud { // Same baud rate. No change. + continue + } + log.Printf("changing /dev/serialout0 baud rate from %d to %d.\n", serialOut.Baud, newBaud) + serialOut.Baud = newBaud + // Close the port if it is open. + if serialOut.serialPort != nil { + log.Printf("closing /dev/serialout0 for baud rate change.\n") + serialOut.serialPort.Close() + serialOut.serialPort = nil + } + globalSettings.SerialOutputs["/dev/serialout0"] = serialOut + } case "WatchList": globalSettings.WatchList = val.(string) case "OwnshipModeS": diff --git a/main/network.go b/main/network.go index 0b5295d7..b27011d2 100644 --- a/main/network.go +++ b/main/network.go @@ -11,6 +11,7 @@ package main import ( "errors" + "github.com/tarm/serial" "golang.org/x/net/icmp" "golang.org/x/net/ipv4" "io/ioutil" @@ -50,6 +51,12 @@ type networkConnection struct { FFCrippled bool } +type serialConnection struct { + DeviceString string + Baud int + serialPort *serial.Port +} + var messageQueue chan networkMessage var outSockets map[string]networkConnection var dhcpLeases map[string]string @@ -113,6 +120,11 @@ func isThrottled(k string) bool { } func sendToAllConnectedClients(msg networkMessage) { + if (msg.msgType & NETWORK_GDL90_STANDARD) != 0 { + // It's a GDL90 message. Send to serial output channel (which may or may not cause something to happen). + serialOutputChan <- msg.msg + } + netMutex.Lock() defer netMutex.Unlock() for k, netconn := range outSockets { @@ -159,6 +171,65 @@ func sendToAllConnectedClients(msg networkMessage) { } } +var serialOutputChan chan []byte + +// Monitor serial output channel, send to serial port. +func serialOutWatcher() { + // Check every 30 seconds for a serial output device. + serialTicker := time.NewTicker(30 * time.Second) + + serialDev := "/dev/serialout0" //FIXME: This is temporary. Only one serial output device for now. + + for { + select { + case <-serialTicker.C: + if _, err := os.Stat(serialDev); !os.IsNotExist(err) { // Check if the device file exists. + var thisSerialConn serialConnection + // Check if we need to start handling a new device. + if val, ok := globalSettings.SerialOutputs[serialDev]; !ok { + newSerialOut := serialConnection{DeviceString: serialDev, Baud: 38400} + log.Printf("detected new serial output, setting up now: %s. Default baudrate 38400.\n", serialDev) + if globalSettings.SerialOutputs == nil { + globalSettings.SerialOutputs = make(map[string]serialConnection) + } + globalSettings.SerialOutputs[serialDev] = newSerialOut + saveSettings() + thisSerialConn = newSerialOut + } else { + thisSerialConn = val + } + // Check if we need to open the connection now. + if thisSerialConn.serialPort == nil { + cfg := &serial.Config{Name: thisSerialConn.DeviceString, Baud: thisSerialConn.Baud} + p, err := serial.OpenPort(cfg) + if err != nil { + log.Printf("serialout port (%s) err: %s\n", thisSerialConn.DeviceString, err.Error()) + break // We'll attempt again in 30 seconds. + } else { + log.Printf("opened serialout: Name: %s, Baud: %d\n", thisSerialConn.DeviceString, thisSerialConn.Baud) + } + // Save the serial port connection. + thisSerialConn.serialPort = p + globalSettings.SerialOutputs[serialDev] = thisSerialConn + } + } + + case b := <-serialOutputChan: + if val, ok := globalSettings.SerialOutputs[serialDev]; ok { + if val.serialPort != nil { + _, err := val.serialPort.Write(b) + if err != nil { // Encountered an error in writing to the serial port. Close it and set Serial_out_enabled. + log.Printf("serialout (%s) port err: %s. Closing port.\n", val.DeviceString, err.Error()) + val.serialPort.Close() + val.serialPort = nil + globalSettings.SerialOutputs[serialDev] = val + } + } + } + } + } +} + // Returns the number of DHCP leases and prints queue lengths. func getNetworkStats() { @@ -511,6 +582,7 @@ func ffMonitor() { func initNetwork() { messageQueue = make(chan networkMessage, 1024) // Buffered channel, 1024 messages. + serialOutputChan = make(chan []byte, 1024) // Buffered channel, 1024 GDL90 messages. outSockets = make(map[string]networkConnection) pingResponse = make(map[string]time.Time) netMutex = &sync.Mutex{} @@ -519,4 +591,5 @@ func initNetwork() { go messageQueueSender() go sleepMonitor() go networkStatsCounter() + go serialOutWatcher() } diff --git a/web/plates/js/settings.js b/web/plates/js/settings.js index fd158dad..2f2dd8b7 100755 --- a/web/plates/js/settings.js +++ b/web/plates/js/settings.js @@ -17,6 +17,9 @@ function SettingsCtrl($rootScope, $scope, $state, $location, $window, $http) { settings = angular.fromJson(data); // consider using angular.extend() $scope.rawSettings = angular.toJson(data, true); + if ((settings.SerialOutputs !== undefined) && (settings.SerialOutputs !== null) && (settings.SerialOutputs['/dev/serialout0'] !== undefined)) { + $scope.Baud = settings.SerialOutputs['/dev/serialout0'].Baud; + } $scope.UAT_Enabled = settings.UAT_Enabled; $scope.ES_Enabled = settings.ES_Enabled; $scope.Ping_Enabled = settings.Ping_Enabled; @@ -91,6 +94,18 @@ function SettingsCtrl($rootScope, $scope, $state, $location, $window, $http) { } }; + $scope.updateBaud = function () { + settings["Baud"] = 0 + if (($scope.Baud !== undefined) && ($scope.Baud !== null) && ($scope.Baud !== settings["Baud"])) { + settings["Baud"] = parseInt($scope.Baud); + newsettings = { + "Baud": settings["Baud"] + }; + // console.log(angular.toJson(newsettings)); + setSettings(angular.toJson(newsettings)); + } + }; + $scope.updatewatchlist = function () { if ($scope.WatchList !== settings["WatchList"]) { settings["WatchList"] = ""; @@ -180,4 +195,4 @@ function SettingsCtrl($rootScope, $scope, $state, $location, $window, $http) { }); }; -}; +}; diff --git a/web/plates/settings.html b/web/plates/settings.html index 44817a0c..130db997 100755 --- a/web/plates/settings.html +++ b/web/plates/settings.html @@ -92,6 +92,13 @@ +
+ +
+ + +
+
From 31bbf1bc1b185295c712b6caa30de65228efbe1c Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Mon, 19 Sep 2016 12:25:23 -0400 Subject: [PATCH 022/128] Don't display serialout settings unless a serialout device is present. --- web/plates/js/settings.js | 2 ++ web/plates/settings.html | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/web/plates/js/settings.js b/web/plates/js/settings.js index 2f2dd8b7..8f85df85 100755 --- a/web/plates/js/settings.js +++ b/web/plates/js/settings.js @@ -17,8 +17,10 @@ function SettingsCtrl($rootScope, $scope, $state, $location, $window, $http) { settings = angular.fromJson(data); // consider using angular.extend() $scope.rawSettings = angular.toJson(data, true); + $scope.visible_serialout = false; if ((settings.SerialOutputs !== undefined) && (settings.SerialOutputs !== null) && (settings.SerialOutputs['/dev/serialout0'] !== undefined)) { $scope.Baud = settings.SerialOutputs['/dev/serialout0'].Baud; + $scope.visible_serialout = true; } $scope.UAT_Enabled = settings.UAT_Enabled; $scope.ES_Enabled = settings.ES_Enabled; diff --git a/web/plates/settings.html b/web/plates/settings.html index 130db997..641c0985 100755 --- a/web/plates/settings.html +++ b/web/plates/settings.html @@ -92,7 +92,7 @@ -
+
From dc62a3abba4caab7341ba206f71dc36594a5f4f1 Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Mon, 19 Sep 2016 18:27:19 -0400 Subject: [PATCH 023/128] Make HardwareBuild checking for updates case insensitive. --- main/managementinterface.go | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/main/managementinterface.go b/main/managementinterface.go index b3741f8b..e16d6092 100644 --- a/main/managementinterface.go +++ b/main/managementinterface.go @@ -323,7 +323,7 @@ func handleUpdatePostRequest(w http.ResponseWriter, r *http.Request) { } defer file.Close() // Special hardware builds. Don't allow an update unless the filename contains the hardware build name. - if (len(globalStatus.HardwareBuild) > 0) && !strings.Contains(handler.Filename, globalStatus.HardwareBuild) { + if (len(globalStatus.HardwareBuild) > 0) && !strings.Contains(strings.ToLower(handler.Filename), strings.ToLower(globalStatus.HardwareBuild)) { w.WriteHeader(404) return } From 2f2c3d27a33ca5593e13dfed0acebfd3257c3ccf Mon Sep 17 00:00:00 2001 From: Jim Jacobsen Date: Sat, 24 Sep 2016 12:17:46 -0500 Subject: [PATCH 024/128] Added UAT statistics to the status page --- main/gen_gdl90.go | 24 +++++++++++++++++++++++- web/plates/js/status.js | 8 +++++++- web/plates/status.html | 33 ++++++++++++++++++++++++++++++++- 3 files changed, 62 insertions(+), 3 deletions(-) mode change 100644 => 100755 main/gen_gdl90.go diff --git a/main/gen_gdl90.go b/main/gen_gdl90.go old mode 100644 new mode 100755 index cf20526b..a28f9c48 --- a/main/gen_gdl90.go +++ b/main/gen_gdl90.go @@ -766,7 +766,20 @@ func registerADSBTextMessageReceived(msg string) { } var wm WeatherMessage - + + if (x[0] == "METAR") || (x[0] == "SPECI") { + globalStatus.UAT_METAR_total++ + } + if x[0] == "TAF" { + globalStatus.UAT_TAF_total++ + } + if x[0] == "WINDS" { + globalStatus.UAT_TAF_total++ + } + if x[0] == "PIREP" { + globalStatus.UAT_PIREP_total++ + } + wm.Type = x[0] wm.Location = x[1] wm.Time = x[2] @@ -865,6 +878,7 @@ func parseInput(buf string) ([]byte, uint16) { // Get all of the "product ids". for _, f := range uatMsg.Frames { thisMsg.Products = append(thisMsg.Products, f.Product_id) + UpdateUATStats(f.Product_id) } // Get all of the text reports. textReports, _ := uatMsg.GetTextReports() @@ -999,6 +1013,14 @@ type status struct { NetworkDataMessagesSentNonqueueableLastSec uint64 NetworkDataBytesSentLastSec uint64 NetworkDataBytesSentNonqueueableLastSec uint64 + UAT_METAR_total uint32 + UAT_TAF_total uint32 + UAT_NEXRAD_total uint32 + UAT_SIGMET_total uint32 + UAT_PIREP_total uint32 + UAT_NOTAM_total uint32 + UAT_OTHER_total uint32 + Errors []string } diff --git a/web/plates/js/status.js b/web/plates/js/status.js index 1a4344c2..d243b35e 100755 --- a/web/plates/js/status.js +++ b/web/plates/js/status.js @@ -56,7 +56,13 @@ function StatusCtrl($rootScope, $scope, $state, $http, $interval) { $scope.GPS_solution = status.GPS_solution; $scope.GPS_position_accuracy = String(status.GPS_solution ? ", " + status.GPS_position_accuracy.toFixed(1) : ""); $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; + $scope.UAT_SIGMET_total = status.UAT_SIGMET_total; + $scope.UAT_PIREP_total = status.UAT_PIREP_total; + $scope.UAT_NOTAM_total = status.UAT_NOTAM_total; + $scope.UAT_OTHER_total = status.UAT_OTHER_total; // Errors array. if (status.Errors.length > 0) { $scope.visible_errors = true; diff --git a/web/plates/status.html b/web/plates/status.html index b82c5159..b56117bd 100755 --- a/web/plates/status.html +++ b/web/plates/status.html @@ -89,7 +89,38 @@
 
- +
+
+ UAT Statistics +
+
+
+
+ METARS + TAFS + NEXRAD + PIREP + SIGMET + NOTAMS + Other +
+
+
+
+ {{UAT_METAR_total}} + {{UAT_TAF_total}} + {{UAT_NEXRAD_total}} + {{UAT_PIREP_total}} + {{UAT_SIGMET_total}} + {{UAT_NOTAM_total}} + {{UAT_OTHER_total}} +
+ +
+
+
+
 
+
Uptime: From f099336823426d5ad0f59f3b88ac0a5a2c747a7b Mon Sep 17 00:00:00 2001 From: Jim Jacobsen Date: Sat, 24 Sep 2016 18:23:39 -0500 Subject: [PATCH 025/128] Fixed typo, and added TAF.AMD --- main/gen_gdl90.go | 25 ++++++++++++++++++++++++- 1 file changed, 24 insertions(+), 1 deletion(-) diff --git a/main/gen_gdl90.go b/main/gen_gdl90.go index a28f9c48..f417c240 100755 --- a/main/gen_gdl90.go +++ b/main/gen_gdl90.go @@ -770,7 +770,7 @@ func registerADSBTextMessageReceived(msg string) { if (x[0] == "METAR") || (x[0] == "SPECI") { globalStatus.UAT_METAR_total++ } - if x[0] == "TAF" { + if (x[0] == "TAF") || (x[0] == "TAF.AMD") { globalStatus.UAT_TAF_total++ } if x[0] == "WINDS" { @@ -792,6 +792,29 @@ func registerADSBTextMessageReceived(msg string) { weatherUpdate.Send(wmJSON) } +func UpdateUATStats(ProductID uint32) { + switch ProductID { + case 0,20: + globalStatus.UAT_METAR_total++ + case 1,21: + globalStatus.UAT_TAF_total++ + case 51,52,53,54,55,56,57,58,59,60,61,62,63,64,81,82,83: + globalStatus.UAT_NEXRAD_total++ + // AIRMET and SIGMETS + case 2,3,4,6,11,12,22,23,24,26,254: + globalStatus.UAT_SIGMET_total++ + case 5,25: + globalStatus.UAT_PIREP_total++ + case 8: + globalStatus.UAT_NOTAM_total++ + case 413: + // Do nothing in the case since text is recorded elsewhere + return + default: + globalStatus.UAT_OTHER_total++ + } +} + func parseInput(buf string) ([]byte, uint16) { //FIXME: We're ignoring all invalid format UAT messages (not sending to datalog). x := strings.Split(buf, ";") // Discard everything after the first ';'. From 8cef4434976f99177fc44652551c328e8c26b084 Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Mon, 26 Sep 2016 14:34:41 -0400 Subject: [PATCH 026/128] Change green (ACT) LED default behavior on RPi - off = stratux not running, on = stratux running. --- image/config.txt | 4 ++++ main/gen_gdl90.go | 5 +++++ 2 files changed, 9 insertions(+) diff --git a/image/config.txt b/image/config.txt index 937f43be..b1247655 100644 --- a/image/config.txt +++ b/image/config.txt @@ -8,3 +8,7 @@ dtparam=i2c_arm_baudrate=400000 # move RPi3 Bluetooth off of hardware UART to free up connection for GPS dtoverlay=pi3-miniuart-bt + +# disable default (mmc0) behavior on the ACT LED. +dtparam=act_led_trigger=none +dtparam=act_led_activelow=off diff --git a/main/gen_gdl90.go b/main/gen_gdl90.go index f417c240..8cbe25e5 100755 --- a/main/gen_gdl90.go +++ b/main/gen_gdl90.go @@ -570,6 +570,9 @@ func heartBeatSender() { for { select { case <-timer.C: + // Turn on green ACT LED on the Pi. + ioutil.WriteFile("/sys/class/leds/led0/brightness", []byte("1\n"), 0644) + sendGDL90(makeHeartbeat(), false) sendGDL90(makeStratuxHeartbeat(), false) sendGDL90(makeStratuxStatus(), false) @@ -1240,6 +1243,8 @@ func gracefulShutdown() { //TODO: Any other graceful shutdown functions. + // Turn off green ACT LED on the Pi. + ioutil.WriteFile("/sys/class/leds/led0/brightness", []byte("0\n"), 0644) os.Exit(1) } From bab827d4929546e0fa75c6527b5eb7799fabee87 Mon Sep 17 00:00:00 2001 From: Jim Jacobsen Date: Tue, 27 Sep 2016 23:56:17 -0500 Subject: [PATCH 027/128] Added ability to have static IP hosts --- main/network.go | 21 +++++++++++++++++++++ 1 file changed, 21 insertions(+) mode change 100644 => 100755 main/network.go diff --git a/main/network.go b/main/network.go old mode 100644 new mode 100755 index b27011d2..8f7727d5 --- a/main/network.go +++ b/main/network.go @@ -71,6 +71,7 @@ const ( NETWORK_AHRS_FFSIM = 2 NETWORK_AHRS_GDL90 = 4 dhcp_lease_file = "/var/lib/dhcp/dhcpd.leases" + extra_hosts_file = "/etc/stratux-static-hosts.conf" ) // Read the "dhcpd.leases" file and parse out IP/hostname. @@ -97,6 +98,26 @@ func getDHCPLeases() (map[string]string, error) { ret[block_ip] = "" } } + + // Added the ability to have static IP hosts stored in /etc/stratux-static-hosts.conf + + dat2, err := ioutil.ReadFile(extra_hosts_file) + if err != nil { + return ret, nil + } + + iplines := strings.Split(string(dat2), "\n") + block_ip2 := "" + for _, ipline := range iplines { + spacedip := strings.Split(ipline, " ") + if len(spacedip) == 2 { + // The ip is in block_ip2 + block_ip2 = spacedip[0] + // the hostname is here + ret[block_ip2] = spacedip[1] + } + } + return ret, nil } From 8f3ca19aca72f6561dfb4826107c6ee7eff9470f Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Thu, 29 Sep 2016 18:30:26 -0400 Subject: [PATCH 028/128] Add GPRMC date sanity checking. Add 'RealTime' monotonic ticker, set once by GPS time. --- main/monotonic.go | 16 ++++++++++++++++ main/ry835ai.go | 4 +++- 2 files changed, 19 insertions(+), 1 deletion(-) diff --git a/main/monotonic.go b/main/monotonic.go index c0e27330..c2aca2cc 100644 --- a/main/monotonic.go +++ b/main/monotonic.go @@ -21,6 +21,8 @@ type monotonic struct { Milliseconds uint64 Time time.Time ticker *time.Ticker + realTimeSet bool + RealTime time.Time } func (m *monotonic) Watcher() { @@ -28,6 +30,9 @@ func (m *monotonic) Watcher() { <-m.ticker.C m.Milliseconds += 10 m.Time = m.Time.Add(10 * time.Millisecond) + if m.realTimeSet { + m.RealTime = m.RealTime.Add(10 * time.Millisecond) + } } } @@ -43,6 +48,17 @@ func (m *monotonic) Unix() int64 { return int64(m.Since(time.Time{}).Seconds()) } +func (m *monotonic) HasRealTimeReference() bool { + return m.realTimeSet +} + +func (m *monotonic) SetRealTimeReference(t time.Time) { + if !m.realTimeSet { // Only allow the real clock to be set once. + m.RealTime = t + m.realTimeSet = true + } +} + func NewMonotonic() *monotonic { t := &monotonic{Milliseconds: 0, Time: time.Time{}, ticker: time.NewTicker(10 * time.Millisecond)} go t.Watcher() diff --git a/main/ry835ai.go b/main/ry835ai.go index 123613cf..715740bb 100644 --- a/main/ry835ai.go +++ b/main/ry835ai.go @@ -812,6 +812,7 @@ func processNMEALine(l string) (sentenceUsed bool) { // We only update ANY of the times if all of the time parsing is complete. mySituation.LastGPSTimeTime = stratuxClock.Time mySituation.GPSTime = gpsTime + stratuxClock.SetRealTimeReference(gpsTime) mySituation.LastFixSinceMidnightUTC = float32(3600*hr+60*min) + float32(sec) // log.Printf("GPS time is: %s\n", gpsTime) //debug if time.Since(gpsTime) > 3*time.Second || time.Since(gpsTime) < -3*time.Second { @@ -986,9 +987,10 @@ func processNMEALine(l string) (sentenceUsed bool) { // Date of Fix, i.e 191115 = 19 November 2015 UTC field 9 gpsTimeStr := fmt.Sprintf("%s %02d:%02d:%06.3f", x[9], hr, min, sec) gpsTime, err := time.Parse("020106 15:04:05.000", gpsTimeStr) - if err == nil { + if err == nil && gpsTime.After(time.Date(2016, time.January, 0, 0, 0, 0, 0, time.UTC)) { // Ignore dates before 2016-JAN-01. tmpSituation.LastGPSTimeTime = stratuxClock.Time tmpSituation.GPSTime = gpsTime + stratuxClock.SetRealTimeReference(gpsTime) if time.Since(gpsTime) > 3*time.Second || time.Since(gpsTime) < -3*time.Second { setStr := gpsTime.Format("20060102 15:04:05.000") + " UTC" log.Printf("setting system time to: '%s'\n", setStr) From 37309af7bb63ec93880937e22ca615862c55bb55 Mon Sep 17 00:00:00 2001 From: peepsnet Date: Fri, 30 Sep 2016 21:05:40 -0400 Subject: [PATCH 029/128] Tool to "automate" setting SDR serials The script walks users through setting serials for the SDRs and offers the "Fallback" option when setting the 1090 SDR. --- image/sdr-tool.sh | 291 ++++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 291 insertions(+) create mode 100644 image/sdr-tool.sh diff --git a/image/sdr-tool.sh b/image/sdr-tool.sh new file mode 100644 index 00000000..61123743 --- /dev/null +++ b/image/sdr-tool.sh @@ -0,0 +1,291 @@ +#!/bin/bash + +###################################################################### +# STRATUX SDR MANAGER # +###################################################################### + +#Set Script Name variable +SCRIPT=`basename ${BASH_SOURCE[0]}` + +# rtl_eeprom -d 0 -s :: +#Initialize variables to default values. +SERVICE=stratux.service +WhichSDR=1090 +FallBack=true +PPMValue=0 + +parm="*" +err="####" +att="+++" + +#Set fonts for Help. +BOLD=$(tput bold) +STOT=$(tput smso) +DIM=$(tput dim) +UNDR=$(tput smul) +REV=$(tput rev) +RED=$(tput setaf 1) +GREEN=$(tput setaf 2) +YELLOW=$(tput setaf 3) +MAGENTA=$(tput setaf 5) +WHITE=$(tput setaf 7) +NORM=$(tput sgr0) +NORMAL=$(tput sgr0) + +#This is the Title +function HEAD { + clear + echo "######################################################################" + echo "# STRATUX SDR SERIAL TOOL #" + echo "######################################################################" + echo " " +} + +function STOPSTRATUX { + + echo "Give me a few seconds to check if STRATUX is running..." + # The service we want to check (according to systemctl) + if [ "`systemctl is-active $SERVICE`" = "active" ] + then + echo "$SERVICE is currently running" + echo "Stopping..." + SDRs=`systemctl stop stratux.service` + fi +} + +#Function to set the serial function +function SETSDRSERIAL { + HEAD + echo "# Setting ${WhichSDR}mhz SDR Serial Data #" + #Build this string + # rtl_eeprom -d 0 -s :: + echo " SETTING SERIAL: " + echo " rtl_eeprom -d 0 -s stx:${WhichSDR}:${PPMValue} " + echo " " + echo "${REV}Answer 'y' to the qustion: 'Write new configuration to device [y/n]?'${NORM}" + echo " " + SDRs=`rtl_eeprom -d 0 -s stx:${WhichSDR}:${PPMValue}` + sleep 2 + echo " " + echo "Do you have another SDR to program?" + echo " 'Yes' will shutdown your STRATUX and allow you to swap SDRs." + echo " 'No' will reboot your STRATUX and return your STRATUX to normal operation." + echo " 'exit' will exit the script and return you to your shell prompt" + choices=( 'Yes' 'No' 'exit' ) + # Present the choices. + # The user chooses by entering the *number* before the desired choice. + select choice in "${choices[@]}"; do + + # If an invalid number was chosen, $choice will be empty. + # Report an error and prompt again. + [[ -n $choice ]] || { echo "Invalid choice." >&2; continue; } + + case $choice in + 'Yes') + echo "Shutting down..." + #SDRs=`shutdown -h now` + ;; + 'No') + echo "Rebooting..." + #SDRs=`reboot` + ;; + exit) + echo "Exiting. " + exit 0 + esac + break + done +} + + +function SDRInfo { + HEAD + echo "# Building ${WhichSDR}mhz SDR Serial #" + echo " " + echo "Do you have a PPM value to enter?" + echo "If not, its ok... Just choose 'No'" + choices=( 'Yes' 'No' 'exit' ) + # Present the choices. + # The user chooses by entering the *number* before the desired choice. + select choice in "${choices[@]}"; do + + # If an invalid number was chosen, $choice will be empty. + # Report an error and prompt again. + [[ -n $choice ]] || { echo "Invalid choice." >&2; continue; } + + case $choice in + 'Yes') + echo "Please enter your PPM value for your 978mhz SDR:" + read PPMValue + ;; + 'No') + echo " " + ;; + exit) + echo "Exiting. " + exit 0 + esac + break + done + SETSDRSERIAL +} + +function PICKFALLBACK { + HEAD + echo "# Gathering ${WhichSDR}mhz SDR Serial #" + echo " " + echo "${RED}${BOLD}IMPORTANT INFORMATION: READ CAREFULLY${NORM}" + echo "${BOLD}DO you want to set the 1090mhz SDR to Fall Back to 978mhz in the event of the 978mhx SDR failing inflight?${NORM}" + echo "If no serials are set on any of the attached SDRs then STRATUX will assign 978mhz to the first SDR found and 1090mhz to the remaining SDR. This is a safety featre of STRATUX to always allow users to always have access to WEATHER and METAR data in the event of one SDR failing in flight. " + echo " " + echo "When a user assigns a frequency to an SDR, via setting serials, STRATUX will always assign that frequency. NO MATTER WHAT." + echo "This could cause issues if an SDR fails in flight. If the 978mhz SDR fails in flight and the other SDR is assigned the 1090 serial this SDR will never be set to 978mhz and the user will not have access to WEATHER and METAR data" + echo " " + echo "Choosing the Fall Back mode will allow the remaining SDR to be assigned to 978mhz while keeping the PPM value, allowing the user to continue to receive WEATHER and METAR data." + echo "Fall Back mode is reccomended!" + + choices=( 'FallBack' '1090mhz' 'exit' ) + # Present the choices. + # The user chooses by entering the *number* before the desired choice. + select choice in "${choices[@]}"; do + + # If an invalid number was chosen, $choice will be empty. + # Report an error and prompt again. + [[ -n $choice ]] || { echo "Invalid choice." >&2; continue; } + + case $choice in + 'FallBack') + WhichSDR=0 + ;; + '1090mhz') + echo " " + ;; + exit) + echo "Exiting. " + exit 0 + esac + break + done + +} + +function PICKFREQ { + HEAD + echo "# Selecting Radio to set Serial #" + echo " " + echo "${BOLD}Which SDR are you setting up?${NORM}" + echo "${DIM}If you have tuned antennas make sure you have the correct SDR and antenna combination hooked up at this time and remember which antenna connection is for which antenna.${NORM}" + choices=( '978mhz' '1090mhz' 'exit' ) + # Present the choices. + # The user chooses by entering the *number* before the desired choice. + select choice in "${choices[@]}"; do + + # If an invalid number was chosen, $choice will be empty. + # Report an error and prompt again. + [[ -n $choice ]] || { echo "Invalid choice." >&2; continue; } + + case $choice in + '978mhz') + WhichSDR=978 + SDRInfo + ;; + '1090mhz') + PICKFALLBACK + SDRInfo + ;; + exit) + echo "Exiting. " + exit 0 + esac + break + done +} + +function MAINMENU { + HEAD + echo "-----------------------------------------------------------" + SDRs=`rtl_eeprom` + echo "-----------------------------------------------------------" + echo " " + echo "${BOLD}${RED}Read the lines above.${NORM}" + echo "${BOLD}How many SDRs were found?${NORM}" + + # Define the choices to present to the user, which will be + # presented line by line, prefixed by a sequential number + # (E.g., '1) copy', ...) + choices=( 'Only 1' '2 or more' 'exit' ) + # Present the choices. + # The user chooses by entering the *number* before the desired choice. + select choice in "${choices[@]}"; do + + # If an invalid number was chosen, $choice will be empty. + # Report an error and prompt again. + [[ -n $choice ]] || { echo "Invalid choice." >&2; continue; } + + case $choice in + 'Only 1') + PICKFREQ + ;; + '2 or more') + echo "#####################################################################################" + echo "# ${RED}Too Many SDRs Plugged in. Unplug all SDRs except one and try again!!${NORM} #" + echo "#####################################################################################" + exit 0 + ;; + exit) + echo "Exiting. " + exit 0 + esac + # Getting here means that a valid choice was made, + # so break out of the select statement and continue below, + # if desired. + # Note that without an explicit break (or exit) statement, + # bash will continue to prompt. + break + done +} + +function START { + echo "Help documentation for ${BOLD}${SCRIPT}.${NORM}" + echo " " + echo "This script will help you in setting your SDR serials. Please read carefully before continuing. There are many options in settings the SDR serials. Programming the SDR serials does 2 things. " + echo " " + echo "${BOLD}First:${NORM}" + echo "Setting the serials will tell your STRATUX which SDR is attached to which tuned antenna." + echo " " + echo "${BOLD}Second:${NORM}" + echo "Setting the PPM value will enhance the reception of your SDR by correcting the Frequency Error in each SDR. Each PPM value is unique to each SDR. For more info on this please refer to the Settings page in the WebUI and click on the Help in the top right." + echo " " + echo "Steps we will take:" + echo "1) Make sure you have ${BOLD}${REV}ONLY ONE${NORM} SDR plugged in at a time. Plugging in one SDR at a time will ensure they are not mixed up." + echo "2) Select which SDR we are setting the serial for." + echo "3) Add a PPM value. If you do not know or do not want to set this value this will be set to 0. " + echo "4) Write the serial to the SDR." + echo " " + echo "If you are ready to begin choose ${BOLD}Continue${NORM} to begin." + echo " Continuing will stop the STRATUX service to release the SDRs for setting the serials" + + choices=( 'Continue' 'Exit' ) + # Present the choices. + # The user chooses by entering the *number* before the desired choice. + select choice in "${choices[@]}"; do + + # If an invalid number was chosen, $choice will be empty. + # Report an error and prompt again. + [[ -n $choice ]] || { echo "Invalid choice." >&2; continue; } + + case $choice in + 'Continue') + STOPSTRATUX + MAINMENU + ;; + exit) + echo "Exiting. " + exit 0 + esac + break + done +} + +HEAD +START From f8bb2c202f1e0ed275e1a73aa375d9cdd10ebf01 Mon Sep 17 00:00:00 2001 From: peepsnet Date: Fri, 30 Sep 2016 21:08:32 -0400 Subject: [PATCH 030/128] update for sdr-tool.sh script --- selfupdate/makeupdate.sh | 1 + 1 file changed, 1 insertion(+) diff --git a/selfupdate/makeupdate.sh b/selfupdate/makeupdate.sh index d6a2d174..64c01b25 100755 --- a/selfupdate/makeupdate.sh +++ b/selfupdate/makeupdate.sh @@ -29,6 +29,7 @@ cp image/bashrc.txt work/bin/ cp image/modules.txt work/bin/ cp image/stxAliases.txt work/bin/ cp image/hostapd_manager.sh work/bin/ +cp image/sdr-tool.sh work/bin/ cp image/10-stratux.rules work/bin/ cp image/99-uavionix.rules work/bin/ cp image/motd work/bin/ From 066b61571c6a982e5730fd4ff21f8b5d7b478986 Mon Sep 17 00:00:00 2001 From: peepsnet Date: Fri, 30 Sep 2016 21:10:16 -0400 Subject: [PATCH 031/128] update for sdr-tool.sh script --- selfupdate/update_footer.sh | 3 +++ 1 file changed, 3 insertions(+) diff --git a/selfupdate/update_footer.sh b/selfupdate/update_footer.sh index bd089b64..945671e6 100755 --- a/selfupdate/update_footer.sh +++ b/selfupdate/update_footer.sh @@ -26,6 +26,9 @@ cp -f hostapd-edimax.conf /etc/hostapd/hostapd-edimax.conf #WiFi Config Manager cp -f hostapd_manager.sh /usr/sbin/ +#SDR Serial Script +cp -f sdr-tool.sh /usr/sbin/ + #boot config cp -f config.txt /boot/config.txt From c2b0e051ad2aead4b8bb4180c5e4436d81087b3e Mon Sep 17 00:00:00 2001 From: peepsnet Date: Fri, 30 Sep 2016 21:13:35 -0400 Subject: [PATCH 032/128] update for sdr-tool.sh --- image/mkimg.sh | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/image/mkimg.sh b/image/mkimg.sh index d8b82626..49745752 100755 --- a/image/mkimg.sh +++ b/image/mkimg.sh @@ -54,6 +54,10 @@ cp -f interfaces mnt/etc/network/interfaces cp stratux-wifi.sh mnt/usr/sbin/ chmod 755 mnt/usr/sbin/stratux-wifi.sh +#SDR Serial Script +cp -f sdr-tool.sh mnt/usr/sbin/sdr-tool.sh +chmod 755 mnt/usr/sbin/sdr-tool.sh + #ping udev cp -f 99-uavionix.rules mnt/etc/udev/rules.d From 0b71091b341f9326654ed4e7c36096061f27a976 Mon Sep 17 00:00:00 2001 From: peepsnet Date: Fri, 30 Sep 2016 21:24:38 -0400 Subject: [PATCH 033/128] added sdr-tool.sh info --- image/stxAliases.txt | 1 + 1 file changed, 1 insertion(+) diff --git a/image/stxAliases.txt b/image/stxAliases.txt index d97ccc2f..323e7e27 100644 --- a/image/stxAliases.txt +++ b/image/stxAliases.txt @@ -53,6 +53,7 @@ echo "kalChan1 Use the Chan from above to get ppm pf SDR1. Exam echo "setSerial0 Set the PPM error to SDR0. Value from kalChan0. Example: setSerial0 -45" echo "setSerial1 Set the PPM error to SDR1. Value from kalChan1. Example: setSerial1 23" echo "hostapd_manager.sh Sets the Change SSID, Channel, or Encryption for your Stratux" +echo "sdr-tool.sh Tool to walk you though setting your SDRs Serials" echo "raspi-config Open Raspberry Pi settings to expand filesystem" } From 06cbb8c50898ba5aa6f4370d4b0832fe57feb972 Mon Sep 17 00:00:00 2001 From: peepsnet Date: Fri, 30 Sep 2016 21:35:09 -0400 Subject: [PATCH 034/128] uncommented a few need lines --- image/sdr-tool.sh | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/image/sdr-tool.sh b/image/sdr-tool.sh index 61123743..5b937565 100644 --- a/image/sdr-tool.sh +++ b/image/sdr-tool.sh @@ -82,12 +82,12 @@ function SETSDRSERIAL { case $choice in 'Yes') - echo "Shutting down..." - #SDRs=`shutdown -h now` - ;; + echo "Shutting down..." + SDRs=`shutdown -h now` + ;; 'No') echo "Rebooting..." - #SDRs=`reboot` + SDRs=`reboot` ;; exit) echo "Exiting. " From 8929116f00cc5a31a8f455bbd78af88238e7ab17 Mon Sep 17 00:00:00 2001 From: Christopher Young Date: Sat, 1 Oct 2016 11:48:27 -0400 Subject: [PATCH 035/128] Formatting. --- main/gen_gdl90.go | 74 +++++++++++++++++++++++------------------------ main/network.go | 34 +++++++++++----------- 2 files changed, 54 insertions(+), 54 deletions(-) diff --git a/main/gen_gdl90.go b/main/gen_gdl90.go index 8cbe25e5..e1724e97 100755 --- a/main/gen_gdl90.go +++ b/main/gen_gdl90.go @@ -769,20 +769,20 @@ func registerADSBTextMessageReceived(msg string) { } var wm WeatherMessage - - if (x[0] == "METAR") || (x[0] == "SPECI") { - globalStatus.UAT_METAR_total++ - } - if (x[0] == "TAF") || (x[0] == "TAF.AMD") { - globalStatus.UAT_TAF_total++ - } - if x[0] == "WINDS" { - globalStatus.UAT_TAF_total++ - } - if x[0] == "PIREP" { - globalStatus.UAT_PIREP_total++ - } - + + if (x[0] == "METAR") || (x[0] == "SPECI") { + globalStatus.UAT_METAR_total++ + } + if (x[0] == "TAF") || (x[0] == "TAF.AMD") { + globalStatus.UAT_TAF_total++ + } + if x[0] == "WINDS" { + globalStatus.UAT_TAF_total++ + } + if x[0] == "PIREP" { + globalStatus.UAT_PIREP_total++ + } + wm.Type = x[0] wm.Location = x[1] wm.Time = x[2] @@ -796,26 +796,26 @@ func registerADSBTextMessageReceived(msg string) { } func UpdateUATStats(ProductID uint32) { - switch ProductID { - case 0,20: - globalStatus.UAT_METAR_total++ - case 1,21: - globalStatus.UAT_TAF_total++ - case 51,52,53,54,55,56,57,58,59,60,61,62,63,64,81,82,83: - globalStatus.UAT_NEXRAD_total++ - // AIRMET and SIGMETS - case 2,3,4,6,11,12,22,23,24,26,254: - globalStatus.UAT_SIGMET_total++ - case 5,25: - globalStatus.UAT_PIREP_total++ - case 8: - globalStatus.UAT_NOTAM_total++ - case 413: - // Do nothing in the case since text is recorded elsewhere - return - default: - globalStatus.UAT_OTHER_total++ - } + switch ProductID { + case 0, 20: + globalStatus.UAT_METAR_total++ + case 1, 21: + globalStatus.UAT_TAF_total++ + case 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 64, 81, 82, 83: + globalStatus.UAT_NEXRAD_total++ + // AIRMET and SIGMETS + case 2, 3, 4, 6, 11, 12, 22, 23, 24, 26, 254: + globalStatus.UAT_SIGMET_total++ + case 5, 25: + globalStatus.UAT_PIREP_total++ + case 8: + globalStatus.UAT_NOTAM_total++ + case 413: + // Do nothing in the case since text is recorded elsewhere + return + default: + globalStatus.UAT_OTHER_total++ + } } func parseInput(buf string) ([]byte, uint16) { @@ -904,7 +904,7 @@ func parseInput(buf string) ([]byte, uint16) { // Get all of the "product ids". for _, f := range uatMsg.Frames { thisMsg.Products = append(thisMsg.Products, f.Product_id) - UpdateUATStats(f.Product_id) + UpdateUATStats(f.Product_id) } // Get all of the text reports. textReports, _ := uatMsg.GetTextReports() @@ -1046,8 +1046,8 @@ type status struct { UAT_PIREP_total uint32 UAT_NOTAM_total uint32 UAT_OTHER_total uint32 - - Errors []string + + Errors []string } var globalSettings settings diff --git a/main/network.go b/main/network.go index 8f7727d5..9a11f651 100755 --- a/main/network.go +++ b/main/network.go @@ -71,7 +71,7 @@ const ( NETWORK_AHRS_FFSIM = 2 NETWORK_AHRS_GDL90 = 4 dhcp_lease_file = "/var/lib/dhcp/dhcpd.leases" - extra_hosts_file = "/etc/stratux-static-hosts.conf" + extra_hosts_file = "/etc/stratux-static-hosts.conf" ) // Read the "dhcpd.leases" file and parse out IP/hostname. @@ -98,26 +98,26 @@ func getDHCPLeases() (map[string]string, error) { ret[block_ip] = "" } } - - // Added the ability to have static IP hosts stored in /etc/stratux-static-hosts.conf - - dat2, err := ioutil.ReadFile(extra_hosts_file) - if err != nil { - return ret, nil - } - - iplines := strings.Split(string(dat2), "\n") + + // Added the ability to have static IP hosts stored in /etc/stratux-static-hosts.conf + + dat2, err := ioutil.ReadFile(extra_hosts_file) + if err != nil { + return ret, nil + } + + iplines := strings.Split(string(dat2), "\n") block_ip2 := "" for _, ipline := range iplines { spacedip := strings.Split(ipline, " ") - if len(spacedip) == 2 { - // The ip is in block_ip2 - block_ip2 = spacedip[0] - // the hostname is here - ret[block_ip2] = spacedip[1] - } + if len(spacedip) == 2 { + // The ip is in block_ip2 + block_ip2 = spacedip[0] + // the hostname is here + ret[block_ip2] = spacedip[1] + } } - + return ret, nil } From 9f1fd88485c91e41bcbff4919bacb3267c1d4cd4 Mon Sep 17 00:00:00 2001 From: Jim Jacobsen Date: Sat, 1 Oct 2016 19:59:41 -0500 Subject: [PATCH 036/128] Added developer mode handing from /etc/stratux.conf instead, then this allows options in the status and settings pages. Would like to add a menu option for this in the future though --- main/gen_gdl90.go | 13 ++++++------- web/plates/js/settings.js | 1 + web/plates/js/status.js | 1 + web/plates/settings.html | 13 +++++++++++++ web/plates/status.html | 11 +++++++++++ 5 files changed, 32 insertions(+), 7 deletions(-) diff --git a/main/gen_gdl90.go b/main/gen_gdl90.go index e1724e97..8bbad739 100755 --- a/main/gen_gdl90.go +++ b/main/gen_gdl90.go @@ -100,7 +100,6 @@ type ReadCloser interface { io.Closer } -var developerMode bool type msg struct { MessageClass uint @@ -1301,7 +1300,8 @@ func main() { // replayESFilename := flag.String("eslog", "none", "ES Log filename") replayUATFilename := flag.String("uatlog", "none", "UAT Log filename") - develFlag := flag.Bool("developer", false, "Developer mode") + // Removed here, but may replace later +// develFlag := flag.Bool("developer", false, "Developer mode") replayFlag := flag.Bool("replay", false, "Replay file flag") replaySpeed := flag.Int("speed", 1, "Replay speed multiplier") stdinFlag := flag.Bool("uatin", false, "Process UAT messages piped to stdin") @@ -1311,11 +1311,6 @@ func main() { timeStarted = time.Now() runtime.GOMAXPROCS(runtime.NumCPU()) // redundant with Go v1.5+ compiler - if *develFlag == true { - log.Printf("Developer mode flag true!\n") - developerMode = true - } - // Duplicate log.* output to debugLog. fp, err := os.OpenFile(debugLogf, os.O_CREATE|os.O_WRONLY|os.O_APPEND, 0666) if err != nil { @@ -1350,6 +1345,10 @@ func main() { globalSettings.ReplayLog = true } + if globalSettings.DeveloperMode == true { + log.Printf("Developer mode set\n") + } + //FIXME: Only do this if data logging is enabled. initDataLog() diff --git a/web/plates/js/settings.js b/web/plates/js/settings.js index 8f85df85..52b18099 100755 --- a/web/plates/js/settings.js +++ b/web/plates/js/settings.js @@ -33,6 +33,7 @@ function SettingsCtrl($rootScope, $scope, $state, $location, $window, $http) { $scope.PPM = settings.PPM; $scope.WatchList = settings.WatchList; $scope.OwnshipModeS = settings.OwnshipModeS; + $scope.DeveloperMode = settings.DeveloperMode; } function getSettings() { diff --git a/web/plates/js/status.js b/web/plates/js/status.js index d243b35e..97c84828 100755 --- a/web/plates/js/status.js +++ b/web/plates/js/status.js @@ -101,6 +101,7 @@ function StatusCtrl($rootScope, $scope, $state, $http, $interval) { $http.get(URL_SETTINGS_GET). then(function (response) { settings = angular.fromJson(response.data); + $scope.developerMode = settings.DeveloperMode; $scope.visible_uat = settings.UAT_Enabled; $scope.visible_es = settings.ES_Enabled; $scope.visible_ping = settings.Ping_Enabled; diff --git a/web/plates/settings.html b/web/plates/settings.html index 641c0985..d3987a01 100755 --- a/web/plates/settings.html +++ b/web/plates/settings.html @@ -134,6 +134,19 @@
+ +
+
+
+
Developer Options
+
+
+

Coming soon

+
+
+
+
+