kopia lustrzana https://github.com/cyoung/stratux
Porównaj commity
35 Commity
Autor | SHA1 | Data |
---|---|---|
Helno | eec0b15d4a | |
Helno | 2d421310bd | |
Eric Westphal | ec997fbf98 | |
Eric Westphal | ac357d8a28 | |
Helno | fb1ef310f5 | |
Eric Westphal | d9a19c0a7f | |
cyoung | 7eeb32acf6 | |
cyoung | e949daed02 | |
Jordan T | b28b002e6b | |
Jordan T | 4241d2a17e | |
Jordan T | 463721c93b | |
Jordan T | fb7a09ba3e | |
Jordan T | eb4fc67e22 | |
cyoung | cf28a07c9f | |
cyoung | 8859b26653 | |
cyoung | e0a22baeac | |
cyoung | 89e158d29b | |
cyoung | 5a47671866 | |
cyoung | 1da3dd81f4 | |
cyoung | c4e00ccf46 | |
cyoung | 9db076f8d3 | |
cyoung | d85695e842 | |
Blaumeiser | ba27147404 | |
cyoung | 8698e90f0a | |
cyoung | 6d470ac0f8 | |
Jonathan | 115c4c3373 | |
matthewh628 | 1738345af5 | |
Linar Yusupov | 2a0f638f63 | |
cyoung | 37911bc692 | |
cyoung | be93f4290c | |
William Castillo | 1c92f75c4d | |
cyoung | eebe80d3c7 | |
William Castillo | cac8dd98d4 | |
cyoung | 93de565e4b | |
PepperJo | 5974fd2266 |
|
@ -7,9 +7,7 @@
|
|||
RTL-SDR UAT tools
|
||||
|
||||
|
||||
Use with Raspberry Pi 3B. Do **not** use with the Raspberry Pi 3 _**B+**_.
|
||||
|
||||
Raspberry Pi 2 with the Edimax EW-7811Un Wi-Fi dongle is supported but not recommended for new builds.
|
||||
Use with Raspberry Pi 3B. The 3B+ and Pi 4B will work but use a lot more power.
|
||||
|
||||
Tested and works well with most common R820T and R820T2 RTL-SDR devices.
|
||||
|
||||
|
@ -25,6 +23,7 @@ Apps with stratux recognition/support:
|
|||
* iFly GPS 9.4+.
|
||||
* DroidEFB 2.1.1+.
|
||||
* kwikEFIS
|
||||
* Pilots Atlas
|
||||
|
||||
Tested weather/traffic displays:
|
||||
* Avare
|
||||
|
|
2
goflying
2
goflying
|
@ -1 +1 @@
|
|||
Subproject commit 0ba3e51be74b4848488e06ec0fee74ebaa7ef705
|
||||
Subproject commit 1da95360a858bfdc5af2b4e7d5caa66542f164e1
|
|
@ -43,3 +43,6 @@ SUBSYSTEMS=="usb", ATTRS{interface}=="Stratux Serialout", SYMLINK+="serialout%n"
|
|||
SUBSYSTEMS=="usb", ATTRS{idVendor}=="10c4", ATTRS{idProduct}=="ea60", ATTRS{product}=="DIY SoftRF", SYMLINK+="softrf"
|
||||
# TTGO T-Beam (ESP32 with OTP CP2104 chip)
|
||||
SUBSYSTEMS=="usb", ATTRS{idVendor}=="10c4", ATTRS{idProduct}=="ea60", ATTRS{product}=="CP2104 USB to UART Bridge Controller", SYMLINK+="softrf"
|
||||
# Dongle Edition (LilyGO & SoftRF T-Motion. USB CDC ACM output)
|
||||
SUBSYSTEMS=="usb", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="5740", SYMLINK+="softrf"
|
||||
# end of SoftRF section
|
||||
|
|
|
@ -0,0 +1,13 @@
|
|||
ddns-update-style none;
|
||||
default-lease-time 86400; # 24 hours
|
||||
max-lease-time 172800; # 48 hours
|
||||
authoritative;
|
||||
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;
|
||||
default-lease-time 12000;
|
||||
max-lease-time 12000;
|
||||
option domain-name "stratux.local";
|
||||
option domain-name-servers 4.2.2.2;
|
||||
}
|
|
@ -295,18 +295,24 @@ func makeOwnshipReport() bool {
|
|||
// See p.16.
|
||||
msg[0] = 0x0A // Message type "Ownship".
|
||||
|
||||
msg[1] = 0x01 // Alert status, address type.
|
||||
|
||||
// Retrieve ICAO code from settings
|
||||
code, _ := hex.DecodeString(globalSettings.OwnshipModeS)
|
||||
if len(code) != 3 {
|
||||
|
||||
// Ownship Target Identify (see 3.5.1.2 of GDL-90 Specifications)
|
||||
// First half of byte is 0 for Alert type of 'No Traffic Alert'
|
||||
// Second half of byte is 0 for traffic type 'ADS-B with ICAO'
|
||||
// Send 0x01 by default, unless ICAO is set, send 0x00
|
||||
if (len(code) == 3 && code[0] != 0xF0 && code[0] != 0x00) {
|
||||
msg[1] = 0x00 // ADS-B Out with ICAO
|
||||
msg[2] = code[0] // Mode S address.
|
||||
msg[3] = code[1] // Mode S address.
|
||||
msg[4] = code[2] // Mode S address.
|
||||
} else {
|
||||
msg[1] = 0x01 // ADS-B Out with self-assigned code
|
||||
// Reserved dummy code.
|
||||
msg[2] = 0xF0
|
||||
msg[3] = 0x00
|
||||
msg[4] = 0x00
|
||||
} else {
|
||||
msg[2] = code[0] // Mode S address.
|
||||
msg[3] = code[1] // Mode S address.
|
||||
msg[4] = code[2] // Mode S address.
|
||||
}
|
||||
|
||||
var tmp []byte
|
||||
|
@ -1097,6 +1103,7 @@ func getProductNameFromId(product_id int) string {
|
|||
}
|
||||
|
||||
type settings struct {
|
||||
DarkMode bool
|
||||
UAT_Enabled bool
|
||||
ES_Enabled bool
|
||||
Ping_Enabled bool
|
||||
|
@ -1122,6 +1129,8 @@ type settings struct {
|
|||
WiFiChannel int
|
||||
WiFiSecurityEnabled bool
|
||||
WiFiPassphrase string
|
||||
WiFiSmartEnabled bool // "Smart WiFi" - disables the default gateway for iOS.
|
||||
NoSleep bool
|
||||
}
|
||||
|
||||
type status struct {
|
||||
|
@ -1178,6 +1187,7 @@ var globalSettings settings
|
|||
var globalStatus status
|
||||
|
||||
func defaultSettings() {
|
||||
globalSettings.DarkMode = false
|
||||
globalSettings.UAT_Enabled = true
|
||||
globalSettings.ES_Enabled = true
|
||||
globalSettings.GPS_Enabled = true
|
||||
|
@ -1196,6 +1206,7 @@ func defaultSettings() {
|
|||
globalSettings.OwnshipModeS = "F00000"
|
||||
globalSettings.DeveloperMode = false
|
||||
globalSettings.StaticIps = make([]string, 0)
|
||||
globalSettings.NoSleep = false
|
||||
}
|
||||
|
||||
func readSettings() {
|
||||
|
@ -1306,6 +1317,14 @@ func saveWiFiUserSettings() {
|
|||
fmt.Fprintf(writer, "wpa_passphrase=%s\n", globalSettings.WiFiPassphrase)
|
||||
}
|
||||
writer.Flush()
|
||||
|
||||
// "Smart WiFi". Just use one of two pre-made dhcpd config files.
|
||||
dhcpd_config := "/etc/dhcp/dhcpd-not_smart.conf"
|
||||
if globalSettings.WiFiSmartEnabled {
|
||||
dhcpd_config = "/etc/dhcp/dhcpd-smart.conf"
|
||||
}
|
||||
os.Remove("/etc/dhcp/dhcpd.conf")
|
||||
os.Symlink(dhcpd_config, "/etc/dhcp/dhcpd.conf")
|
||||
}
|
||||
|
||||
func openReplay(fn string, compressed bool) (WriteCloser, error) {
|
||||
|
|
|
@ -271,6 +271,8 @@ func handleSettingsSetRequest(w http.ResponseWriter, r *http.Request) {
|
|||
for key, val := range msg {
|
||||
// log.Printf("handleSettingsSetRequest:json: testing for key:%s of type %s\n", key, reflect.TypeOf(val))
|
||||
switch key {
|
||||
case "DarkMode":
|
||||
globalSettings.DarkMode = val.(bool)
|
||||
case "UAT_Enabled":
|
||||
globalSettings.UAT_Enabled = val.(bool)
|
||||
case "ES_Enabled":
|
||||
|
@ -378,6 +380,9 @@ func handleSettingsSetRequest(w http.ResponseWriter, r *http.Request) {
|
|||
case "WiFiPassphrase":
|
||||
globalSettings.WiFiPassphrase = val.(string)
|
||||
resetWiFi = true
|
||||
case "WiFiSmartEnabled":
|
||||
globalSettings.WiFiSmartEnabled = val.(bool)
|
||||
resetWiFi = true
|
||||
default:
|
||||
log.Printf("handleSettingsSetRequest:json: unrecognized key:%s\n", key)
|
||||
}
|
||||
|
|
|
@ -145,6 +145,9 @@ func getDHCPLeases() (map[string]string, error) {
|
|||
***WARNING***: netMutex must be locked before calling this function.
|
||||
*/
|
||||
func isSleeping(k string) bool {
|
||||
if globalSettings.NoSleep == true {
|
||||
return false
|
||||
}
|
||||
ipAndPort := strings.Split(k, ":")
|
||||
// No ping response. Assume disconnected/sleeping device.
|
||||
if lastPing, ok := pingResponse[ipAndPort[0]]; !ok || stratuxClock.Since(lastPing) > (10*time.Second) {
|
||||
|
|
|
@ -19,6 +19,12 @@ const (
|
|||
numRetries uint8 = 5
|
||||
calCLimit = 0.15
|
||||
calDLimit = 10.0
|
||||
|
||||
// WHO_AM_I values to differentiate between the different IMUs.
|
||||
MPUREG_WHO_AM_I = 0x75
|
||||
MPUREG_WHO_AM_I_VAL = 0x71 // Expected value.
|
||||
ICMREG_WHO_AM_I = 0x00
|
||||
ICMREG_WHO_AM_I_VAL = 0xEA // Expected value.
|
||||
)
|
||||
|
||||
var (
|
||||
|
@ -123,13 +129,36 @@ func tempAndPressureSender() {
|
|||
}
|
||||
|
||||
func initIMU() (ok bool) {
|
||||
imu, err := sensors.NewMPU9250()
|
||||
if err == nil {
|
||||
myIMUReader = imu
|
||||
return true
|
||||
// Check if the chip is the ICM-20948 or MPU-9250.
|
||||
v, err := i2cbus.ReadByteFromReg(0x68, ICMREG_WHO_AM_I)
|
||||
if err != nil {
|
||||
log.Printf("Error identifying IMU: %s\n", err.Error())
|
||||
return false
|
||||
}
|
||||
v2, err := i2cbus.ReadByteFromReg(0x68, MPUREG_WHO_AM_I)
|
||||
if err != nil {
|
||||
log.Printf("Error identifying IMU: %s\n", err.Error())
|
||||
return false
|
||||
}
|
||||
|
||||
// TODO westphae: try to connect to MPU9150 or other IMUs.
|
||||
if v == ICMREG_WHO_AM_I_VAL {
|
||||
log.Println("ICM-20948 detected.")
|
||||
imu, err := sensors.NewICM20948(&i2cbus)
|
||||
if err == nil {
|
||||
myIMUReader = imu
|
||||
return true
|
||||
}
|
||||
} else if v2 == MPUREG_WHO_AM_I_VAL {
|
||||
log.Println("MPU-9250 detected.")
|
||||
imu, err := sensors.NewMPU9250(&i2cbus)
|
||||
if err == nil {
|
||||
myIMUReader = imu
|
||||
return true
|
||||
}
|
||||
} else {
|
||||
log.Printf("Could not identify MPU. v=%02x, v2=%02x.\n", v, v2)
|
||||
return false
|
||||
}
|
||||
|
||||
return false
|
||||
}
|
||||
|
|
|
@ -36,7 +36,8 @@ cp image/99-uavionix.rules work/bin/
|
|||
cp image/motd work/bin/
|
||||
cp image/stratux-wifi.sh work/bin/
|
||||
cp image/rc.local work/bin/
|
||||
cp image/dhcpd.conf work/bin/
|
||||
cp image/dhcpd-not_smart.conf work/bin/
|
||||
cp image/dhcpd-smart.conf work/bin/
|
||||
cp image/interfaces work/bin/
|
||||
cp image/logrotate.conf work/bin/
|
||||
cp image/logrotate_d_stratux work/bin/
|
||||
|
|
|
@ -87,7 +87,9 @@ cp -f ahrs_approx /usr/bin/
|
|||
chmod 755 /usr/bin/ahrs_approx
|
||||
|
||||
# DHCPD Config.
|
||||
cp -f dhcpd.conf /etc/dhcp/dhcpd.conf
|
||||
cp -f dhcpd-not_smart.conf /etc/dhcp/
|
||||
cp -f dhcpd-smart.conf /etc/dhcp/
|
||||
ln -s /etc/dhcp/dhcpd-not_smart.conf /etc/dhcp/dhcpd.conf
|
||||
|
||||
# Interfaces file.
|
||||
cp -f interfaces /etc/network/interfaces
|
||||
|
|
|
@ -0,0 +1,98 @@
|
|||
// Package sensors provides a stratux interface to sensors used for AHRS calculations.
|
||||
package sensors
|
||||
|
||||
import (
|
||||
"../goflying/icm20948"
|
||||
"github.com/kidoman/embd"
|
||||
)
|
||||
|
||||
const (
|
||||
gyroRange = 250 // gyroRange is the default range to use for the Gyro.
|
||||
accelRange = 4 // accelRange is the default range to use for the Accel.
|
||||
updateFreq = 50 // updateFreq is the rate at which to update the sensor values.
|
||||
)
|
||||
|
||||
// ICM20948 represents an InvenSense ICM-20948 attached to the I2C bus and satisfies
|
||||
// the IMUReader interface.
|
||||
type ICM20948 struct {
|
||||
mpu *icm20948.ICM20948
|
||||
}
|
||||
|
||||
// NewICM20948 returns an instance of the ICM-20948 IMUReader, connected to an
|
||||
// ICM-20948 attached on the I2C bus with either valid address.
|
||||
func NewICM20948(i2cbus *embd.I2CBus) (*ICM20948, error) {
|
||||
var (
|
||||
m ICM20948
|
||||
mpu *icm20948.ICM20948
|
||||
err error
|
||||
)
|
||||
|
||||
mpu, err = icm20948.NewICM20948(i2cbus, gyroRange, accelRange, updateFreq, true, false)
|
||||
if err != nil {
|
||||
return nil, err
|
||||
}
|
||||
|
||||
// Set Gyro (Accel) LPFs to 25 Hz to filter out prop/glareshield vibrations above 1200 (1260) RPM
|
||||
mpu.SetGyroLPF(25)
|
||||
mpu.SetAccelLPF(25)
|
||||
|
||||
m.mpu = mpu
|
||||
return &m, nil
|
||||
}
|
||||
|
||||
// Read returns the average (since last reading) time, Gyro X-Y-Z, Accel X-Y-Z, Mag X-Y-Z,
|
||||
// error reading Gyro/Accel, and error reading Mag.
|
||||
func (m *ICM20948) Read() (T int64, G1, G2, G3, A1, A2, A3, M1, M2, M3 float64, GAError, MAGError error) {
|
||||
var (
|
||||
data *icm20948.MPUData
|
||||
i int8
|
||||
)
|
||||
data = new(icm20948.MPUData)
|
||||
|
||||
for data.N == 0 && i < 5 {
|
||||
data = <-m.mpu.CAvg
|
||||
T = data.T.UnixNano()
|
||||
G1 = data.G1
|
||||
G2 = data.G2
|
||||
G3 = data.G3
|
||||
A1 = data.A1
|
||||
A2 = data.A2
|
||||
A3 = data.A3
|
||||
M1 = data.M1
|
||||
M2 = data.M2
|
||||
M3 = data.M3
|
||||
GAError = data.GAError
|
||||
MAGError = data.MagError
|
||||
i++
|
||||
}
|
||||
return
|
||||
}
|
||||
|
||||
// ReadOne returns the most recent time, Gyro X-Y-Z, Accel X-Y-Z, Mag X-Y-Z,
|
||||
// error reading Gyro/Accel, and error reading Mag.
|
||||
func (m *ICM20948) ReadOne() (T int64, G1, G2, G3, A1, A2, A3, M1, M2, M3 float64, GAError, MAGError error) {
|
||||
var (
|
||||
data *icm20948.MPUData
|
||||
)
|
||||
data = new(icm20948.MPUData)
|
||||
|
||||
data = <-m.mpu.C
|
||||
T = data.T.UnixNano()
|
||||
G1 = data.G1
|
||||
G2 = data.G2
|
||||
G3 = data.G3
|
||||
A1 = data.A1
|
||||
A2 = data.A2
|
||||
A3 = data.A3
|
||||
M1 = data.M1
|
||||
M2 = data.M2
|
||||
M3 = data.M3
|
||||
GAError = data.GAError
|
||||
MAGError = data.MagError
|
||||
return
|
||||
}
|
||||
|
||||
// Close stops reading the MPU.
|
||||
func (m *ICM20948) Close() {
|
||||
m.mpu.CloseMPU()
|
||||
}
|
|
@ -3,12 +3,13 @@ package sensors
|
|||
|
||||
import (
|
||||
"../goflying/mpu9250"
|
||||
"github.com/kidoman/embd"
|
||||
)
|
||||
|
||||
const (
|
||||
gyroRange = 250 // gyroRange is the default range to use for the Gyro.
|
||||
accelRange = 4 // accelRange is the default range to use for the Accel.
|
||||
updateFreq = 50 // updateFreq is the rate at which to update the sensor values.
|
||||
mpu9250GyroRange = 250 // mpu9250GyroRange is the default range to use for the Gyro.
|
||||
mpu9250AccelRange = 4 // mpu9250AccelRange is the default range to use for the Accel.
|
||||
mpu9250UpdateFreq = 50 // mpu9250UpdateFreq is the rate at which to update the sensor values.
|
||||
)
|
||||
|
||||
// MPU9250 represents an InvenSense MPU9250 attached to the I2C bus and satisfies
|
||||
|
@ -19,14 +20,14 @@ type MPU9250 struct {
|
|||
|
||||
// NewMPU9250 returns an instance of the MPU9250 IMUReader, connected to an
|
||||
// MPU9250 attached on the I2C bus with either valid address.
|
||||
func NewMPU9250() (*MPU9250, error) {
|
||||
func NewMPU9250(i2cbus *embd.I2CBus) (*MPU9250, error) {
|
||||
var (
|
||||
m MPU9250
|
||||
mpu *mpu9250.MPU9250
|
||||
err error
|
||||
)
|
||||
|
||||
mpu, err = mpu9250.NewMPU9250(gyroRange, accelRange, updateFreq, true, false)
|
||||
mpu, err = mpu9250.NewMPU9250(i2cbus, mpu9250GyroRange, mpu9250AccelRange, mpu9250UpdateFreq, true, false)
|
||||
if err != nil {
|
||||
return nil, err
|
||||
}
|
||||
|
|
|
@ -1,87 +0,0 @@
|
|||
package main
|
||||
|
||||
import (
|
||||
"bufio"
|
||||
"fmt"
|
||||
"github.com/gonum/plot"
|
||||
"github.com/gonum/plot/plotter"
|
||||
"github.com/gonum/plot/plotutil"
|
||||
"github.com/gonum/plot/vg"
|
||||
"net/http"
|
||||
"os"
|
||||
"strconv"
|
||||
"strings"
|
||||
"time"
|
||||
)
|
||||
|
||||
type XY struct {
|
||||
X float64
|
||||
Y float64
|
||||
}
|
||||
|
||||
func imageWriter() {
|
||||
for {
|
||||
p, err := plot.New()
|
||||
if err != nil {
|
||||
panic(err)
|
||||
}
|
||||
p.Title.Text = "AHRS Plot"
|
||||
p.X.Label.Text = "Roll"
|
||||
p.Y.Label.Text = "Pitch"
|
||||
|
||||
file, err := os.Open("ahrs_table.log")
|
||||
if err != nil {
|
||||
panic(err)
|
||||
}
|
||||
defer file.Close()
|
||||
|
||||
scanner := bufio.NewScanner(file)
|
||||
|
||||
vals := make([]XY, 0)
|
||||
for scanner.Scan() {
|
||||
l := scanner.Text()
|
||||
x := strings.Split(l, ",")
|
||||
if len(x) < 3 {
|
||||
continue
|
||||
}
|
||||
roll, err := strconv.ParseFloat(x[0], 64)
|
||||
if err != nil {
|
||||
continue
|
||||
}
|
||||
pitch, err := strconv.ParseFloat(x[1], 64)
|
||||
if err != nil {
|
||||
continue
|
||||
}
|
||||
v := XY{X: roll, Y: pitch}
|
||||
vals = append(vals, v)
|
||||
}
|
||||
vals_XY := make(plotter.XYs, len(vals))
|
||||
for i := 0; i < len(vals); i++ {
|
||||
vals_XY[i].X = vals[i].X
|
||||
vals_XY[i].Y = vals[i].Y
|
||||
}
|
||||
err = plotutil.AddScatters(p, "First", vals_XY)
|
||||
if err != nil {
|
||||
panic(err)
|
||||
}
|
||||
if err := p.Save(8*vg.Inch, 8*vg.Inch, "out.png"); err != nil {
|
||||
panic(err)
|
||||
}
|
||||
time.Sleep(1000 * time.Millisecond)
|
||||
}
|
||||
}
|
||||
|
||||
func main() {
|
||||
go imageWriter()
|
||||
http.Handle("/", http.FileServer(http.Dir(".")))
|
||||
err := http.ListenAndServe(":8080", nil)
|
||||
|
||||
if err != nil {
|
||||
fmt.Printf("managementInterface ListenAndServe: %s\n", err.Error())
|
||||
}
|
||||
|
||||
for {
|
||||
time.Sleep(1 * time.Second)
|
||||
}
|
||||
|
||||
}
|
|
@ -1,109 +0,0 @@
|
|||
package main
|
||||
|
||||
import (
|
||||
"encoding/hex"
|
||||
"encoding/json"
|
||||
"fmt"
|
||||
"io/ioutil"
|
||||
"net"
|
||||
"net/http"
|
||||
"os"
|
||||
"sync"
|
||||
"time"
|
||||
)
|
||||
|
||||
const (
|
||||
SITUATION_URL = "http://127.0.0.1/getSituation"
|
||||
)
|
||||
|
||||
type MySituation struct {
|
||||
AHRSRoll float64
|
||||
AHRSPitch float64
|
||||
}
|
||||
|
||||
var Location MySituation
|
||||
|
||||
var situationMutex *sync.Mutex
|
||||
|
||||
func chkErr(err error) {
|
||||
if err != nil {
|
||||
fmt.Printf("error: %s\n", err.Error())
|
||||
os.Exit(1)
|
||||
}
|
||||
}
|
||||
|
||||
var currentAHRSString string
|
||||
|
||||
func listener() {
|
||||
t := time.Now()
|
||||
addr := net.UDPAddr{Port: 41504, IP: net.ParseIP("0.0.0.0")}
|
||||
conn, err := net.ListenUDP("udp", &addr)
|
||||
if err != nil {
|
||||
fmt.Printf("error listening: %s\n", err.Error())
|
||||
return
|
||||
}
|
||||
defer conn.Close()
|
||||
for {
|
||||
buf := make([]byte, 1024)
|
||||
n, _, err := conn.ReadFrom(buf)
|
||||
if err != nil {
|
||||
fmt.Printf("Err receive: %s\n", err.Error())
|
||||
continue
|
||||
}
|
||||
buf_encoded := make([]byte, hex.EncodedLen(n))
|
||||
hex.Encode(buf_encoded, buf[:n])
|
||||
t2 := time.Now()
|
||||
time_diff := t2.Sub(t)
|
||||
t = t2
|
||||
|
||||
fmt.Sprintf("%d,%s\n", time_diff/time.Millisecond, buf_encoded)
|
||||
currentAHRSString = string(buf_encoded)
|
||||
}
|
||||
}
|
||||
|
||||
func situationUpdater() {
|
||||
situationUpdateTicker := time.NewTicker(100 * time.Millisecond)
|
||||
for {
|
||||
<-situationUpdateTicker.C
|
||||
situationMutex.Lock()
|
||||
|
||||
resp, err := http.Get(SITUATION_URL)
|
||||
if err != nil {
|
||||
fmt.Printf("HTTP GET error: %s\n", err.Error())
|
||||
situationMutex.Unlock()
|
||||
continue
|
||||
}
|
||||
|
||||
body, err := ioutil.ReadAll(resp.Body)
|
||||
if err != nil {
|
||||
fmt.Printf("HTTP GET body error: %s\n", err.Error())
|
||||
resp.Body.Close()
|
||||
situationMutex.Unlock()
|
||||
continue
|
||||
}
|
||||
|
||||
// fmt.Printf("body: %s\n", string(body))
|
||||
err = json.Unmarshal(body, &Location)
|
||||
|
||||
if err != nil {
|
||||
fmt.Printf("HTTP JSON unmarshal error: %s\n", err.Error())
|
||||
}
|
||||
resp.Body.Close()
|
||||
situationMutex.Unlock()
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
func main() {
|
||||
situationMutex = &sync.Mutex{}
|
||||
|
||||
go listener()
|
||||
go situationUpdater()
|
||||
|
||||
tm := time.NewTicker(125 * time.Millisecond)
|
||||
for {
|
||||
<-tm.C
|
||||
fmt.Printf("%f,%f,%s\n", Location.AHRSRoll, Location.AHRSPitch, currentAHRSString)
|
||||
}
|
||||
|
||||
}
|
|
@ -1,34 +0,0 @@
|
|||
package main
|
||||
|
||||
import (
|
||||
"encoding/hex"
|
||||
"fmt"
|
||||
"net"
|
||||
"time"
|
||||
)
|
||||
|
||||
func main() {
|
||||
t := time.Now()
|
||||
addr := net.UDPAddr{Port: 41504, IP: net.ParseIP("0.0.0.0")}
|
||||
conn, err := net.ListenUDP("udp", &addr)
|
||||
if err != nil {
|
||||
fmt.Printf("ffMonitor(): error listening: %s\n", err.Error())
|
||||
return
|
||||
}
|
||||
defer conn.Close()
|
||||
for {
|
||||
buf := make([]byte, 1024)
|
||||
n, _, err := conn.ReadFrom(buf)
|
||||
if err != nil {
|
||||
fmt.Printf("Err receive: %s\n", err.Error())
|
||||
continue
|
||||
}
|
||||
buf_encoded := make([]byte, hex.EncodedLen(n))
|
||||
hex.Encode(buf_encoded, buf[:n])
|
||||
t2 := time.Now()
|
||||
time_diff := t2.Sub(t)
|
||||
t = t2
|
||||
|
||||
fmt.Printf("%d,%s\n", time_diff/time.Millisecond, buf_encoded)
|
||||
}
|
||||
}
|
|
@ -1,67 +0,0 @@
|
|||
package main
|
||||
|
||||
import (
|
||||
"bufio"
|
||||
"encoding/hex"
|
||||
"fmt"
|
||||
"net"
|
||||
"os"
|
||||
"strconv"
|
||||
"strings"
|
||||
"time"
|
||||
)
|
||||
|
||||
func main() {
|
||||
if len(os.Args) < 2 {
|
||||
fmt.Printf("%s: <file>\n", os.Args[0])
|
||||
return
|
||||
}
|
||||
|
||||
f, err := os.Open(os.Args[1])
|
||||
if err != nil {
|
||||
fmt.Printf("error: %s\n", err.Error())
|
||||
return
|
||||
}
|
||||
defer f.Close()
|
||||
|
||||
scanner := bufio.NewScanner(f)
|
||||
|
||||
// Open a socket.
|
||||
BROADCAST_IPv4 := net.IPv4(255, 255, 255, 255)
|
||||
|
||||
// addr, _ := net.ResolveUDPAddr("udp", "192.168.10.10:41501")
|
||||
// laddr, _ := net.ResolveUDPAddr("udp", "192.168.10.1:58814")
|
||||
// conn, err := net.DialUDP("udp", laddr, addr)
|
||||
conn, err := net.DialUDP("udp", nil, &net.UDPAddr{
|
||||
IP: BROADCAST_IPv4,
|
||||
Port: 41504,
|
||||
})
|
||||
|
||||
if err != nil {
|
||||
fmt.Printf("DialUDP(): %s\n", err.Error())
|
||||
return
|
||||
}
|
||||
|
||||
for scanner.Scan() {
|
||||
s := scanner.Text()
|
||||
x := strings.Split(s, ",")
|
||||
if len(x) < 2 {
|
||||
continue
|
||||
}
|
||||
i, err := strconv.ParseInt(x[0], 10, 32)
|
||||
if err != nil {
|
||||
fmt.Printf("error parsing '%s': %s.\n", x[0], err.Error())
|
||||
continue
|
||||
}
|
||||
buf := make([]byte, hex.DecodedLen(len(x[1])))
|
||||
n, err := hex.Decode(buf, []byte(x[1]))
|
||||
if err != nil {
|
||||
fmt.Printf("error parsing '%s': %s.\n", x[1], err.Error())
|
||||
continue
|
||||
}
|
||||
|
||||
fmt.Printf("sleeping %dms, sending %s\n", i, x[1])
|
||||
time.Sleep(time.Duration(i) * time.Millisecond)
|
||||
conn.Write(buf[:n])
|
||||
}
|
||||
}
|
|
@ -0,0 +1,184 @@
|
|||
pre {
|
||||
color: #9b9b9b;
|
||||
}
|
||||
|
||||
.app-body,
|
||||
.panel-default,
|
||||
.scrollable-content,
|
||||
.form-group {
|
||||
color: #9b9b9b;
|
||||
background-color: #121212;
|
||||
}
|
||||
|
||||
.help-page {
|
||||
background-color: #121212;
|
||||
}
|
||||
|
||||
a,
|
||||
.btn,
|
||||
.navbar-app .btn {
|
||||
color: #1e88e5;
|
||||
}
|
||||
|
||||
a:hover,
|
||||
a:focus,
|
||||
.btn:hover,
|
||||
.btn:focus,
|
||||
.navbar-app .btn:hover,
|
||||
.navbar-app .btn:focus {
|
||||
color: #42a5f5;
|
||||
}
|
||||
|
||||
.btn-primary {
|
||||
color: #121212;
|
||||
background-color: #1e88e5;
|
||||
border-color: #1e88e5;
|
||||
}
|
||||
|
||||
.btn-primary:hover {
|
||||
color: #121212;
|
||||
background-color: #42a5f5;
|
||||
border-color: #42a5f5;
|
||||
}
|
||||
|
||||
.btn-default {
|
||||
color: #e0e0e0;
|
||||
background-color: #343434;
|
||||
}
|
||||
|
||||
.btn-default:hover {
|
||||
background-color: #383838;
|
||||
}
|
||||
|
||||
a.list-group-item,
|
||||
.list-group-item {
|
||||
color: #e0e0e0;
|
||||
border-color: #373737;
|
||||
background-color: #242424;
|
||||
}
|
||||
|
||||
a.list-group-item:hover,
|
||||
.list-group-item:hover {
|
||||
text-decoration: none;
|
||||
color: #e0e0e0;
|
||||
background-color: #373737;
|
||||
}
|
||||
|
||||
.list-group-item.active,
|
||||
.list-group-item.active:focus,
|
||||
.list-group-item.active:hover {
|
||||
color: #121212;
|
||||
background-color: #1e88e5;
|
||||
border-color: #1e88e5;
|
||||
}
|
||||
|
||||
.navbar-app {
|
||||
background-color: #2d2d2d;
|
||||
border-color: #373737;
|
||||
}
|
||||
|
||||
.panel {
|
||||
border-color: #373737;
|
||||
}
|
||||
|
||||
.panel-default>.panel-heading {
|
||||
color: #e0e0e0;
|
||||
background-color: #2d2d2d;
|
||||
border-color: #373737;
|
||||
}
|
||||
|
||||
.panel-default>.panel-footer {
|
||||
color: #e0e0e0;
|
||||
background-color: #2d2d2d;
|
||||
border-color: #373737;
|
||||
}
|
||||
|
||||
.row-header {
|
||||
background-color: #212121;
|
||||
}
|
||||
|
||||
.separator {
|
||||
border-bottom-color: #2d2d2d;
|
||||
}
|
||||
|
||||
.sidebar-header,
|
||||
.app-name {
|
||||
color: #e0e0e0;
|
||||
background-color: #2d2d2d;
|
||||
border-color: #373737;
|
||||
}
|
||||
|
||||
.switch {
|
||||
background-color: #2d2d2d;
|
||||
border-color: #9b9b9b;
|
||||
}
|
||||
|
||||
.switch .switch-handle {
|
||||
background-color: #9b9b9b;
|
||||
border-color: #9b9b9b;
|
||||
}
|
||||
|
||||
.switch.active {
|
||||
background-color: #1e88e5;
|
||||
border-color: #1e88e5;
|
||||
}
|
||||
|
||||
.text-primary {
|
||||
color: #1e88e5;
|
||||
}
|
||||
|
||||
.label-success {
|
||||
color: #121212;
|
||||
background-color: #4caf50;
|
||||
}
|
||||
|
||||
.label-warning {
|
||||
color: #121212;
|
||||
background-color: #ffeb3b;
|
||||
}
|
||||
|
||||
.label-danger {
|
||||
color: #121212;
|
||||
background-color: #f44336;
|
||||
}
|
||||
|
||||
/* Input changes */
|
||||
input[type=text],
|
||||
input[type=number] {
|
||||
color: #e0e0e0;
|
||||
background-color: #212121;
|
||||
border: 2px solid #2d2d2d;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
input.ng-invalid:not(.grayout) {
|
||||
color: #121212;
|
||||
}
|
||||
|
||||
select {
|
||||
color: #e0e0e0;
|
||||
background-color: #212121;
|
||||
border: 2px solid #2d2d2d;
|
||||
border-radius: 4px;
|
||||
}
|
||||
|
||||
/* Modal changes */
|
||||
.modal-content {
|
||||
background-color: #343434;
|
||||
}
|
||||
|
||||
.modal-header {
|
||||
border-color: #9b9b9b;
|
||||
}
|
||||
|
||||
.modal-title {
|
||||
color: #e0e0e0;
|
||||
}
|
||||
|
||||
.modal-body {
|
||||
color: #9b9b9b;
|
||||
}
|
||||
|
||||
.modal-footer {
|
||||
border-color: #9b9b9b;
|
||||
}
|
|
@ -262,6 +262,9 @@
|
|||
width: 100%;
|
||||
}
|
||||
|
||||
.row-header {
|
||||
background-color: #f7f7f7;
|
||||
}
|
||||
|
||||
/* ***************************************************************************
|
||||
everything below this comment represents tweaks to the mobile-angular-uis CSS
|
||||
|
|
|
@ -50,6 +50,7 @@
|
|||
|
||||
<link rel="stylesheet" href="css/main.css" />
|
||||
<link rel="stylesheet" href="css/ahrs.css" />
|
||||
<link rel="stylesheet" id="themeStylesheet" href="" />
|
||||
|
||||
<script src="maui/js/angular.min.js"></script>
|
||||
<script src="maui/js/angular-ui-router.min.js"></script>
|
||||
|
|
|
@ -99,7 +99,23 @@ app.controller('MainCtrl', function ($scope, $http) {
|
|||
.then(function(response) {
|
||||
var settings = angular.fromJson(response.data);
|
||||
$scope.DeveloperMode = settings.DeveloperMode;
|
||||
|
||||
// Update theme
|
||||
$scope.updateTheme(settings.DarkMode);
|
||||
}, function(response) {
|
||||
//Second function handles error
|
||||
});
|
||||
|
||||
$scope.updateTheme = function(darkMode) {
|
||||
if(darkMode != $scope.DarkMode) {
|
||||
// console.log("Updating theme, use dark mode?", darkMode);
|
||||
$scope.DarkMode = darkMode;
|
||||
|
||||
if($scope.DarkMode) {
|
||||
document.getElementById('themeStylesheet').href = 'css/dark-mode.css';
|
||||
} else {
|
||||
document.getElementById('themeStylesheet').href = '';
|
||||
}
|
||||
}
|
||||
};
|
||||
});
|
||||
|
|
|
@ -83,7 +83,11 @@
|
|||
</div>
|
||||
<div class="row">
|
||||
<span class="col-xs-6 text-center">{{gps_lat}}, {{gps_lon}} ± {{gps_horizontal_accuracy}} m <br>
|
||||
{{gps_alt}} ± {{gps_vertical_accuracy}} ft @ {{gps_vert_speed}} ft/min</span>
|
||||
<b>Altitude MSL:</b> <br>
|
||||
{{gps_alt}} ± {{gps_vertical_accuracy}} ft @ {{gps_vert_speed}} ft/min <br>
|
||||
<b>Height WGS-84 ellipsoid:</b> <br>
|
||||
{{ gps_height_above_ellipsoid }} ft
|
||||
</span>
|
||||
<span class="col-xs-6 text-center">{{gps_track}}° @ {{gps_speed}} KTS</span>
|
||||
</div>
|
||||
</div>
|
||||
|
|
|
@ -165,6 +165,7 @@ function GPSCtrl($rootScope, $scope, $state, $http, $interval) {
|
|||
$scope.gps_lat = situation.GPSLatitude.toFixed(5); // result is string
|
||||
$scope.gps_lon = situation.GPSLongitude.toFixed(5); // result is string
|
||||
$scope.gps_alt = situation.GPSAltitudeMSL.toFixed(1);
|
||||
$scope.gps_height_above_ellipsoid = situation.GPSHeightAboveEllipsoid.toFixed(1);
|
||||
$scope.gps_track = situation.GPSTrueCourse.toFixed(1);
|
||||
$scope.gps_speed = situation.GPSGroundSpeed.toFixed(1);
|
||||
$scope.gps_vert_speed = situation.GPSVerticalSpeed.toFixed(1);
|
||||
|
@ -172,6 +173,7 @@ function GPSCtrl($rootScope, $scope, $state, $http, $interval) {
|
|||
$scope.gps_lat = "--";
|
||||
$scope.gps_lon = "--";
|
||||
$scope.gps_alt = "--";
|
||||
$scope.gps_height_above_ellipsoid = "--";
|
||||
$scope.gps_track = "--";
|
||||
$scope.gps_speed = "--";
|
||||
$scope.gps_vert_speed = "--";
|
||||
|
|
|
@ -8,7 +8,7 @@ function SettingsCtrl($rootScope, $scope, $state, $location, $window, $http) {
|
|||
$scope.$parent.helppage = 'plates/settings-help.html';
|
||||
|
||||
var toggles = ['UAT_Enabled', 'ES_Enabled', 'Ping_Enabled', 'GPS_Enabled', 'IMU_Sensor_Enabled',
|
||||
'BMP_Sensor_Enabled', 'DisplayTrafficSource', 'DEBUG', 'ReplayLog', 'AHRSLog'];
|
||||
'BMP_Sensor_Enabled', 'DisplayTrafficSource', 'DEBUG', 'ReplayLog', 'AHRSLog', 'DarkMode'];
|
||||
var settings = {};
|
||||
for (var i = 0; i < toggles.length; i++) {
|
||||
settings[toggles[i]] = undefined;
|
||||
|
@ -24,6 +24,9 @@ function SettingsCtrl($rootScope, $scope, $state, $location, $window, $http) {
|
|||
$scope.Baud = settings.SerialOutputs['/dev/serialout0'].Baud;
|
||||
$scope.visible_serialout = true;
|
||||
}
|
||||
|
||||
$scope.DarkMode = settings.DarkMode;
|
||||
|
||||
$scope.UAT_Enabled = settings.UAT_Enabled;
|
||||
$scope.ES_Enabled = settings.ES_Enabled;
|
||||
$scope.Ping_Enabled = settings.Ping_Enabled;
|
||||
|
@ -47,8 +50,12 @@ function SettingsCtrl($rootScope, $scope, $state, $location, $window, $http) {
|
|||
$scope.WiFiPassphrase = settings.WiFiPassphrase;
|
||||
$scope.WiFiSecurityEnabled = settings.WiFiSecurityEnabled;
|
||||
$scope.WiFiChannel = settings.WiFiChannel;
|
||||
$scope.WiFiSmartEnabled = settings.WiFiSmartEnabled;
|
||||
|
||||
$scope.Channels = [1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11];
|
||||
|
||||
// Update theme
|
||||
$scope.$parent.updateTheme($scope.DarkMode);
|
||||
}
|
||||
|
||||
function getSettings() {
|
||||
|
@ -287,7 +294,8 @@ function SettingsCtrl($rootScope, $scope, $state, $location, $window, $http) {
|
|||
"WiFiSSID" : $scope.WiFiSSID,
|
||||
"WiFiSecurityEnabled" : $scope.WiFiSecurityEnabled,
|
||||
"WiFiPassphrase" : $scope.WiFiPassphrase,
|
||||
"WiFiChannel" : parseInt($scope.WiFiChannel)
|
||||
"WiFiChannel" : parseInt($scope.WiFiChannel),
|
||||
"WiFiSmartEnabled": $scope.WiFiSmartEnabled
|
||||
};
|
||||
|
||||
// console.log(angular.toJson(newsettings));
|
||||
|
|
|
@ -56,6 +56,21 @@
|
|||
</div>
|
||||
</div>
|
||||
</div>
|
||||
<!-- App Theme -->
|
||||
<div class="panel-group col-sm-12">
|
||||
<div class="panel panel-default">
|
||||
<div class="panel-heading">Theme</div>
|
||||
<div class="panel-body">
|
||||
<!-- Dark Mode -->
|
||||
<div class="form-group">
|
||||
<label class="control-label col-xs-7">Dark Mode</label>
|
||||
<div class="col-xs-5">
|
||||
<ui-switch ng-model='DarkMode' settings-change></ui-switch>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
<!-- End Left Col -->
|
||||
<!-- Begin Right Col -->
|
||||
|
@ -134,6 +149,12 @@
|
|||
<select id="WiFiChannel" class="input-small col-sm-2 form-control-sm"
|
||||
ng-model="WiFiChannel" ng-options="x for x in Channels"></select>
|
||||
</div>
|
||||
<div class="form-group reset-flow">
|
||||
<label class="control-label col-xs-7">Smart WiFi</label>
|
||||
<div class="col-xs-5">
|
||||
<ui-switch ng-model="WiFiSmartEnabled" settings-change></ui-switch>
|
||||
</div>
|
||||
</div>
|
||||
<div class="form-group reset-flow">
|
||||
<button class="btn btn-primary btn-block" ng-click="updateWiFi()">Submit WiFi Changes</button>
|
||||
</div>
|
||||
|
@ -383,6 +404,7 @@
|
|||
<p>WiFi Security: <b>{{WiFiSecurityEnabled}}</b></p>
|
||||
<p>WiFi Passphrase: <b>{{WiFiPassphrase}}</b></p>
|
||||
<p>WiFi Channel: <b>{{WiFiChannel}}</b></p>
|
||||
<p>Smart mode: <b>{{WiFiSmartEnabled}}</b></p>
|
||||
<p>Your Stratux's WiFi services are now restarting to apply the new settings. This could take up to 30 seconds.<br/>
|
||||
You might have to reconnect to your new WiFi SSID. </p>
|
||||
</div>
|
||||
|
|
|
@ -1,6 +1,6 @@
|
|||
<div class="col-sm-12">
|
||||
<div class="text-center">
|
||||
<a ng-click="VersionClick()" class="btn btn-hidden"<strong>Version: <span>{{Version}} ({{Build}})</span></strong></a>
|
||||
<a ng-click="VersionClick()" class="btn btn-hidden"><strong>Version: <span>{{Version}} ({{Build}})</span></strong></a>
|
||||
</div>
|
||||
<div class="panel panel-default">
|
||||
<div class="panel-heading">
|
||||
|
@ -56,10 +56,10 @@
|
|||
</div>
|
||||
<div class="row" ng-class="{'section_invisible': !visible_uat}">
|
||||
<div class="col-sm-12">
|
||||
<span align="center" style="background-color: #f7f7f7" class="col-xs-3">Towers</span>
|
||||
<span align="center" style="background-color: #f7f7f7" class="col-xs-3">METARS</span>
|
||||
<span align="center" style="background-color: #f7f7f7" class="col-xs-3">TAFS</span>
|
||||
<span align="center" style="background-color: #f7f7f7" class="col-xs-3">NEXRAD</span>
|
||||
<span align="center" class="col-xs-3 row-header">Towers</span>
|
||||
<span align="center" class="col-xs-3 row-header">METARS</span>
|
||||
<span align="center" class="col-xs-3 row-header">TAFS</span>
|
||||
<span align="center" class="col-xs-3 row-header">NEXRAD</span>
|
||||
</div>
|
||||
</div>
|
||||
<div class="row" ng-class="{'section_invisible': !visible_uat}">
|
||||
|
@ -72,10 +72,10 @@
|
|||
</div>
|
||||
<div class="row" ng-class="{'section_invisible': !visible_uat}">
|
||||
<div class="col-sm-12">
|
||||
<span align="center" style="background-color: #f7f7f7" class="col-xs-3">PIREP</span>
|
||||
<span align="center" style="background-color: #f7f7f7" class="col-xs-3">SIGMET</span>
|
||||
<span align="center" style="background-color: #f7f7f7" class="col-xs-3">NOTAMS</span>
|
||||
<span align="center" style="background-color: #f7f7f7" class="col-xs-3">Other</span>
|
||||
<span align="center" class="col-xs-3 row-header">PIREP</span>
|
||||
<span align="center" class="col-xs-3 row-header">SIGMET</span>
|
||||
<span align="center" class="col-xs-3 row-header">NOTAMS</span>
|
||||
<span align="center" class="col-xs-3 row-header">Other</span>
|
||||
</div>
|
||||
</div>
|
||||
<div class="row" ng-class="{'section_invisible': !visible_uat}">
|
||||
|
|
Ładowanie…
Reference in New Issue