kopia lustrzana https://github.com/cyoung/stratux
Merge remote-tracking branch 'origin/master' into ahrs_dev
# Conflicts: # main/gps.go # main/traffic.gopull/598/head
commit
17b719f755
|
@ -43,9 +43,9 @@ echo "stxstart Start Stratux Service."
|
||||||
echo "sdr0 Test to see if sdr0 is in use by Stratux."
|
echo "sdr0 Test to see if sdr0 is in use by Stratux."
|
||||||
echo "sdr1 Test to see if sdr1 is in use by Startux."
|
echo "sdr1 Test to see if sdr1 is in use by Startux."
|
||||||
echo "sdrs Test to see if both SDRs are in use by Stratux."
|
echo "sdrs Test to see if both SDRs are in use by Stratux."
|
||||||
echo "d90 List my SDRs with serials"
|
echo "d90 Run dump1090 on SDR0"
|
||||||
echo "d900 Run dump1090 on SDR0 in interactive mode."
|
echo "d900 Run dump1090 on SDR0 in interactive mode."
|
||||||
echo "d901 Run dump1090 on SDR0 in interactive mode."
|
echo "d901 Run dump1090 on SDR1 in interactive mode."
|
||||||
echo "kal0 Find Channels for calibrating PPM of SDR0."
|
echo "kal0 Find Channels for calibrating PPM of SDR0."
|
||||||
echo "kal1 Find Channels for calibrating PPM of SDR1."
|
echo "kal1 Find Channels for calibrating PPM of SDR1."
|
||||||
echo "kalChan0 Use the Chan from above to get ppm pf SDR0. Example: kalChan0 151"
|
echo "kalChan0 Use the Chan from above to get ppm pf SDR0. Example: kalChan0 151"
|
||||||
|
@ -53,7 +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 "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 "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 "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 "sdr-tool.sh Tool to walk you though setting your SDRs Serials"
|
||||||
echo "raspi-config Open Raspberry Pi settings to expand filesystem"
|
echo "raspi-config Open Raspberry Pi settings to expand filesystem"
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,6 +1,6 @@
|
||||||
/*
|
/*
|
||||||
Copyright (c) 2015-2016 Christopher Young
|
Copyright (c) 2015-2016 Christopher Young
|
||||||
Distributable under the terms of The "BSD New"" License
|
Distributable under the terms of The "BSD New" License
|
||||||
that can be found in the LICENSE file, herein included
|
that can be found in the LICENSE file, herein included
|
||||||
as part of this header.
|
as part of this header.
|
||||||
|
|
||||||
|
|
|
@ -1,6 +1,6 @@
|
||||||
/*
|
/*
|
||||||
Copyright (c) 2015-2016 Christopher Young
|
Copyright (c) 2015-2016 Christopher Young
|
||||||
Distributable under the terms of The "BSD New"" License
|
Distributable under the terms of The "BSD New" License
|
||||||
that can be found in the LICENSE file, herein included
|
that can be found in the LICENSE file, herein included
|
||||||
as part of this header.
|
as part of this header.
|
||||||
|
|
||||||
|
@ -581,6 +581,11 @@ func makeHeartbeat() []byte {
|
||||||
}
|
}
|
||||||
msg[1] = msg[1] | 0x10 //FIXME: Addr talkback.
|
msg[1] = msg[1] | 0x10 //FIXME: Addr talkback.
|
||||||
|
|
||||||
|
// "Maintenance Req'd". Add flag if there are any current critical system errors.
|
||||||
|
if len(globalStatus.Errors) > 0 {
|
||||||
|
msg[1] = msg[1] | 0x40
|
||||||
|
}
|
||||||
|
|
||||||
nowUTC := time.Now().UTC()
|
nowUTC := time.Now().UTC()
|
||||||
// Seconds since 0000Z.
|
// Seconds since 0000Z.
|
||||||
midnightUTC := time.Date(nowUTC.Year(), nowUTC.Month(), nowUTC.Day(), 0, 0, 0, 0, time.UTC)
|
midnightUTC := time.Date(nowUTC.Year(), nowUTC.Month(), nowUTC.Day(), 0, 0, 0, 0, time.UTC)
|
||||||
|
@ -612,14 +617,37 @@ func relayMessage(msgtype uint16, msg []byte) {
|
||||||
sendGDL90(prepareMessage(ret), true)
|
sendGDL90(prepareMessage(ret), true)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
func blinkStatusLED() {
|
||||||
|
timer := time.NewTicker(100 * time.Millisecond)
|
||||||
|
ledON := false
|
||||||
|
for {
|
||||||
|
<-timer.C
|
||||||
|
if ledON {
|
||||||
|
ioutil.WriteFile("/sys/class/leds/led0/brightness", []byte("0\n"), 0644)
|
||||||
|
} else {
|
||||||
|
ioutil.WriteFile("/sys/class/leds/led0/brightness", []byte("1\n"), 0644)
|
||||||
|
}
|
||||||
|
ledON = !ledON
|
||||||
|
}
|
||||||
|
}
|
||||||
func heartBeatSender() {
|
func heartBeatSender() {
|
||||||
timer := time.NewTicker(1 * time.Second)
|
timer := time.NewTicker(1 * time.Second)
|
||||||
timerMessageStats := time.NewTicker(2 * time.Second)
|
timerMessageStats := time.NewTicker(2 * time.Second)
|
||||||
|
ledBlinking := false
|
||||||
for {
|
for {
|
||||||
select {
|
select {
|
||||||
case <-timer.C:
|
case <-timer.C:
|
||||||
// Turn on green ACT LED on the Pi.
|
// Green LED - always on during normal operation.
|
||||||
ioutil.WriteFile("/sys/class/leds/led0/brightness", []byte("1\n"), 0644)
|
// Blinking when there is a critical system error (and Stratux is still running).
|
||||||
|
|
||||||
|
if len(globalStatus.Errors) == 0 { // Any system errors?
|
||||||
|
// Turn on green ACT LED on the Pi.
|
||||||
|
ioutil.WriteFile("/sys/class/leds/led0/brightness", []byte("1\n"), 0644)
|
||||||
|
} else if !ledBlinking {
|
||||||
|
// This assumes that system errors do not disappear until restart.
|
||||||
|
go blinkStatusLED()
|
||||||
|
ledBlinking = true
|
||||||
|
}
|
||||||
|
|
||||||
sendGDL90(makeHeartbeat(), false)
|
sendGDL90(makeHeartbeat(), false)
|
||||||
sendGDL90(makeStratuxHeartbeat(), false)
|
sendGDL90(makeStratuxHeartbeat(), false)
|
||||||
|
|
92
main/gps.go
92
main/gps.go
|
@ -1,6 +1,6 @@
|
||||||
/*
|
/*
|
||||||
Copyright (c) 2015-2016 Christopher Young
|
Copyright (c) 2015-2016 Christopher Young
|
||||||
Distributable under the terms of The "BSD New"" License
|
Distributable under the terms of The "BSD New" License
|
||||||
that can be found in the LICENSE file, herein included
|
that can be found in the LICENSE file, herein included
|
||||||
as part of this header.
|
as part of this header.
|
||||||
|
|
||||||
|
@ -30,7 +30,7 @@ const (
|
||||||
SAT_TYPE_UNKNOWN = 0 // default type
|
SAT_TYPE_UNKNOWN = 0 // default type
|
||||||
SAT_TYPE_GPS = 1 // GPxxx; NMEA IDs 1-32
|
SAT_TYPE_GPS = 1 // GPxxx; NMEA IDs 1-32
|
||||||
SAT_TYPE_GLONASS = 2 // GLxxx; NMEA IDs 65-88
|
SAT_TYPE_GLONASS = 2 // GLxxx; NMEA IDs 65-88
|
||||||
SAT_TYPE_GALILEO = 3 // GAxxx; NMEA IDs unknown
|
SAT_TYPE_GALILEO = 3 // GAxxx; NMEA IDs
|
||||||
SAT_TYPE_BEIDOU = 4 // GBxxx; NMEA IDs 201-235
|
SAT_TYPE_BEIDOU = 4 // GBxxx; NMEA IDs 201-235
|
||||||
SAT_TYPE_SBAS = 10 // NMEA IDs 33-54
|
SAT_TYPE_SBAS = 10 // NMEA IDs 33-54
|
||||||
)
|
)
|
||||||
|
@ -113,6 +113,7 @@ type gpsPerfStats struct {
|
||||||
gpsPitch float64 // estimated pitch angle, deg. Calculated from gps ground speed and VV. Equal to flight path angle.
|
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.
|
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.
|
gpsLoadFactor float64 // estimated load factor from turn rate and groundspeed, "gee". Assumes airplane in coordinated turns.
|
||||||
|
//TODO: valid/invalid flag.
|
||||||
}
|
}
|
||||||
|
|
||||||
var gpsPerf gpsPerfStats
|
var gpsPerf gpsPerfStats
|
||||||
|
@ -258,9 +259,8 @@ func initGPSSerial() bool {
|
||||||
} else {
|
} else {
|
||||||
// Byte order for UBX configuration is little endian.
|
// Byte order for UBX configuration is little endian.
|
||||||
|
|
||||||
// Set 10 Hz update to make gpsattitude more responsive for ublox7/8.
|
// Set 10 Hz update to make gpsattitude more responsive for ublox7.
|
||||||
p.Write(makeUBXCFG(0x06, 0x08, 6, []byte{0x64, 0x00, 0x01, 0x00, 0x01, 0x00})) // 10 Hz
|
updatespeed := []byte{0x64, 0x00, 0x01, 0x00, 0x01, 0x00} // 10 Hz
|
||||||
//p.Write(makeUBXCFG(0x06, 0x08, 6, []byte{0xc8, 0x00, 0x01, 0x00, 0x01, 0x00})) // 5 Hz
|
|
||||||
|
|
||||||
// Set navigation settings.
|
// Set navigation settings.
|
||||||
nav := make([]byte, 36)
|
nav := make([]byte, 36)
|
||||||
|
@ -281,26 +281,32 @@ func initGPSSerial() bool {
|
||||||
// gpsattitude too much -- without WAAS corrections, the algorithm could get jumpy at higher
|
// gpsattitude too much -- without WAAS corrections, the algorithm could get jumpy at higher
|
||||||
// sampling rates.
|
// sampling rates.
|
||||||
|
|
||||||
cfgGnss := []byte{0x00, 0x20, 0x20, 0x05}
|
cfgGnss := []byte{0x00, 0x20, 0x20, 0x06}
|
||||||
gps := []byte{0x00, 0x08, 0x10, 0x00, 0x01, 0x00, 0x01, 0x01} // enable GPS with 8-16 tracking channels
|
gps := []byte{0x00, 0x08, 0x10, 0x00, 0x01, 0x00, 0x01, 0x01} // enable GPS with 8-16 tracking channels
|
||||||
sbas := []byte{0x01, 0x02, 0x03, 0x00, 0x01, 0x00, 0x01, 0x01} // enable SBAS (WAAS) with 2-3 tracking channels
|
sbas := []byte{0x01, 0x02, 0x03, 0x00, 0x01, 0x00, 0x01, 0x01} // enable SBAS (WAAS) with 2-3 tracking channels
|
||||||
beidou := []byte{0x03, 0x00, 0x10, 0x00, 0x00, 0x00, 0x01, 0x01}
|
beidou := []byte{0x03, 0x00, 0x10, 0x00, 0x00, 0x00, 0x01, 0x01}
|
||||||
qzss := []byte{0x05, 0x00, 0x03, 0x00, 0x00, 0x00, 0x01, 0x01}
|
qzss := []byte{0x05, 0x00, 0x03, 0x00, 0x00, 0x00, 0x01, 0x01}
|
||||||
glonass := []byte{0x06, 0x04, 0x0E, 0x00, 0x00, 0x00, 0x01, 0x01} // this disables GLONASS
|
glonass := []byte{0x06, 0x04, 0x0E, 0x00, 0x00, 0x00, 0x01, 0x01} // this disables GLONASS
|
||||||
|
galileo := []byte{0x02, 0x04, 0x08, 0x00, 0x00, 0x00, 0x01, 0x01} // this disables Galileo
|
||||||
|
|
||||||
if (globalStatus.GPS_detected_type == GPS_TYPE_UBX8) || (globalStatus.GPS_detected_type == GPS_TYPE_UART) { // assume that any GPS connected to serial GPIO is ublox8 (RY835/6AI)
|
if (globalStatus.GPS_detected_type == GPS_TYPE_UBX8) || (globalStatus.GPS_detected_type == GPS_TYPE_UART) { // assume that any GPS connected to serial GPIO is ublox8 (RY835/6AI)
|
||||||
//log.Printf("UBX8 device detected on USB, or GPS serial connection in use. Attempting GLONASS configuration.\n")
|
//log.Printf("UBX8 device detected on USB, or GPS serial connection in use. Attempting GLONASS and Galelio configuration.\n")
|
||||||
glonass = []byte{0x06, 0x08, 0x0E, 0x00, 0x01, 0x00, 0x01, 0x01} // this enables GLONASS with 8-14 tracking channels
|
glonass = []byte{0x06, 0x08, 0x0E, 0x00, 0x01, 0x00, 0x01, 0x01} // this enables GLONASS with 8-14 tracking channels
|
||||||
|
galileo = []byte{0x02, 0x04, 0x08, 0x00, 0x01, 0x00, 0x01, 0x01} // this enables Galileo with 4-8 tracking channels
|
||||||
|
updatespeed = []byte{0x06, 0x00, 0xF4, 0x01, 0x01, 0x00} // Nav speed 2Hz
|
||||||
}
|
}
|
||||||
cfgGnss = append(cfgGnss, gps...)
|
cfgGnss = append(cfgGnss, gps...)
|
||||||
cfgGnss = append(cfgGnss, sbas...)
|
cfgGnss = append(cfgGnss, sbas...)
|
||||||
cfgGnss = append(cfgGnss, beidou...)
|
cfgGnss = append(cfgGnss, beidou...)
|
||||||
cfgGnss = append(cfgGnss, qzss...)
|
cfgGnss = append(cfgGnss, qzss...)
|
||||||
cfgGnss = append(cfgGnss, glonass...)
|
cfgGnss = append(cfgGnss, glonass...)
|
||||||
|
cfgGnss = append(cfgGnss, galileo...)
|
||||||
p.Write(makeUBXCFG(0x06, 0x3E, uint16(len(cfgGnss)), cfgGnss))
|
p.Write(makeUBXCFG(0x06, 0x3E, uint16(len(cfgGnss)), cfgGnss))
|
||||||
|
|
||||||
// SBAS configuration for ublox 6 and higher
|
// SBAS configuration for ublox 6 and higher
|
||||||
p.Write(makeUBXCFG(0x06, 0x16, 8, []byte{0x01, 0x07, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00}))
|
p.Write(makeUBXCFG(0x06, 0x16, 8, []byte{0x01, 0x07, 0x03, 0x00, 0x00, 0x00, 0x00, 0x00}))
|
||||||
|
//Navigation Rate 10Hz for <= UBX7 2Hz for UBX8
|
||||||
|
p.Write(makeUBXCFG(0x06, 0x08, 6, updatespeed))
|
||||||
|
|
||||||
// Message output configuration: UBX,00 (position) on each calculated fix; UBX,03 (satellite info) every 5th fix,
|
// Message output configuration: UBX,00 (position) on each calculated fix; UBX,03 (satellite info) every 5th fix,
|
||||||
// UBX,04 (timing) every 10th, GGA (NMEA position) every 5th. All other NMEA messages disabled.
|
// UBX,04 (timing) every 10th, GGA (NMEA position) every 5th. All other NMEA messages disabled.
|
||||||
|
@ -324,6 +330,50 @@ func initGPSSerial() bool {
|
||||||
p.Write(makeUBXCFG(0x06, 0x01, 8, []byte{0xF1, 0x03, 0x00, 0x05, 0x00, 0x05, 0x00, 0x00})) // Ublox,3
|
p.Write(makeUBXCFG(0x06, 0x01, 8, []byte{0xF1, 0x03, 0x00, 0x05, 0x00, 0x05, 0x00, 0x00})) // Ublox,3
|
||||||
p.Write(makeUBXCFG(0x06, 0x01, 8, []byte{0xF1, 0x04, 0x00, 0x0A, 0x00, 0x0A, 0x00, 0x00})) // Ublox,4
|
p.Write(makeUBXCFG(0x06, 0x01, 8, []byte{0xF1, 0x04, 0x00, 0x0A, 0x00, 0x0A, 0x00, 0x00})) // Ublox,4
|
||||||
|
|
||||||
|
// Power save mode.
|
||||||
|
|
||||||
|
// UBX-CFG-PM2.
|
||||||
|
pm2 := make([]byte, 44)
|
||||||
|
pm2[0] = 1 // Version.
|
||||||
|
|
||||||
|
// flags.
|
||||||
|
pm2[4] = 0
|
||||||
|
pm2[5] = 0 // ON/OFF mode.
|
||||||
|
pm2[6] = 4 + 8 + 16 // WaitTimeFix+updateRTC+updateEPH.
|
||||||
|
pm2[7] = 32 // extintWake.
|
||||||
|
|
||||||
|
// updatePeriod.
|
||||||
|
pm2[8] = 0
|
||||||
|
pm2[9] = 0
|
||||||
|
pm2[10] = 0x3A // 15000ms.
|
||||||
|
pm2[11] = 0x98
|
||||||
|
|
||||||
|
// searchPeriod.
|
||||||
|
pm2[12] = 0
|
||||||
|
pm2[13] = 0
|
||||||
|
pm2[14] = 0x3A // 15000ms.
|
||||||
|
pm2[15] = 0x98
|
||||||
|
|
||||||
|
// gridOffset.
|
||||||
|
pm2[16] = 0
|
||||||
|
pm2[17] = 0
|
||||||
|
pm2[18] = 0
|
||||||
|
pm2[19] = 0
|
||||||
|
|
||||||
|
// onTime.
|
||||||
|
pm2[20] = 0
|
||||||
|
pm2[21] = 15 // 15s.
|
||||||
|
|
||||||
|
// minAcqTime.
|
||||||
|
pm2[22] = 0
|
||||||
|
pm2[23] = 15 // 15s.
|
||||||
|
|
||||||
|
p.Write(makeUBXCFG(0x06, 0x3B, 44, pm2))
|
||||||
|
|
||||||
|
// UBX-CFG-RXM.
|
||||||
|
|
||||||
|
p.Write(makeUBXCFG(0x06, 0x11, 2, []byte{8, 1})) // Enable.
|
||||||
|
|
||||||
// Reconfigure serial port.
|
// Reconfigure serial port.
|
||||||
cfg := make([]byte, 20)
|
cfg := make([]byte, 20)
|
||||||
cfg[0] = 0x01 // portID.
|
cfg[0] = 0x01 // portID.
|
||||||
|
@ -697,7 +747,7 @@ func calcGPSAttitude() bool {
|
||||||
//log.Printf("\n")
|
//log.Printf("\n")
|
||||||
//log.Printf("tempHdg: %v\n", tempHdg)
|
//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
|
// Next, unwrap the heading so we don't mess up the regression by fitting a line across the 0/360 deg discontinuity.
|
||||||
lengthHeading = len(tempHdg)
|
lengthHeading = len(tempHdg)
|
||||||
tempHdgUnwrapped = make([]float64, lengthHeading, lengthHeading)
|
tempHdgUnwrapped = make([]float64, lengthHeading, lengthHeading)
|
||||||
tempRegWeights = make([]float64, lengthHeading, lengthHeading)
|
tempRegWeights = make([]float64, lengthHeading, lengthHeading)
|
||||||
|
@ -775,7 +825,7 @@ func calcGPSAttitude() bool {
|
||||||
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
g := 32.174 // ft-s^-2
|
g := 32.174 // ft/(s^2)
|
||||||
omega = radians(myGPSPerfStats[index].gpsTurnRate) // need radians/sec
|
omega = radians(myGPSPerfStats[index].gpsTurnRate) // need radians/sec
|
||||||
a_c = v_x * omega
|
a_c = v_x * omega
|
||||||
myGPSPerfStats[index].gpsRoll = math.Atan2(a_c, g) * 180 / math.Pi // output is degrees
|
myGPSPerfStats[index].gpsRoll = math.Atan2(a_c, g) * 180 / math.Pi // output is degrees
|
||||||
|
@ -786,11 +836,12 @@ func calcGPSAttitude() bool {
|
||||||
myGPSPerfStats[index].gpsLoadFactor = 1
|
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 {
|
if globalSettings.DEBUG {
|
||||||
|
// 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)
|
||||||
log.Printf("%s", buf) // FIXME. Send to sqlite log or other file?
|
log.Printf("%s", buf) // FIXME. Send to sqlite log or other file?
|
||||||
}
|
}
|
||||||
|
|
||||||
logGPSAttitude(myGPSPerfStats[index])
|
logGPSAttitude(myGPSPerfStats[index])
|
||||||
//replayLog(buf, MSGCLASS_AHRS)
|
//replayLog(buf, MSGCLASS_AHRS)
|
||||||
return true
|
return true
|
||||||
|
@ -1103,6 +1154,9 @@ func processNMEALine(l string) (sentenceUsed bool) {
|
||||||
svType = SAT_TYPE_SBAS
|
svType = SAT_TYPE_SBAS
|
||||||
svStr = fmt.Sprintf("S%d", sv)
|
svStr = fmt.Sprintf("S%d", sv)
|
||||||
sv -= 87 // subtract 87 to convert to NMEA from PRN.
|
sv -= 87 // subtract 87 to convert to NMEA from PRN.
|
||||||
|
} else if sv > 210 {
|
||||||
|
svType = SAT_TYPE_GALILEO
|
||||||
|
svStr = fmt.Sprintf("E%d", sv-210)
|
||||||
} else { //TODO: Galileo
|
} else { //TODO: Galileo
|
||||||
svType = SAT_TYPE_UNKNOWN
|
svType = SAT_TYPE_UNKNOWN
|
||||||
svStr = fmt.Sprintf("U%d", sv)
|
svStr = fmt.Sprintf("U%d", sv)
|
||||||
|
@ -1552,6 +1606,7 @@ func processNMEALine(l string) (sentenceUsed bool) {
|
||||||
var svType uint8
|
var svType uint8
|
||||||
var svSBAS bool // used to indicate whether this GSA message contains a SBAS satellite
|
var svSBAS bool // used to indicate whether this GSA message contains a SBAS satellite
|
||||||
var svGLONASS bool // used to indicate whether this GSA message contains GLONASS satellites
|
var svGLONASS bool // used to indicate whether this GSA message contains GLONASS satellites
|
||||||
|
var svGalileo bool // used to indicate whether this GSA message contains Galileo satellites
|
||||||
sat := 0
|
sat := 0
|
||||||
|
|
||||||
for _, svtxt := range x[3:15] {
|
for _, svtxt := range x[3:15] {
|
||||||
|
@ -1570,7 +1625,11 @@ func processNMEALine(l string) (sentenceUsed bool) {
|
||||||
svType = SAT_TYPE_GLONASS
|
svType = SAT_TYPE_GLONASS
|
||||||
svStr = fmt.Sprintf("R%d", sv-64) // subtract 64 to convert from NMEA to PRN.
|
svStr = fmt.Sprintf("R%d", sv-64) // subtract 64 to convert from NMEA to PRN.
|
||||||
svGLONASS = true
|
svGLONASS = true
|
||||||
} else { //TODO: Galileo
|
} else if sv < 210 { // Galileo
|
||||||
|
svType = SAT_TYPE_GALILEO
|
||||||
|
svStr = fmt.Sprintf("E%d", sv-210) // subtract 300 to convert from NMEA to PRN
|
||||||
|
svGalileo = true
|
||||||
|
} else {
|
||||||
svType = SAT_TYPE_UNKNOWN
|
svType = SAT_TYPE_UNKNOWN
|
||||||
svStr = fmt.Sprintf("U%d", sv)
|
svStr = fmt.Sprintf("U%d", sv)
|
||||||
}
|
}
|
||||||
|
@ -1638,7 +1697,7 @@ func processNMEALine(l string) (sentenceUsed bool) {
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (x[0] == "GPGSV") || (x[0] == "GLGSV") { // GPS + SBAS or GLONASS satellites in view message. Galileo is TBD.
|
if (x[0] == "GPGSV") || (x[0] == "GLGSV") || (x[0] == "GAGSV") { // GPS + SBAS or GLONASS or Galileo satellites in view message.
|
||||||
if len(x) < 4 {
|
if len(x) < 4 {
|
||||||
return false
|
return false
|
||||||
}
|
}
|
||||||
|
@ -1694,7 +1753,10 @@ func processNMEALine(l string) (sentenceUsed bool) {
|
||||||
} else if sv < 97 { // GLONASS
|
} else if sv < 97 { // GLONASS
|
||||||
svType = SAT_TYPE_GLONASS
|
svType = SAT_TYPE_GLONASS
|
||||||
svStr = fmt.Sprintf("R%d", sv-64) // subtract 64 to convert from NMEA to PRN.
|
svStr = fmt.Sprintf("R%d", sv-64) // subtract 64 to convert from NMEA to PRN.
|
||||||
} else { //TODO: Galileo
|
} else if sv < 210 { // Galileo
|
||||||
|
svType = SAT_TYPE_GALILEO
|
||||||
|
svStr = fmt.Sprintf("E%d", sv-210) // subtract 300 to convert from NMEA to PRN
|
||||||
|
} else {
|
||||||
svType = SAT_TYPE_UNKNOWN
|
svType = SAT_TYPE_UNKNOWN
|
||||||
svStr = fmt.Sprintf("U%d", sv)
|
svStr = fmt.Sprintf("U%d", sv)
|
||||||
}
|
}
|
||||||
|
@ -1895,7 +1957,7 @@ func gpsAttitudeSender() {
|
||||||
for !(globalSettings.IMU_Sensor_Enabled && globalStatus.IMUConnected) && (globalSettings.GPS_Enabled && globalStatus.GPS_connected) {
|
for !(globalSettings.IMU_Sensor_Enabled && globalStatus.IMUConnected) && (globalSettings.GPS_Enabled && globalStatus.GPS_connected) {
|
||||||
<-timer.C
|
<-timer.C
|
||||||
|
|
||||||
if mySituation.GPSFixQuality == 0 || !calcGPSAttitude() {
|
if !isGPSValid() || !calcGPSAttitude() {
|
||||||
if globalSettings.DEBUG {
|
if globalSettings.DEBUG {
|
||||||
log.Printf("Couldn't calculate GPS-based attitude statistics\n")
|
log.Printf("Couldn't calculate GPS-based attitude statistics\n")
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,6 +1,6 @@
|
||||||
/*
|
/*
|
||||||
Copyright (c) 2015-2016 Christopher Young
|
Copyright (c) 2015-2016 Christopher Young
|
||||||
Distributable under the terms of The "BSD New"" License
|
Distributable under the terms of The "BSD New" License
|
||||||
that can be found in the LICENSE file, herein included
|
that can be found in the LICENSE file, herein included
|
||||||
as part of this header.
|
as part of this header.
|
||||||
|
|
||||||
|
|
|
@ -1,6 +1,6 @@
|
||||||
/*
|
/*
|
||||||
Copyright (c) 2015-2016 Christopher Young
|
Copyright (c) 2015-2016 Christopher Young
|
||||||
Distributable under the terms of The "BSD New"" License
|
Distributable under the terms of The "BSD New" License
|
||||||
that can be found in the LICENSE file, herein included
|
that can be found in the LICENSE file, herein included
|
||||||
as part of this header.
|
as part of this header.
|
||||||
|
|
||||||
|
|
|
@ -1,6 +1,6 @@
|
||||||
/*
|
/*
|
||||||
Copyright (c) 2015-2016 Christopher Young
|
Copyright (c) 2015-2016 Christopher Young
|
||||||
Distributable under the terms of The "BSD New"" License
|
Distributable under the terms of The "BSD New" License
|
||||||
that can be found in the LICENSE file, herein included
|
that can be found in the LICENSE file, herein included
|
||||||
as part of this header.
|
as part of this header.
|
||||||
|
|
||||||
|
|
|
@ -1,6 +1,6 @@
|
||||||
/*
|
/*
|
||||||
Copyright (c) 2016 uAvionix
|
Copyright (c) 2016 uAvionix
|
||||||
Distributable under the terms of The "BSD New"" License
|
Distributable under the terms of The "BSD New" License
|
||||||
that can be found in the LICENSE file, herein included
|
that can be found in the LICENSE file, herein included
|
||||||
as part of this header.
|
as part of this header.
|
||||||
|
|
||||||
|
|
|
@ -1,6 +1,6 @@
|
||||||
/*
|
/*
|
||||||
Copyright (c) 2015-2016 Christopher Young
|
Copyright (c) 2015-2016 Christopher Young
|
||||||
Distributable under the terms of The "BSD New"" License
|
Distributable under the terms of The "BSD New" License
|
||||||
that can be found in the LICENSE file, herein included
|
that can be found in the LICENSE file, herein included
|
||||||
as part of this header.
|
as part of this header.
|
||||||
|
|
||||||
|
|
|
@ -1,6 +1,6 @@
|
||||||
/*
|
/*
|
||||||
Copyright (c) 2015-2016 Christopher Young
|
Copyright (c) 2015-2016 Christopher Young
|
||||||
Distributable under the terms of The "BSD New"" License
|
Distributable under the terms of The "BSD New" License
|
||||||
that can be found in the LICENSE file, herein included
|
that can be found in the LICENSE file, herein included
|
||||||
as part of this header.
|
as part of this header.
|
||||||
|
|
||||||
|
@ -111,9 +111,9 @@ type TrafficInfo struct {
|
||||||
Last_speed time.Time // Time of last velocity and track update (stratuxClock).
|
Last_speed time.Time // Time of last velocity and track update (stratuxClock).
|
||||||
Last_source uint8 // Last frequency on which this target was received.
|
Last_source uint8 // Last frequency on which this target was received.
|
||||||
ExtrapolatedPosition bool //TODO: True if Stratux is "coasting" the target from last known position.
|
ExtrapolatedPosition bool //TODO: True if Stratux is "coasting" the target from last known position.
|
||||||
Bearing float64 // Bearing in degrees true to traffic from ownship, if it can be calculated.
|
BearingDist_valid bool // set when bearing and distance information is valid
|
||||||
Distance float64 // Distance to traffic from ownship, if it can be calculated.
|
Bearing float64 // Bearing in degrees true to traffic from ownship, if it can be calculated. Units: degrees.
|
||||||
//FIXME: Some indicator that Bearing and Distance are valid, since they aren't always available.
|
Distance float64 // Distance to traffic from ownship, if it can be calculated. Units: meters.
|
||||||
//FIXME: Rename variables for consistency, especially "Last_".
|
//FIXME: Rename variables for consistency, especially "Last_".
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -191,6 +191,11 @@ func sendTrafficUpdates() {
|
||||||
dist, bearing := distance(float64(mySituation.GPSLatitude), float64(mySituation.GPSLongitude), float64(ti.Lat), float64(ti.Lng))
|
dist, bearing := distance(float64(mySituation.GPSLatitude), float64(mySituation.GPSLongitude), float64(ti.Lat), float64(ti.Lng))
|
||||||
ti.Distance = dist
|
ti.Distance = dist
|
||||||
ti.Bearing = bearing
|
ti.Bearing = bearing
|
||||||
|
ti.BearingDist_valid = true
|
||||||
|
} else {
|
||||||
|
ti.Distance = 0
|
||||||
|
ti.Bearing = 0
|
||||||
|
ti.BearingDist_valid = false
|
||||||
}
|
}
|
||||||
ti.Age = stratuxClock.Since(ti.Last_seen).Seconds()
|
ti.Age = stratuxClock.Since(ti.Last_seen).Seconds()
|
||||||
ti.AgeLastAlt = stratuxClock.Since(ti.Last_alt).Seconds()
|
ti.AgeLastAlt = stratuxClock.Since(ti.Last_alt).Seconds()
|
||||||
|
@ -251,12 +256,30 @@ func registerTrafficUpdate(ti TrafficInfo) {
|
||||||
trafficUpdate.SendJSON(ti)
|
trafficUpdate.SendJSON(ti)
|
||||||
}
|
}
|
||||||
|
|
||||||
|
func isTrafficAlertable(ti TrafficInfo) bool {
|
||||||
|
// Set alert bit if possible and traffic is within some threshold
|
||||||
|
// TODO: Could be more intelligent, taking into account headings etc.
|
||||||
|
if ti.BearingDist_valid &&
|
||||||
|
ti.Distance < 3704 { // 3704 meters, 2 nm.
|
||||||
|
return true
|
||||||
|
}
|
||||||
|
|
||||||
|
return false
|
||||||
|
}
|
||||||
|
|
||||||
func makeTrafficReportMsg(ti TrafficInfo) []byte {
|
func makeTrafficReportMsg(ti TrafficInfo) []byte {
|
||||||
msg := make([]byte, 28)
|
msg := make([]byte, 28)
|
||||||
// See p.16.
|
// See p.16.
|
||||||
msg[0] = 0x14 // Message type "Traffic Report".
|
msg[0] = 0x14 // Message type "Traffic Report".
|
||||||
|
|
||||||
msg[1] = 0x10 | ti.Addr_type // Alert status, address type.
|
// Address type
|
||||||
|
msg[1] = ti.Addr_type
|
||||||
|
|
||||||
|
// Set alert if needed
|
||||||
|
if isTrafficAlertable(ti) {
|
||||||
|
// Set the alert bit. See pg. 18 of GDL90 ICD
|
||||||
|
msg[1] |= 0x10
|
||||||
|
}
|
||||||
|
|
||||||
// ICAO Address.
|
// ICAO Address.
|
||||||
msg[2] = byte((ti.Icao_addr & 0x00FF0000) >> 16)
|
msg[2] = byte((ti.Icao_addr & 0x00FF0000) >> 16)
|
||||||
|
@ -849,6 +872,7 @@ func esListen() {
|
||||||
ti.Lng = lng
|
ti.Lng = lng
|
||||||
if isGPSValid() {
|
if isGPSValid() {
|
||||||
ti.Distance, ti.Bearing = distance(float64(mySituation.GPSLatitude), float64(mySituation.GPSLongitude), float64(ti.Lat), float64(ti.Lng))
|
ti.Distance, ti.Bearing = distance(float64(mySituation.GPSLatitude), float64(mySituation.GPSLongitude), float64(ti.Lat), float64(ti.Lng))
|
||||||
|
ti.BearingDist_valid = true
|
||||||
}
|
}
|
||||||
ti.Position_valid = true
|
ti.Position_valid = true
|
||||||
ti.ExtrapolatedPosition = false
|
ti.ExtrapolatedPosition = false
|
||||||
|
@ -1083,6 +1107,7 @@ func updateDemoTraffic(icao uint32, tail string, relAlt float32, gs float64, off
|
||||||
ti.Lng = float32(lng + traffRelLng)
|
ti.Lng = float32(lng + traffRelLng)
|
||||||
|
|
||||||
ti.Distance, ti.Bearing = distance(float64(lat), float64(lng), float64(ti.Lat), float64(ti.Lng))
|
ti.Distance, ti.Bearing = distance(float64(lat), float64(lng), float64(ti.Lat), float64(ti.Lng))
|
||||||
|
ti.BearingDist_valid = true
|
||||||
|
|
||||||
ti.Position_valid = true
|
ti.Position_valid = true
|
||||||
ti.ExtrapolatedPosition = false
|
ti.ExtrapolatedPosition = false
|
||||||
|
|
|
@ -1,6 +1,6 @@
|
||||||
/*
|
/*
|
||||||
Copyright (c) 2015-2016 Christopher Young
|
Copyright (c) 2015-2016 Christopher Young
|
||||||
Distributable under the terms of The "BSD New"" License
|
Distributable under the terms of The "BSD New" License
|
||||||
that can be found in the LICENSE file, herein included
|
that can be found in the LICENSE file, herein included
|
||||||
as part of this header.
|
as part of this header.
|
||||||
|
|
||||||
|
|
Ładowanie…
Reference in New Issue