First working commit merging latest cyoung/master into westphae/dev

pull/578/head
Eric Westphal 2016-12-29 06:33:11 -06:00
commit a3a811aa53
61 zmienionych plików z 2514 dodań i 1031 usunięć

3
.gitmodules vendored
Wyświetl plik

@ -1,6 +1,3 @@
[submodule "linux-mpu9150"]
path = linux-mpu9150
url = git://github.com/cyoung/linux-mpu9150
[submodule "dump1090"]
path = dump1090
url = https://github.com/AvSquirrel/dump1090

Wyświetl plik

@ -9,12 +9,11 @@ endif
all:
make xdump978
make xdump1090
make xlinux-mpu9150
make xgen_gdl90
xgen_gdl90:
go get -t -d -v ./main ./test ./linux-mpu9150/mpu ./godump978 ./mpu ./uatparse
go build $(BUILDINFO) -p 4 main/gen_gdl90.go main/traffic.go main/ry83Xai.go main/network.go main/managementinterface.go main/sdr.go main/ping.go main/uibroadcast.go main/monotonic.go main/datalog.go main/equations.go
go get -t -d -v ./main ./test ./godump978 ./uatparse ./sensors
go build $(BUILDINFO) -p 4 main/gen_gdl90.go main/traffic.go main/gps.go main/network.go main/managementinterface.go main/sdr.go main/ping.go main/uibroadcast.go main/monotonic.go main/datalog.go main/equations.go main/sensors.go
xdump1090:
git submodule update --init
@ -24,10 +23,6 @@ xdump978:
cd dump978 && make lib
sudo cp -f ./libdump978.so /usr/lib/libdump978.so
xlinux-mpu9150:
git submodule update --init
cd linux-mpu9150 && make -f Makefile-native-shared
.PHONY: test
test:
make -C test
@ -53,4 +48,3 @@ clean:
rm -f gen_gdl90 libdump978.so
cd dump1090 && make clean
cd dump978 && make clean
rm -f linux-mpu9150/*.o linux-mpu9150/*.so

Wyświetl plik

@ -13,6 +13,9 @@ Raspberry Pi 2 with the Edimax EW-7811Un Wi-Fi dongle is supported but not recom
Tested and works well with most common R820T and R820T2 RTL-SDR devices.
Tested with and preliminary support added for [uAvionix pingEFB dual-link ADS-B receiver](http://www.uavionix.com/products/pingefb/).
Apps with stratux recognition/support:
* Seattle Avionics FlyQ EFB 2.1.1+.
* AvNav EFB 2.0.0+.
@ -33,3 +36,10 @@ Questions? [See the FAQ](https://github.com/cyoung/stratux/wiki/FAQ)
http://stratux.me/
https://www.reddit.com/r/stratux
Jet tests (high gain antennas):
* Dassault Falcon 20
* Embraer ERJ 145
* Cessna Citation 501
* Lear 35

Wyświetl plik

@ -15,3 +15,39 @@ if [ -e /root/update*stratux*v*.sh ] ; then
fi
fi
##### Script for setting up new file structure for hostapd settings
##### Look for hostapd.user and if found do nothing.
##### If not assume because of previous version and convert to new file structure
DAEMON_USER_PREF=/etc/hostapd/hostapd.user
if [ ! -f $DAEMON_USER_PREF ]; then
DAEMON_CONF=/etc/hostapd/hostapd.conf
DAEMON_CONF_EDIMAX=/etc/hostapd/hostapd-edimax.conf
HOSTAPD_VALUES=('ssid=' 'channel=' 'auth_algs=' 'wpa=' 'wpa_passphrase=' 'wpa_key_mgmt=' 'wpa_pairwise=' 'rsn_pairwise=')
HOSTAPD_VALUES_RM=('#auth_algs=' '#wpa=' '#wpa_passphrase=' '#wpa_key_mgmt=' '#wpa_pairwise=' '#rsn_pairwise=')
for i in "${HOSTAPD_VALUES[@]}"
do
if grep -q "^$i" $DAEMON_CONF
then
grep "^$i" $DAEMON_CONF >> $DAEMON_USER_PREF
sed -i '/^'"$i"'/d' $DAEMON_CONF
sed -i '/^'"$i"'/d' $DAEMON_CONF_EDIMAX
fi
done
for i in "${HOSTAPD_VALUES_RM[@]}"
do
if grep -q "^$i" $DAEMON_CONF
then
sed -i '/^'"$i"'/d' $DAEMON_CONF
sed -i '/^'"$i"'/d' $DAEMON_CONF_EDIMAX
fi
done
sleep 1 #make sure there is time to get the file written before checking for it again
# If once the code above runs and there is still no hostapd.user file then something is wrong and we will just create the file with basic settings.
# Any more then this they somebody was messing with things and its not our fault things are this bad
if [ ! -f $DAEMON_USER_PREF ]; then
echo "ssid=stratux" >> $DAEMON_USER_PREF
echo "channel=1" >> $DAEMON_USER_PREF
fi
fi
##### End hostapd settings structure script

Wyświetl plik

@ -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

Wyświetl plik

@ -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";

53
image/fancontrol.py 100644 → 100755
Wyświetl plik

@ -3,32 +3,43 @@
#
# This script throttles a fan based on CPU temperature.
#
# It expects a fan that's externally powered, and uses GPIO pin 11 for control.
# It expects a fan that's externally powered, and uses GPIO pin 12 for control.
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 = '/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):
GPIO.setmode(GPIO.BOARD)
GPIO.setup(12, GPIO.OUT)
GPIO.setwarnings(False)
p=GPIO.PWM(12, 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()

Wyświetl plik

@ -1,8 +1,6 @@
interface=wlan0
driver=rtl871xdrv
ssid=stratux
hw_mode=g
channel=1
wme_enabled=1
ieee80211n=1
ignore_broadcast_ssid=0

Wyświetl plik

@ -1,7 +1,5 @@
interface=wlan0
ssid=stratux
hw_mode=g
channel=1
wmm_enabled=1
ieee80211n=1
ignore_broadcast_ssid=0

Wyświetl plik

@ -69,7 +69,7 @@ fi
#If an option should be followed by an argument, it should be followed by a ":".
#Notice there is no ":" after "oqh". The leading ":" suppresses error messages from
#getopts. This is required to get my unrecognized option code to work.
options=':s:c:e:oqh'
options=':s:c:eoqh'
while getopts $options option; do
case $option in
s) #set option "s"
@ -90,7 +90,7 @@ while getopts $options option; do
OPT_C=$OPTARG
echo "$parm Channel option -c used: $OPT_C"
if [[ "$OPT_C" =~ ^[0-9]+$ ]] && [ "$OPT_C" -ge 1 -a "$OPT_C" -le 13 ]; then
echo "${GREEN} Channel will now be set to ${BOLD}${UNDR}$OPT_C.${WHITE}${NORMAL}"
echo "${GREEN} Channel will now be set to ${BOLD}${UNDR}$OPT_C${WHITE}${NORMAL}."
else
echo "${BOLD}${RED}$err Channel is not within acceptable values, exiting...${WHITE}${NORMAL}"
exit 1
@ -99,8 +99,8 @@ while getopts $options option; do
;;
e) #set option "e"
if [[ -z "${OPTARG}" || "${OPTARG}" == *[[:space:]]* || "${OPTARG}" == -* ]]; then
echo "${BOLD}${RED}$err Encryption option(-e) used without passphrase, exiting...${WHITE}${NORMAL}"
exit 1
echo "${BOLD}${RED}$err Encryption option(-e) used without passphrase, Passphrase will be set to ${BOLD}$defaultPass${NORMAL}...${WHITE}${NORMAL}"
OPT_E=$defaultPass
else
OPT_E=$OPTARG
echo "$parm Encryption option -e used:"
@ -126,7 +126,7 @@ while getopts $options option; do
HELP
;;
\?) # invalid option
echo "${BOLD}${RED}$err Invalid option -$OPTARG" >&2
echo "${BOLD}${RED}$err Invalid option -$OPTARG ${WHITE}${NORMAL}" >&2
exit 1
;;
:) # Missing Arg
@ -161,7 +161,7 @@ echo "${BOLD}No errors found. Continuning...${NORMAL}"
echo ""
# files to edit
HOSTAPD=('/etc/hostapd/hostapd.conf' '/etc/hostapd/hostapd-edimax.conf')
HOSTAPD=('/etc/hostapd/hostapd.user')
####
#### File modification loop
@ -254,9 +254,31 @@ do
echo ""
fi
done
echo "${YELLOW}$att Don't forget to reboot... $att ${WHITE}"
echo "${RED}${BOLD} $att At this time the script will restart your WiFi services.${WHITE}${NORMAL}"
echo "If you are connected to Stratux through the ${BOLD}192.168.10.1${NORMAL} interface then you will be disconnected"
echo "Please wait 1 min and look for the new SSID on your wireless device."
sleep 3
echo "${YELLOW}$att Restarting Stratux WiFi Services... $att ${WHITE}"
echo "Killing hostapd..."
/usr/bin/killall -9 hostapd hostapd-edimax
echo "Killed..."
echo ""
echo "Killing DHCP Server..."
echo ""
/usr/sbin/service isc-dhcp-server stop
sleep 0.5
echo "Killed..."
echo ""
echo "ifdown wlan0..."
ifdown wlan0
sleep 0.5
echo "ifup wlan0..."
echo "Calling Stratux WiFI Start Script(stratux-wifi.sh)..."
ifup wlan0
sleep 0.5
echo ""
echo ""
echo "All systems should be up and running and you should see your new SSID!"
### End main loop ###

Wyświetl plik

@ -4,33 +4,52 @@ iface lo inet loopback
iface eth0 inet dhcp
allow-hotplug wlan0
#iface wlan0 inet manual
#wpa-roam /etc/wpa_supplicant/wpa_supplicant.conf
#iface default inet dhcp
iface wlan0 inet static
address 192.168.10.1
netmask 255.255.255.0
post-up /usr/sbin/stratux-wifi.sh
#####################################################################
## Custom settings not for novice users!!!!!!
## Modify at your own risk!!!!!!!!!!!!!!!!!!!
##
## Second Wifi Dongle for local work and internet access
## wifi must be open for these settings to work
## This template is for adding a second wifi dongle to your PI for internet access while debugging
## Modify /etc/wpa_supplicant/wpa_supplicant.conf with your settings also( see below )
##
## uncomment the next two lines to activate the service as well as modify the settings and comments below
#allow-hotplug wlan1
#iface wlan1 inet static
## Uncomment the following lines as needed.
# The SSID you want to connect to
# uncomment the next line and modify if necessary
# wireless-essid 6719
# The address you want to use on your network
# uncomment the next line and modify if necessary
# address 192.168.1.50
# The address of your netmask
# uncomment the next line and modify if necessary
# netmask 255.255.255.0
# The gateway of your router that you are connecting to
# uncomment the next line and modify
# gateway 192.168.1.1
# allow-hotplug wlan1
# iface wlan1 inet manual
# wpa-roam /etc/wpa_supplicant/wpa_supplicant.conf
# iface name_of_WPA_Config inet dhcp
# iface name_of_other_WPA_Config inet dhcp
## End of interfaces
#contents of wpa_supplicant.conf
#############################################################
# ctrl_interface=DIR=/var/run/wpa_supplicant GROUP=netdev
# update_config=1
# network={
# ssid="SSID_1"
# id_str="name_of_WPA_Config"
# scan_ssid=1
# key_mgmt=WPA-PSK
# psk="mypassword"
# priority=1
# }
# network={
# ssid="SSID_2"
# id_str="name_of_other_WPA_Config"
# scan_ssid=1
# key_mgmt=WPA-PSK
# psk="mypassword"
# priority=3
# }
#############################################################

Wyświetl plik

@ -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
@ -72,7 +76,6 @@ cp -f 10-stratux.rules mnt/etc/udev/rules.d
#stratux files
cp -f ../libdump978.so mnt/usr/lib/libdump978.so
cp -f ../linux-mpu9150/libimu.so mnt/usr/lib/libimu.so
#go1.5.1 setup
cp -rf /root/go mnt/root/
@ -126,6 +129,18 @@ 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 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
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
#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 rc.local mnt/etc/rc.local

25
image/rc.local 100755
Wyświetl plik

@ -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

295
image/sdr-tool.sh 100644
Wyświetl plik

@ -0,0 +1,295 @@
#!/bin/bash
######################################################################
# STRATUX SDR MANAGER #
######################################################################
#Set Script Name variable
SCRIPT=`basename ${BASH_SOURCE[0]}`
# rtl_eeprom -d 0 -s <String>:<Freq>:<PPM>
#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 {
HEAD
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
sleep 3
}
#Function to set the serial function
function SETSDRSERIAL {
HEAD
echo "# Setting ${WhichSDR}mhz SDR Serial Data #"
#Build this string
# rtl_eeprom -d 0 -s <String>:<Freq>:<PPM>
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 "Loading SDR info..."
sleep 2
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

Wyświetl plik

@ -1,29 +1,36 @@
#!/bin/bash
# Preliminaries. Kill off old services.
/usr/bin/killall -9 hostapd hostapd-edimax
/usr/sbin/service isc-dhcp-server stop
#Assume PI3 settings
DAEMON_CONF=/etc/hostapd/hostapd.conf
DAEMON_SBIN=/usr/sbin/hostapd
#User settings for hostapd.conf and hostapd-edimax.conf
DAEMON_USER_PREF=/etc/hostapd/hostapd.user
# Temporary hostapd.conf built by combining
# non-editable /etc/hostapd/hostapd.conf or hostapd-edimax.conf
# and the user configurable /etc/hostapd/hostapd.conf
DAEMON_TMP=/tmp/hostapd.conf
# Detect RPi version.
# Per http://elinux.org/RPi_HardwareHistory
DAEMON_CONF=/etc/hostapd/hostapd.conf
DAEMON_SBIN=/usr/sbin/hostapd
EW7811Un=$(lsusb | grep EW-7811Un)
RPI_REV=`cat /proc/cpuinfo | grep 'Revision' | awk '{print $3}' | sed 's/^1000//'`
if [ "$RPI_REV" = "a01041" ] || [ "$RPI_REV" = "a21041" ] || [ "$RPI_REV" = "900092" ] || [ "$RPI_REV" = "900093" ] && [ "$EW7811Un" != '' ]; then
# This is a RPi2B or RPi0 with Edimax USB Wifi dongle.
DAEMON_CONF=/etc/hostapd/hostapd-edimax.conf
DAEMON_SBIN=/usr/sbin/hostapd-edimax
else
DAEMON_CONF=/etc/hostapd/hostapd.conf
fi
#Make a new hostapd or hostapd-edimax conf file based on logic above
cat ${DAEMON_USER_PREF} ${DAEMON_CONF} > ${DAEMON_TMP}
${DAEMON_SBIN} -B ${DAEMON_CONF}
${DAEMON_SBIN} -B ${DAEMON_TMP}
sleep 5
sleep 3
/usr/sbin/service isc-dhcp-server start

Wyświetl plik

@ -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"
}

@ -1 +0,0 @@
Subproject commit 56658ffe83c23fde04fccc8e747bf9b7c1e184ea

Wyświetl plik

@ -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}

Wyświetl plik

@ -249,12 +249,12 @@ func degreesHdg(angle float64) float64 {
return angle * 180.0 / math.Pi
}
// roundToInt cheaply rounds a float64 to an int, rather than truncating
func roundToInt(in float64) (out int) {
// roundToInt16 cheaply rounds a float64 to an int16, rather than truncating
func roundToInt16(in float64) (out int16) {
if in >= 0 {
out = int(in + 0.5)
out = int16(in + 0.5)
} else {
out = int(in - 0.5)
out = int16(in - 0.5)
}
return
}

Wyświetl plik

@ -35,7 +35,8 @@ import (
"github.com/ricochet2200/go-disk-usage/du"
)
// http://www.faa.gov/nextgen/programs/adsb/wsa/media/GDL90_Public_ICD_RevA.PDF
// https://www.faa.gov/nextgen/programs/adsb/Archival/
// https://www.faa.gov/nextgen/programs/adsb/Archival/media/GDL90_Public_ICD_RevA.PDF
var debugLogf string // Set according to OS config.
var dataLogFilef string // Set according to OS config.
@ -75,6 +76,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
@ -100,8 +110,6 @@ type ReadCloser interface {
io.Closer
}
var developerMode bool
type msg struct {
MessageClass uint
TimeReceived time.Time
@ -163,8 +171,8 @@ func prepareMessage(data []byte) []byte {
// Compute CRC before modifying the message.
crc := crcCompute(data)
// Add the two CRC16 bytes before replacing control characters.
data = append(data, byte(crc & 0xFF))
data = append(data, byte((crc >> 8) & 0xFF))
data = append(data, byte(crc&0xFF))
data = append(data, byte(crc>>8))
tmp := []byte{0x7E} // Flag start.
@ -196,10 +204,18 @@ func makeLatLng(v float32) []byte {
return ret
}
func isDetectedOwnshipValid() bool {
return stratuxClock.Since(OwnshipTrafficInfo.Last_seen) < 10*time.Second
}
func makeOwnshipReport() bool {
if !isGPSValid() {
gpsValid := isGPSValid()
selfOwnshipValid := isDetectedOwnshipValid()
if !gpsValid && !selfOwnshipValid {
return false
}
curOwnship := OwnshipTrafficInfo
msg := make([]byte, 28)
// See p.16.
msg[0] = 0x0A // Message type "Ownship".
@ -218,15 +234,26 @@ func makeOwnshipReport() bool {
msg[4] = code[2] // Mode S address.
}
tmp := makeLatLng(mySituation.Lat)
msg[5] = tmp[0] // Latitude.
msg[6] = tmp[1] // Latitude.
msg[7] = tmp[2] // Latitude.
tmp = makeLatLng(mySituation.Lng)
msg[8] = tmp[0] // Longitude.
msg[9] = tmp[1] // Longitude.
msg[10] = tmp[2] // Longitude.
var tmp []byte
if selfOwnshipValid {
tmp = makeLatLng(curOwnship.Lat)
msg[5] = tmp[0] // Latitude.
msg[6] = tmp[1] // Latitude.
msg[7] = tmp[2] // Latitude.
tmp = makeLatLng(curOwnship.Lng)
msg[8] = tmp[0] // Longitude.
msg[9] = tmp[1] // Longitude.
msg[10] = tmp[2] // Longitude.
} else {
tmp = makeLatLng(mySituation.Lat)
msg[5] = tmp[0] // Latitude.
msg[6] = tmp[1] // Latitude.
msg[7] = tmp[2] // Latitude.
tmp = makeLatLng(mySituation.Lng)
msg[8] = tmp[0] // Longitude.
msg[9] = tmp[1] // Longitude.
msg[10] = tmp[2] // Longitude.
}
// This is **PRESSURE ALTITUDE**
//FIXME: Temporarily removing "invalid altitude" when pressure altitude not available - using GPS altitude instead.
@ -235,25 +262,30 @@ func makeOwnshipReport() bool {
var alt uint16
var altf float64
if isTempPressValid() {
if selfOwnshipValid {
altf = float64(curOwnship.Alt)
} else if isTempPressValid() {
altf = float64(mySituation.Pressure_alt)
} else {
altf = float64(mySituation.Alt) //FIXME: Pass GPS altitude if PA not available. **WORKAROUND FOR FF**
}
altf = (altf + 1000) / 25
alt = uint16(altf) & 0xFFF // Should fit in 12 bits.
msg[11] = byte((alt & 0xFF0) >> 4) // Altitude.
msg[12] = byte((alt & 0x00F) << 4)
if isGPSGroundTrackValid() {
if selfOwnshipValid || isGPSGroundTrackValid() {
msg[12] = msg[12] | 0x09 // "Airborne" + "True Track"
}
msg[13] = byte(0x80 | (mySituation.NACp & 0x0F)) //Set NIC = 8 and use NACp from ry83xai.go.
msg[13] = byte(0x80 | (mySituation.NACp & 0x0F)) //Set NIC = 8 and use NACp from gps.go.
gdSpeed := uint16(0) // 1kt resolution.
if isGPSGroundTrackValid() {
if selfOwnshipValid && curOwnship.Speed_valid {
gdSpeed = curOwnship.Speed
} else if isGPSGroundTrackValid() {
gdSpeed = uint16(mySituation.GroundSpeed + 0.5)
}
@ -269,7 +301,9 @@ func makeOwnshipReport() bool {
// Track is degrees true, set from GPS true course.
groundTrack := float32(0)
if isGPSGroundTrackValid() {
if selfOwnshipValid {
groundTrack = float32(curOwnship.Track)
} else if isGPSGroundTrackValid() {
groundTrack = mySituation.TrueCourse
}
@ -290,6 +324,17 @@ func makeOwnshipReport() bool {
msg[18] = 0x01 // "Light (ICAO) < 15,500 lbs"
if selfOwnshipValid {
// Limit tail number to 7 characters.
tail := curOwnship.Tail
if len(tail) > 7 {
tail = tail[:7]
}
// Copy tail number into message.
for i := 0; i < len(tail); i++ {
msg[19+i] = tail[i]
}
}
// Create callsign "Stratux".
msg[19] = 0x53
msg[20] = 0x74
@ -423,18 +468,14 @@ func makeStratuxStatus() []byte {
}
// Valid/Enabled: AHRS Enabled portion.
if globalSettings.AHRS_Enabled {
msg[12] = 1 << 0
}
// msg[12] = 1 << 0
// Valid/Enabled: last bit unused.
// Connected hardware: number of radios.
msg[15] = msg[15] | (byte(globalStatus.Devices) & 0x3)
// Connected hardware: RY83XAI.
if globalStatus.RY83XAI_connected {
msg[15] = msg[15] | (1 << 2)
}
// Connected hardware.
// RY835AI: msg[15] = msg[15] | (1 << 2)
// Number of GPS satellites locked.
msg[16] = byte(globalStatus.GPS_satellites_locked)
@ -442,24 +483,12 @@ func makeStratuxStatus() []byte {
// Number of satellites tracked
msg[17] = byte(globalStatus.GPS_satellites_tracked)
// Summarize number of UAT and 1090ES traffic targets for reports that follow.
var uat_traffic_targets uint16
var es_traffic_targets uint16
for _, traf := range traffic {
switch traf.Last_source {
case TRAFFIC_SOURCE_1090ES:
es_traffic_targets++
case TRAFFIC_SOURCE_UAT:
uat_traffic_targets++
}
}
// Number of UAT traffic targets.
msg[18] = byte((uat_traffic_targets & 0xFF00) >> 8)
msg[19] = byte(uat_traffic_targets & 0xFF)
msg[18] = byte((globalStatus.UAT_traffic_targets_tracking & 0xFF00) >> 8)
msg[19] = byte(globalStatus.UAT_traffic_targets_tracking & 0xFF)
// Number of 1090ES traffic targets.
msg[20] = byte((es_traffic_targets & 0xFF00) >> 8)
msg[21] = byte(es_traffic_targets & 0xFF)
msg[20] = byte((globalStatus.ES_traffic_targets_tracking & 0xFF00) >> 8)
msg[21] = byte(globalStatus.ES_traffic_targets_tracking & 0xFF)
// Number of UAT messages per minute.
msg[22] = byte((globalStatus.UAT_messages_last_minute & 0xFF00) >> 8)
@ -570,6 +599,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)
@ -759,7 +791,7 @@ type WeatherMessage struct {
}
// Send update to connected websockets.
func registerADSBTextMessageReceived(msg string) {
func registerADSBTextMessageReceived(msg string, uatMsg *uatparse.UATMsg) {
x := strings.Split(msg, " ")
if len(x) < 5 {
return
@ -767,16 +799,49 @@ 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++
}
wm.Type = x[0]
wm.Location = x[1]
wm.Time = x[2]
wm.Data = strings.Join(x[3:], " ")
wm.LocaltimeReceived = stratuxClock.Time
wmJSON, _ := json.Marshal(&wm)
// Send to weatherUpdate channel for any connected clients.
weatherUpdate.Send(wmJSON)
weatherUpdate.SendJSON(wm)
}
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) {
@ -865,11 +930,13 @@ 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)
weatherRawUpdate.SendJSON(f)
}
// Get all of the text reports.
textReports, _ := uatMsg.GetTextReports()
for _, r := range textReports {
registerADSBTextMessageReceived(r)
registerADSBTextMessageReceived(r, uatMsg)
}
thisMsg.uatMsg = uatMsg
}
@ -959,13 +1026,14 @@ type settings struct {
Ping_Enabled bool
GPS_Enabled bool
NetworkOutputs []networkConnection
AHRS_Enabled bool
SerialOutputs map[string]serialConnection
DisplayTrafficSource bool
DEBUG bool
ReplayLog bool
PPM int
OwnshipModeS string
WatchList string
DeveloperMode bool
}
type status struct {
@ -979,6 +1047,8 @@ type status struct {
UAT_messages_max uint
ES_messages_last_minute uint
ES_messages_max uint
UAT_traffic_targets_tracking uint16
ES_traffic_targets_tracking uint16
Ping_connected bool
GPS_satellites_locked uint16
GPS_satellites_seen uint16
@ -986,7 +1056,7 @@ type status struct {
GPS_position_accuracy float32
GPS_connected bool
GPS_solution string
RY83XAI_connected bool
GPS_detected_type uint
Uptime int64
UptimeClock time.Time
CPUTemp float32
@ -998,7 +1068,17 @@ type status struct {
NetworkDataMessagesSentNonqueueableLastSec uint64
NetworkDataBytesSentLastSec uint64
NetworkDataBytesSentNonqueueableLastSec uint64
Errors []string
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
PressureSensorConnected bool
IMUConnected bool
Errors []string
}
var globalSettings settings
@ -1013,11 +1093,11 @@ func defaultSettings() {
{Conn: nil, Ip: "", Port: 4000, Capability: NETWORK_GDL90_STANDARD | NETWORK_AHRS_GDL90},
// {Conn: nil, Ip: "", Port: 49002, Capability: NETWORK_AHRS_FFSIM},
}
globalSettings.AHRS_Enabled = false
globalSettings.DEBUG = false
globalSettings.DisplayTrafficSource = false
globalSettings.ReplayLog = false //TODO: 'true' for debug builds.
globalSettings.OwnshipModeS = "F00000"
globalSettings.DeveloperMode = false
}
func readSettings() {
@ -1086,6 +1166,21 @@ func openReplay(fn string, compressed bool) (WriteCloser, error) {
return ret, err
}
/*
fsWriteTest().
Makes a temporary file in 'dir', checks for error. Deletes the file.
*/
func fsWriteTest(dir string) error {
fn := dir + "/.write_test"
err := ioutil.WriteFile(fn, []byte("test\n"), 0644)
if err != nil {
return err
}
err = os.Remove(fn)
return err
}
func printStats() {
statTimer := time.NewTicker(30 * time.Second)
diskUsageWarning := false
@ -1194,6 +1289,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)
}
@ -1210,6 +1307,12 @@ func main() {
stratuxClock = NewMonotonic() // Start our "stratux clock".
// Set up mySituation, do it here so logging JSON doesn't panic
mySituation.mu_GPS = &sync.Mutex{}
mySituation.mu_GPSPerf = &sync.Mutex{}
mySituation.mu_Attitude = &sync.Mutex{}
mySituation.mu_Pressure = &sync.Mutex{}
// Set up status.
globalStatus.Version = stratuxVersion
globalStatus.Build = stratuxBuild
@ -1250,7 +1353,6 @@ 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")
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")
@ -1260,11 +1362,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 {
@ -1299,10 +1396,27 @@ 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()
initRY83XAI()
// Start the AHRS sensor monitoring.
initI2CSensors()
// Start the GPS external sensor monitoring.
initGPS()
// Start appropriate AHRS calc, depending on whether or not we have an IMU connected
if globalStatus.IMUConnected {
log.Println("AHRS Info: IMU connected - starting sensorAttitudeSender")
go sensorAttitudeSender()
} else {
log.Println("AHRS Info: IMU not connected - starting gpsAttitudeSender")
go gpsAttitudeSender()
}
// Start the heartbeat message loop in the background, once per second.
go heartBeatSender()

Wyświetl plik

@ -35,6 +35,31 @@ type SettingMessage struct {
// Weather updates channel.
var weatherUpdate *uibroadcaster
var trafficUpdate *uibroadcaster
var gdl90Update *uibroadcaster
func handleGDL90WS(conn *websocket.Conn) {
// Subscribe the socket to receive updates.
gdl90Update.AddSocket(conn)
// Connection closes when function returns. Since uibroadcast is writing and we don't need to read anything (for now), just keep it busy.
for {
buf := make([]byte, 1024)
_, err := conn.Read(buf)
if err != nil {
break
}
if buf[0] != 0 { // Dummy.
continue
}
time.Sleep(1 * time.Second)
}
}
// Situation updates channel.
var situationUpdate *uibroadcaster
// Raw weather (UATFrame packet stream) update channel.
var weatherRawUpdate *uibroadcaster
/*
The /weather websocket starts off by sending the current buffer of weather messages, then sends updates as they are received.
@ -57,6 +82,36 @@ func handleWeatherWS(conn *websocket.Conn) {
}
}
func handleJsonIo(conn *websocket.Conn) {
trafficMutex.Lock()
for _, traf := range traffic {
if !traf.Position_valid { // Don't send unless a valid position exists.
continue
}
trafficJSON, _ := json.Marshal(&traf)
conn.Write(trafficJSON)
}
// Subscribe the socket to receive updates.
trafficUpdate.AddSocket(conn)
weatherRawUpdate.AddSocket(conn)
situationUpdate.AddSocket(conn)
trafficMutex.Unlock()
// Connection closes when function returns. Since uibroadcast is writing and we don't need to read anything (for now), just keep it busy.
for {
buf := make([]byte, 1024)
_, err := conn.Read(buf)
if err != nil {
break
}
if buf[0] != 0 { // Dummy.
continue
}
time.Sleep(1 * time.Second)
}
}
// Works just as weather updates do.
func handleTrafficWS(conn *websocket.Conn) {
@ -104,7 +159,6 @@ func handleStatusWS(conn *websocket.Conn) {
*/
// Send status.
<-timer.C
update, _ := json.Marshal(&globalStatus)
_, err := conn.Write(update)
@ -112,19 +166,20 @@ func handleStatusWS(conn *websocket.Conn) {
// log.Printf("Web client disconnected.\n")
break
}
<-timer.C
}
}
func handleSituationWS(conn *websocket.Conn) {
timer := time.NewTicker(100 * time.Millisecond)
for {
<-timer.C
situationJSON, _ := json.Marshal(&mySituation)
_, err := conn.Write(situationJSON)
if err != nil {
break
}
<-timer.C
}
@ -219,8 +274,6 @@ func handleSettingsSetRequest(w http.ResponseWriter, r *http.Request) {
globalSettings.Ping_Enabled = val.(bool)
case "GPS_Enabled":
globalSettings.GPS_Enabled = val.(bool)
case "AHRS_Enabled":
globalSettings.AHRS_Enabled = val.(bool)
case "DEBUG":
globalSettings.DEBUG = val.(bool)
case "DisplayTrafficSource":
@ -232,6 +285,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":
@ -274,6 +343,17 @@ func doReboot() {
syscall.Reboot(syscall.LINUX_REBOOT_CMD_RESTART)
}
func handleDevelModeToggle(w http.ResponseWriter, r *http.Request) {
log.Printf("handleDevelModeToggle called!!!\n")
globalSettings.DeveloperMode = true
saveSettings()
}
func handleRestartRequest(w http.ResponseWriter, r *http.Request) {
log.Printf("handleRestartRequest called\n")
go doRestartApp()
}
func handleRebootRequest(w http.ResponseWriter, r *http.Request) {
setNoCache(w)
setJSONHeaders(w)
@ -282,6 +362,17 @@ func handleRebootRequest(w http.ResponseWriter, r *http.Request) {
go delayReboot()
}
func doRestartApp() {
time.Sleep(1)
syscall.Sync()
out, err := exec.Command("/bin/systemctl", "restart", "stratux").Output()
if err != nil {
log.Printf("restart error: %s\n%s", err.Error(), out)
} else {
log.Printf("restart: %s\n", out)
}
}
// AJAX call - /getClients. Responds with all connected clients.
func handleClientsGetRequest(w http.ResponseWriter, r *http.Request) {
setNoCache(w)
@ -307,7 +398,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
}
@ -444,11 +535,20 @@ func viewLogs(w http.ResponseWriter, r *http.Request) {
func managementInterface() {
weatherUpdate = NewUIBroadcaster()
trafficUpdate = NewUIBroadcaster()
situationUpdate = NewUIBroadcaster()
weatherRawUpdate = NewUIBroadcaster()
gdl90Update = NewUIBroadcaster()
http.HandleFunc("/", defaultServer)
http.Handle("/logs/", http.StripPrefix("/logs/", http.FileServer(http.Dir("/var/log"))))
http.HandleFunc("/view_logs/", viewLogs)
http.HandleFunc("/gdl90",
func(w http.ResponseWriter, req *http.Request) {
s := websocket.Server{
Handler: websocket.Handler(handleGDL90WS)}
s.ServeHTTP(w, req)
})
http.HandleFunc("/status",
func(w http.ResponseWriter, req *http.Request) {
s := websocket.Server{
@ -474,17 +574,26 @@ func managementInterface() {
s.ServeHTTP(w, req)
})
http.HandleFunc("/jsonio",
func(w http.ResponseWriter, req *http.Request) {
s := websocket.Server{
Handler: websocket.Handler(handleJsonIo)}
s.ServeHTTP(w, req)
})
http.HandleFunc("/getStatus", handleStatusRequest)
http.HandleFunc("/getSituation", handleSituationRequest)
http.HandleFunc("/getTowers", handleTowersRequest)
http.HandleFunc("/getSatellites", handleSatellitesRequest)
http.HandleFunc("/getSettings", handleSettingsGetRequest)
http.HandleFunc("/setSettings", handleSettingsSetRequest)
http.HandleFunc("/restart", handleRestartRequest)
http.HandleFunc("/shutdown", handleShutdownRequest)
http.HandleFunc("/reboot", handleRebootRequest)
http.HandleFunc("/getClients", handleClientsGetRequest)
http.HandleFunc("/updateUpload", handleUpdatePostRequest)
http.HandleFunc("/roPartitionRebuild", handleroPartitionRebuild)
http.HandleFunc("/develmodetoggle", handleDevelModeToggle)
err := http.ListenAndServe(managementAddr, nil)

Wyświetl plik

@ -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()

Wyświetl plik

@ -11,6 +11,8 @@ package main
import (
"errors"
"fmt"
"github.com/tarm/serial"
"golang.org/x/net/icmp"
"golang.org/x/net/ipv4"
"io/ioutil"
@ -50,6 +52,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
@ -64,10 +72,26 @@ const (
NETWORK_AHRS_FFSIM = 2
NETWORK_AHRS_GDL90 = 4
dhcp_lease_file = "/var/lib/dhcp/dhcpd.leases"
dhcp_lease_dir = "/var/lib/dhcp"
extra_hosts_file = "/etc/stratux-static-hosts.conf"
)
var dhcpLeaseFileWarning bool
var dhcpLeaseDirectoryLastTest time.Time // Last time fsWriteTest() was run on the DHCP lease directory.
// Read the "dhcpd.leases" file and parse out IP/hostname.
func getDHCPLeases() (map[string]string, error) {
// Do a write test. Even if we are able to read the file, it may be out of date because there's a fs write issue.
// Only perform the test once every 5 minutes to minimize writes.
if !dhcpLeaseFileWarning && (stratuxClock.Since(dhcpLeaseDirectoryLastTest) >= 5*time.Minute) {
err := fsWriteTest(dhcp_lease_dir)
if err != nil {
err_p := fmt.Errorf("Write error on '%s', your EFB may have issues receiving weather and traffic.", dhcp_lease_dir)
addSystemError(err_p)
dhcpLeaseFileWarning = true
}
dhcpLeaseDirectoryLastTest = stratuxClock.Time
}
dat, err := ioutil.ReadFile(dhcp_lease_file)
ret := make(map[string]string)
if err != nil {
@ -90,14 +114,33 @@ 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
}
func isSleeping(k string) bool {
ipAndPort := strings.Split(k, ":")
lastPing, ok := pingResponse[ipAndPort[0]]
// No ping response. Assume disconnected/sleeping device.
if !ok || stratuxClock.Since(lastPing) > (10*time.Second) {
if lastPing, ok := pingResponse[ipAndPort[0]]; !ok || stratuxClock.Since(lastPing) > (10*time.Second) {
return true
}
if stratuxClock.Since(outSockets[k].LastUnreachable) < (5 * time.Second) {
@ -113,6 +156,12 @@ 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
networkGDL90Chan <- msg.msg
}
netMutex.Lock()
defer netMutex.Unlock()
for k, netconn := range outSockets {
@ -135,11 +184,7 @@ func sendToAllConnectedClients(msg networkMessage) {
if sleepFlag {
continue
}
_, err := netconn.Conn.Write(msg.msg) // Write immediately.
if err != nil {
//TODO: Maybe we should drop the client? Retry first?
log.Printf("GDL Message error: %s\n", err.Error())
}
netconn.Conn.Write(msg.msg) // Write immediately.
totalNetworkMessagesSent++
globalStatus.NetworkDataMessagesSent++
globalStatus.NetworkDataMessagesSentNonqueueable++
@ -163,6 +208,73 @@ func sendToAllConnectedClients(msg networkMessage) {
}
}
var serialOutputChan chan []byte
var networkGDL90Chan chan []byte
func networkOutWatcher() {
for {
ch := <-networkGDL90Chan
gdl90Update.SendJSON(ch)
}
}
// 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() {
@ -461,7 +573,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.
*/
@ -500,8 +612,7 @@ 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.
if !ff_warned {
e := errors.New("Stratux is not supported by your EFB app. Your EFB app is known to regularly make changes that cause compatibility issues with Stratux. See the README for a list of apps that officially support Stratux.")
addSystemError(e)
@ -515,6 +626,8 @@ func ffMonitor() {
func initNetwork() {
messageQueue = make(chan networkMessage, 1024) // Buffered channel, 1024 messages.
serialOutputChan = make(chan []byte, 1024) // Buffered channel, 1024 GDL90 messages.
networkGDL90Chan = make(chan []byte, 1024)
outSockets = make(map[string]networkConnection)
pingResponse = make(map[string]time.Time)
netMutex = &sync.Mutex{}
@ -523,4 +636,6 @@ func initNetwork() {
go messageQueueSender()
go sleepMonitor()
go networkStatsCounter()
go serialOutWatcher()
go networkOutWatcher()
}

Wyświetl plik

@ -11,7 +11,7 @@ package main
import (
"bufio"
"fmt"
//"fmt"
"log"
"os"
"strings"
@ -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

278
main/sensors.go 100644
Wyświetl plik

@ -0,0 +1,278 @@
package main
import (
"fmt"
"log"
"math"
"time"
"../sensors"
"github.com/kidoman/embd"
_ "github.com/kidoman/embd/host/all"
// "github.com/kidoman/embd/sensor/bmp180"
"github.com/westphae/goflying/ahrs"
"github.com/westphae/goflying/ahrsweb"
)
var (
i2cbus embd.I2CBus
myPressureReader sensors.PressureReader
myIMUReader sensors.IMUReader
)
func initI2CSensors() {
i2cbus = embd.NewI2CBus(1)
globalStatus.PressureSensorConnected = initPressureSensor() // I2C temperature and pressure altitude.
log.Printf("AHRS Info: pressure sensor connected: %t\n", globalStatus.PressureSensorConnected)
globalStatus.IMUConnected = initIMU() // I2C accel/gyro/mag.
log.Printf("AHRS Info: IMU connected: %t\n", globalStatus.IMUConnected)
if !(globalStatus.PressureSensorConnected || globalStatus.IMUConnected) {
i2cbus.Close()
log.Println("AHRS Info: I2C bus closed")
}
if globalStatus.PressureSensorConnected {
go tempAndPressureSender()
log.Println("AHRS Info: monitoring pressure sensor")
}
}
func initPressureSensor() (ok bool) {
bmp, err := sensors.NewBMP280(&i2cbus, 100*time.Millisecond)
if err == nil {
myPressureReader = bmp
ok = true
log.Println("AHRS Info: Successfully initialized BMP280")
return
}
// TODO westphae: make bmp180.go to fit bmp interface
//for i := 0; i < 5; i++ {
// myBMPX80 = bmp180.New(i2cbus)
// _, err := myBMPX80.Temperature() // Test to see if it works, since bmp180.New doesn't return err
// if err != nil {
// time.Sleep(250 * time.Millisecond)
// } else {
// globalStatus.PressureSensorConnected = true
// log.Println("AHRS Info: Successfully initialized BMP180")
// return nil
// }
//}
log.Println("AHRS Info: couldn't initialize BMP280 or BMP180")
return
}
func initIMU() (ok bool) {
var err error
for i := 0; i < 5; i++ {
log.Printf("AHRS Info: attempt %d to connect to MPU9250\n", i)
myIMUReader, err = sensors.NewMPU9250()
if err != nil {
log.Printf("AHRS Info: attempt %d failed to connect to MPU9250\n", i)
time.Sleep(100 * time.Millisecond)
} else {
time.Sleep(time.Second)
log.Println("AHRS Info: Successfully connected MPU9250, running calibration")
myIMUReader.Calibrate(1, 5)
log.Println("AHRS Info: Successfully initialized MPU9250")
return true
}
}
//for i := 0; i < 5; i++ {
// myIMUReader, err = sensors.NewMPU6050()
// if err != nil {
// log.Printf("AHRS Info: attempt %d failed to connect to MPU6050\n", i)
// time.Sleep(100 * time.Millisecond)
// } else {
// ok = true
// log.Println("AHRS Info: Successfully initialized MPU6050")
// return
// }
//}
log.Println("AHRS Error: couldn't initialize MPU9250 or MPU6050")
return
}
func tempAndPressureSender() {
var (
temp float64
press float64
altLast float64
altitude float64
err error
dt float64 = 0.1
)
// Initialize variables for rate of climb calc
u := 5 / (5 + float64(dt)) // Use 5 sec decay time for rate of climb, slightly faster than typical VSI
if press, err = myPressureReader.Pressure(); err != nil {
log.Printf("AHRS Error: Couldn't read temp from sensor: %s", err)
}
altLast = CalcAltitude(press)
timer := time.NewTicker(time.Duration(1000*dt) * time.Millisecond)
for globalStatus.PressureSensorConnected {
<-timer.C
// Read temperature and pressure altitude.
temp, err = myPressureReader.Temperature()
if err != nil {
log.Printf("AHRS Error: Couldn't read temperature from sensor: %s", err)
}
press, err = myPressureReader.Pressure()
if err != nil {
log.Printf("AHRS Error: Couldn't read pressure from sensor: %s", err)
continue
}
// Update the Situation data.
mySituation.mu_Pressure.Lock()
mySituation.LastTempPressTime = stratuxClock.Time
mySituation.Temp = temp
altitude = CalcAltitude(press)
mySituation.Pressure_alt = altitude
// Assuming timer is reasonably accurate, use a regular ewma
mySituation.RateOfClimb = u*mySituation.RateOfClimb + (1-u)*(altitude-altLast)/(float64(dt)/60)
mySituation.mu_Pressure.Unlock()
altLast = altitude
}
}
func sensorAttitudeSender() {
log.Println("AHRS Info: Setting up sensorAttitudeSender")
var (
roll, pitch, heading float64
t time.Time
s ahrs.AHRSProvider
m *ahrs.Measurement
bx, by, bz, ax, ay, az, mx, my, mz float64
mpuError, magError error
headingMag, slipSkid, turnRate, gLoad float64
errHeadingMag, errSlipSkid, errTurnRate, errGLoad error
)
m = ahrs.NewMeasurement()
//TODO westphae: remove this logging when finished testing, or make it optional in settings
logger := ahrs.NewSensorLogger(fmt.Sprintf("/var/log/sensors_%s.csv", time.Now().Format("20060102_150405")),
"T", "TS", "A1", "A2", "A3", "H1", "H2", "H3", "M1", "M2", "M3", "TW", "W1", "W2", "W3", "TA", "Alt",
"pitch", "roll", "heading", "mag_heading", "slip_skid", "turn_rate", "g_load", "T_Attitude")
defer logger.Close()
ahrswebListener, err := ahrsweb.NewKalmanListener()
if err != nil {
log.Printf("AHRS Error: couldn't start ahrswebListener: %s\n", err.Error())
}
// Need a 10Hz sampling freq
timer := time.NewTicker(100 * time.Millisecond) // ~10Hz update.
for globalStatus.IMUConnected {
<-timer.C
t = stratuxClock.Time
m.T = float64(t.UnixNano()/1000) / 1e6
_, bx, by, bz, ax, ay, az, mx, my, mz, mpuError, magError = myIMUReader.ReadRaw()
//TODO westphae: allow user configuration of this mapping from a file, plus UI modification
//m.B1, m.B2, m.B3 = +by, -bx, +bz // This is how the RY83XAI is wired up
//m.A1, m.A2, m.A3 = -ay, +ax, -az // This is how the RY83XAI is wired up
m.B1, m.B2, m.B3 = -bx, +by, -bz // This is how the OpenFlightBox board is wired up
m.A1, m.A2, m.A3 = -ay, +ax, +az // This is how the OpenFlightBox board is wired up
m.M1, m.M2, m.M3 = +mx, +my, +mz
m.SValid = mpuError == nil
m.MValid = magError == nil
if mpuError != nil {
log.Printf("AHRS Gyro/Accel Error, not using for this run: %s\n", mpuError.Error())
//TODO westphae: disconnect?
}
if magError != nil {
log.Printf("AHRS Magnetometer Error, not using for this run: %s\n", magError.Error())
m.MValid = false
}
m.WValid = t.Sub(mySituation.LastGroundTrackTime) < 500*time.Millisecond
if m.WValid {
m.W1 = mySituation.GroundSpeed * math.Sin(float64(mySituation.TrueCourse)*ahrs.Deg)
m.W2 = mySituation.GroundSpeed * math.Cos(float64(mySituation.TrueCourse)*ahrs.Deg)
if globalStatus.PressureSensorConnected {
m.W3 = mySituation.RateOfClimb * 3600 / 6076.12
} else {
m.W3 = float64(mySituation.GPSVertVel) * 3600 / 6076.12
}
}
// Run the AHRS calcs
if s == nil { // s is nil if we should (re-)initialize the Kalman state
log.Println("AHRS Info: initializing new simple AHRS")
s = ahrs.InitializeSimple(m, "")
}
s.Compute(m)
// Debugging server:
if ahrswebListener != nil {
ahrswebListener.Send(s.GetState(), m)
}
// If we have valid AHRS info, then send
if s.Valid() {
mySituation.mu_Attitude.Lock()
roll, pitch, heading = s.CalcRollPitchHeading()
mySituation.Roll = roll / ahrs.Deg
mySituation.Pitch = pitch / ahrs.Deg
mySituation.Gyro_heading = heading / ahrs.Deg
if headingMag, errHeadingMag = myIMUReader.MagHeading(); errHeadingMag != nil {
log.Printf("AHRS MPU Error: %s\n", errHeadingMag.Error())
} else {
mySituation.Mag_heading = headingMag
}
if slipSkid, errSlipSkid = myIMUReader.SlipSkid(); errSlipSkid != nil {
log.Printf("AHRS MPU Error: %s\n", errSlipSkid.Error())
} else {
mySituation.SlipSkid = slipSkid
}
if turnRate, errTurnRate = myIMUReader.RateOfTurn(); errTurnRate != nil {
log.Printf("AHRS MPU Error: %s\n", errTurnRate.Error())
} else {
mySituation.RateOfTurn = turnRate
}
if gLoad, errGLoad = myIMUReader.GLoad(); errGLoad != nil {
log.Printf("AHRS MPU Error: %s\n", errGLoad.Error())
} else {
mySituation.GLoad = gLoad
}
mySituation.LastAttitudeTime = t
mySituation.mu_Attitude.Unlock()
// 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.
} else {
s = nil
mySituation.LastAttitudeTime = time.Time{}
}
makeAHRSGDL90Report() // Send whether or not valid - the function will invalidate the values as appropriate
logger.Log(
float64(t.UnixNano()/1000)/1e6,
m.T, m.A1, m.A2, m.A3, m.B1, m.B2, m.B3, m.M1, m.M2, m.M3,
float64(mySituation.LastGroundTrackTime.UnixNano()/1000)/1e6, m.W1, m.W2, m.W3,
float64(mySituation.LastTempPressTime.UnixNano()/1000)/1e6, mySituation.Pressure_alt,
pitch/ahrs.Deg, roll/ahrs.Deg, heading/ahrs.Deg, headingMag, slipSkid, turnRate, gLoad,
float64(mySituation.LastAttitudeTime.UnixNano()/1000)/1e6)
}
log.Println("AHRS Info: Exited sensorAttitudeSender loop")
globalStatus.IMUConnected = false
ahrswebListener.Close()
myPressureReader.Close()
myIMUReader.Close()
}

Wyświetl plik

@ -84,7 +84,7 @@ type TrafficInfo struct {
TargetType uint8 // types decribed in const above
SignalLevel float64 // Signal level, dB RSSI.
Squawk int // Squawk code
Position_valid bool // set when position report received. Unset after n seconds? (To-do)
Position_valid bool //TODO: set when position report received. Unset after n seconds?
Lat float32 // decimal degrees, north positive
Lng float32 // decimal degrees, east positive
Alt int32 // Pressure altitude, feet
@ -109,7 +109,7 @@ type TrafficInfo struct {
Last_GnssDiffAlt int32 // Altitude at last GnssDiffFromBaroAlt update.
Last_speed time.Time // Time of last velocity and track update (stratuxClock).
Last_source uint8 // Last frequency on which this target was received.
ExtrapolatedPosition bool // TO-DO: 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.
Distance float64 // Distance to traffic from ownship, if it can be calculated.
//FIXME: Some indicator that Bearing and Distance are valid, since they aren't always available.
@ -165,13 +165,26 @@ func sendTrafficUpdates() {
trafficMutex.Lock()
defer trafficMutex.Unlock()
cleanupOldEntries()
var msg []byte
// Summarize number of UAT and 1090ES traffic targets for reports that follow.
globalStatus.UAT_traffic_targets_tracking = 0
globalStatus.ES_traffic_targets_tracking = 0
for _, traf := range traffic {
switch traf.Last_source {
case TRAFFIC_SOURCE_1090ES:
globalStatus.ES_traffic_targets_tracking++
case TRAFFIC_SOURCE_UAT:
globalStatus.UAT_traffic_targets_tracking++
}
}
msgs := make([][]byte, 1)
if globalSettings.DEBUG && (stratuxClock.Time.Second()%15) == 0 {
log.Printf("List of all aircraft being tracked:\n")
log.Printf("==================================================================\n")
}
code, _ := strconv.ParseInt(globalSettings.OwnshipModeS, 16, 32)
for icao, ti := range traffic { // TO-DO: Limit number of aircraft in traffic message. ForeFlight 7.5 chokes at ~1000-2000 messages depending on iDevice RAM. Practical limit likely around ~500 aircraft without filtering.
for icao, ti := range traffic { // ForeFlight 7.5 chokes at ~1000-2000 messages depending on iDevice RAM. Practical limit likely around ~500 aircraft without filtering.
if isGPSValid() {
// func distRect(lat1, lon1, lat2, lon2 float64) (dist, bearing, distN, distE float64) {
dist, bearing := distance(float64(mySituation.Lat), float64(mySituation.Lng), float64(ti.Lat), float64(ti.Lng))
@ -194,23 +207,35 @@ func sendTrafficUpdates() {
traffic[icao] = ti // write the updated ti back to the map
//log.Printf("Traffic age of %X is %f seconds\n",icao,ti.Age)
if ti.Age > 2 { // if nothing polls an inactive ti, it won't push to the webUI, and its Age won't update.
tiJSON, _ := json.Marshal(&ti)
trafficUpdate.Send(tiJSON)
trafficUpdate.SendJSON(ti)
}
if ti.Position_valid && ti.Age < 6 { // ... but don't pass stale data to the EFB. TO-DO: Coast old traffic? Need to determine how FF, WingX, etc deal with stale targets.
if ti.Position_valid && ti.Age < 6 { // ... but don't pass stale data to the EFB.
//TODO: Coast old traffic? Need to determine how FF, WingX, etc deal with stale targets.
logTraffic(ti) // only add to the SQLite log if it's not stale
if ti.Icao_addr == uint32(code) { //
log.Printf("Ownship target detected for code %X\n", code) // DEBUG - REMOVE
if ti.Icao_addr == uint32(code) {
if globalSettings.DEBUG {
log.Printf("Ownship target detected for code %X\n", code)
}
OwnshipTrafficInfo = ti
} else {
msg = append(msg, makeTrafficReportMsg(ti)...)
cur_n := len(msgs) - 1
if len(msgs[cur_n]) >= 35 {
// Batch messages into packets with at most 35 traffic reports
// to keep each packet under 1KB.
cur_n++
msgs = append(msgs, make([]byte, 0))
}
msgs[cur_n] = append(msgs[cur_n], makeTrafficReportMsg(ti)...)
}
}
}
if len(msg) > 0 {
sendGDL90(msg, false)
for i := 0; i < len(msgs); i++ {
msg := msgs[i]
if len(msg) > 0 {
sendGDL90(msg, false)
}
}
}
@ -222,8 +247,7 @@ func registerTrafficUpdate(ti TrafficInfo) {
return
}
*/ // Send all traffic to the websocket and let JS sort it out. This will provide user indication of why they see 1000 ES messages and no traffic.
tiJSON, _ := json.Marshal(&ti)
trafficUpdate.Send(tiJSON)
trafficUpdate.SendJSON(ti)
}
func makeTrafficReportMsg(ti TrafficInfo) []byte {
@ -677,7 +701,7 @@ func esListen() {
}
// generate human readable summary of message types for debug
// TO-DO: Use for ES message statistics?
//TODO: Use for ES message statistics?
/*
var s1 string
if newTi.DF == 17 {
@ -1061,7 +1085,7 @@ func icao2reg(icao_addr uint32) (string, bool) {
} else if (icao_addr >= 0xC00001) && (icao_addr <= 0xC3FFFF) {
nation = "CA"
} else {
// future national decoding is TO-DO
//TODO: future national decoding.
return "NON-NA", false
}

Wyświetl plik

@ -11,6 +11,7 @@
package main
import (
"encoding/json"
"golang.org/x/net/websocket"
"sync"
"time"
@ -36,6 +37,11 @@ func (u *uibroadcaster) Send(msg []byte) {
u.messages <- msg
}
func (u *uibroadcaster) SendJSON(i interface{}) {
j, _ := json.Marshal(&i)
u.Send(j)
}
func (u *uibroadcaster) AddSocket(sock *websocket.Conn) {
u.sockets_mu.Lock()
u.sockets = append(u.sockets, sock)

Wyświetl plik

@ -1,7 +0,0 @@
package mpu
type BMP interface {
Temperature() (float64, error)
Pressure() (float64, error)
Close()
}

Wyświetl plik

@ -1,74 +0,0 @@
package mpu
import (
"github.com/westphae/goflying/bmp280"
"github.com/kidoman/embd"
"log"
"time"
"errors"
)
const (
BMP280PowerMode = bmp280.NormalMode
BMP280Standby = bmp280.StandbyTime63ms
BMP280FilterCoeff = bmp280.FilterCoeff16
BMP280TempRes = bmp280.Oversamp16x
BMP280PressRes = bmp280.Oversamp16x
)
type BMP280 struct {
bmp *bmp280.BMP280
bmpdata *bmp280.BMPData
running bool
}
var bmperr = errors.New("BMP280 Error: BMP280 is not running")
func NewBMP280(i2cbus *embd.I2CBus, freq time.Duration) (*BMP280, error) {
var (
bmp *bmp280.BMP280
errbmp error
)
bmp, errbmp = bmp280.NewBMP280(i2cbus, bmp280.Address1,
BMP280PowerMode, BMP280Standby, BMP280FilterCoeff, BMP280TempRes, BMP280PressRes)
if errbmp != nil { // Maybe the BMP280 isn't at Address1, try Address2
bmp, errbmp = bmp280.NewBMP280(i2cbus, bmp280.Address2,
BMP280PowerMode, BMP280Standby, BMP280FilterCoeff, BMP280TempRes, BMP280PressRes)
}
if errbmp != nil {
log.Println("AHRS Error: couldn't initialize BMP280")
return nil, errbmp
}
newbmp := BMP280{bmp: bmp, bmpdata: new(bmp280.BMPData)}
go newbmp.run()
return &newbmp, nil
}
func (bmp *BMP280) run() {
bmp.running = true
for bmp.running {
bmp.bmpdata = <-bmp.bmp.C
}
}
func (bmp *BMP280) Temperature() (float64, error) {
if !bmp.running {
return 0, bmperr
}
return bmp.bmpdata.Temperature, nil
}
func (bmp *BMP280) Pressure() (float64, error) {
if !bmp.running {
return 0, bmperr
}
return bmp.bmpdata.Pressure, nil
}
func (bmp *BMP280) Close() {
bmp.running = false
bmp.bmp.Close()
}

Wyświetl plik

@ -1,12 +0,0 @@
package mpu
type MPU interface {
Close()
ResetHeading(float64, float64)
MagHeading() (float64, error)
SlipSkid() (float64, error)
RateOfTurn() (float64, error)
GLoad() (float64, error)
ReadRaw() (int64, float64, float64, float64, float64, float64, float64, float64, float64, float64, error, error)
Calibrate(int, int) error
}

Wyświetl plik

@ -1,197 +0,0 @@
// Package mpu6050 allows interfacing with InvenSense mpu6050 barometric pressure sensor. This sensor
// has the ability to provided compensated temperature and pressure readings.
package mpu
import (
"../linux-mpu9150/mpu"
"log"
"math"
"time"
"errors"
)
//https://www.olimex.com/Products/Modules/Sensors/MOD-MPU6050/resources/RM-MPU-60xxA_rev_4.pdf
const (
pollDelay = 98 * time.Millisecond // ~10Hz
)
// MPU6050 represents a InvenSense MPU6050 sensor.
type MPU6050 struct {
poll time.Duration
started bool
pitch float64
roll float64
// Calibration variables.
calibrated bool
pitch_history []float64
roll_history []float64
pitch_resting float64
roll_resting float64
// For tracking heading (mixing GPS track and the gyro output).
heading float64 // Current heading.
gps_track float64 // Last reading directly from the gyro for comparison with current heading.
gps_track_valid bool
heading_correction float64
quit chan struct{}
}
// New returns a handle to a MPU6050 sensor.
func NewMPU6050() (*MPU6050, error) {
n := &MPU6050{poll: pollDelay}
if err := n.startUp(); err != nil {
return nil, err
}
return n, nil
}
func (d *MPU6050) startUp() error {
mpu_sample_rate := 10 // 10 Hz read rate of hardware IMU
yaw_mix_factor := 0 // must be zero if no magnetometer
err := mpu.InitMPU(mpu_sample_rate, yaw_mix_factor)
if err != 0 {
return errors.New("MPU6050 Error: couldn't start MPU")
}
d.pitch_history = make([]float64, 0)
d.roll_history = make([]float64, 0)
d.started = true
d.run()
return nil
}
/*
func (d *MPU6050) calibrate() {
//TODO: Error checking to make sure that the histories are extensive enough to be significant.
//TODO: Error checking to do continuous calibrations.
pitch_adjust := float64(0)
for _, v := range d.pitch_history {
pitch_adjust = pitch_adjust + v
}
pitch_adjust = pitch_adjust / float64(len(d.pitch_history))
d.pitch_resting = pitch_adjust
roll_adjust := float64(0)
for _, v := range d.roll_history {
roll_adjust = roll_adjust + v
}
roll_adjust = roll_adjust / float64(len(d.roll_history))
d.roll_resting = roll_adjust
log.Printf("calibrate: pitch %f, roll %f\n", pitch_adjust, roll_adjust)
d.calibrated = true
}
*/
func normalizeHeading(h float64) float64 {
for h < float64(0.0) {
h = h + float64(360.0)
}
for h >= float64(360.0) {
h = h - float64(360.0)
}
return h
}
func (d *MPU6050) getMPUData() {
pr, rr, hr, err := mpu.ReadMPU()
// Convert from radians to degrees.
pitch := float64(pr) * (float64(180.0) / math.Pi)
roll := float64(-rr) * (float64(180.0) / math.Pi)
heading := float64(hr) * (float64(180.0) / math.Pi)
if heading < float64(0.0) {
heading = float64(360.0) + heading
}
if err == nil {
d.pitch = pitch
d.roll = roll
// Heading is raw value off the IMU. Without mag compass fusion, need to apply correction bias.
// Amount of correction is set by ResetHeading() -- doesn't necessarily have to be based off GPS.
d.heading = normalizeHeading((heading - d.heading_correction))
} else {
// log.Printf("mpu6050.calculatePitchAndRoll(): mpu.ReadMPU() err: %s\n", err.Error())
}
}
func (d *MPU6050) run() {
time.Sleep(d.poll)
go func() {
d.quit = make(chan struct{})
timer := time.NewTicker(d.poll)
// calibrateTimer := time.NewTicker(1 * time.Minute)
for {
select {
case <-timer.C:
d.getMPUData()
// case <-calibrateTimer.C:
// d.calibrate()
// calibrateTimer.Stop()
case <-d.quit:
mpu.CloseMPU()
return
}
}
}()
return
}
// Set heading from a known value (usually GPS true heading).
func (d *MPU6050) ResetHeading(newHeading float64, gain float64) {
if gain < 0.001 { // sanitize our inputs!
gain = 0.001
} else if gain > 1 {
gain = 1
}
old_hdg := d.heading // only used for debug log report
//newHeading = float64(30*time.Now().Minute()) // demo input for testing
newHeading = normalizeHeading(newHeading) // sanitize the inputs
// By applying gain factor, this becomes a 1st order function that slowly converges on solution.
// Time constant is poll rate over gain. With gain of 0.1, convergence to +/-2 deg on a 180 correction difference is about 4 sec; 0.01 converges in 45 sec.
hdg_corr_bias := float64(d.heading - newHeading) // desired adjustment to heading_correction
if hdg_corr_bias > 180 {
hdg_corr_bias = hdg_corr_bias - 360
} else if hdg_corr_bias < -180 {
hdg_corr_bias = hdg_corr_bias + 360
}
hdg_corr_bias = hdg_corr_bias * gain
d.heading_correction = normalizeHeading(d.heading_correction + hdg_corr_bias)
log.Printf("Adjusted heading. Old: %f Desired: %f Adjustment: %f New: %f\n", old_hdg, newHeading, hdg_corr_bias, d.heading-hdg_corr_bias)
}
// Close.
func (d *MPU6050) Close() {
if d.quit != nil {
d.quit <- struct{}{}
}
}
func (d *MPU6050) MagHeading() (float64, error) { return 0, nil }
func (d *MPU6050) SlipSkid() (float64, error) { return 0, nil }
func (d *MPU6050) RateOfTurn() (float64, error) { return 0, nil }
func (d *MPU6050) GLoad() (float64, error) { return 0, nil }
func (d *MPU6050) ReadRaw() (int64, float64, float64, float64, float64, float64, float64, float64, float64, float64, error, error) {
return 0, // Ts, time of last sensor reading
0.0, 0.0, 0.0, // Gyro x, y, z
0.0, 0.0, 0.0, // Accel x, y, z
0.0, 0.0, 0.0, // Mag x, y, z
errors.New("Error: ReadRaw() not implemented yet for MPU6050"),
errors.New("Error: MPU6050 magnetometer isn't working on RY835AI chip")
}
func (d *MPU6050) Calibrate(dur int, retries int) error {
return nil //TODO westphae: for now, maybe we'll get lucky; but eventually we should calibrate
}

Wyświetl plik

@ -103,7 +103,6 @@ Stratux makes available a webserver to retrieve statistics which may be useful t
"GPS_satellites_locked": 0, // Number of GPS satellites used in last GPS lock.
"GPS_connected": true, // GPS unit connected and functioning.
"GPS_solution": "", // "DGPS (WAAS)", "3D GPS", "N/A", or "" when GPS not connected/enabled.
"RY835AI_connected": false, // GPS/AHRS unit - use only for debugging (this will be removed).
"Uptime": 227068, // Device uptime (in milliseconds).
"CPUTemp": 42.236 // CPU temperature (in ºC).
}
@ -131,7 +130,6 @@ Stratux makes available a webserver to retrieve statistics which may be useful t
"Capability": 2
}
],
"AHRS_Enabled": false,
"DEBUG": false,
"ReplayLog": true,
"PPM": 0,

Wyświetl plik

@ -23,16 +23,19 @@ cp __root__stratux-pre-start.sh work/bin/
cp dump1090/dump1090 work/bin/
cp -r web work/bin/
cp image/hostapd.conf work/bin/
cp image/hostapd-edimax.conf work/bin/
cp image/config.txt work/bin/
cp image/rtl-sdr-blacklist.conf work/bin/
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/
cp image/fancontrol.py work/bin/
cp image/stratux-wifi.sh work/bin/
#TODO: librtlsdr.
cd work/

Wyświetl plik

@ -23,9 +23,15 @@ ln -fs /lib/systemd/system/stratux.service /etc/systemd/system/multi-user.target
cp -f hostapd.conf /etc/hostapd/hostapd.conf
cp -f hostapd-edimax.conf /etc/hostapd/hostapd-edimax.conf
#WiFi Hostapd ver test and hostapd.conf builder script
cp -f stratux-wifi.sh /usr/sbin/
#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

79
sensors/bmp280.go 100644
Wyświetl plik

@ -0,0 +1,79 @@
// Package sensors provides a stratux interface to sensors used for AHRS calculations.
package sensors
import (
"errors"
"time"
"github.com/kidoman/embd"
"github.com/westphae/goflying/bmp280"
)
const (
bmp280PowerMode = bmp280.NormalMode
bmp280Standby = bmp280.StandbyTime63ms
bmp280FilterCoeff = bmp280.FilterCoeff16
bmp280TempRes = bmp280.Oversamp16x
bmp280PressRes = bmp280.Oversamp16x
)
// BMP280 represents a BMP280 sensor and implements the PressureSensor interface.
type BMP280 struct {
sensor *bmp280.BMP280
data *bmp280.BMPData
running bool
}
var errBMP = errors.New("BMP280 Error: BMP280 is not running")
// NewBMP280 looks for a BMP280 connected on the I2C bus having one of the valid addresses and begins reading it.
func NewBMP280(i2cbus *embd.I2CBus, freq time.Duration) (*BMP280, error) {
var (
bmp *bmp280.BMP280
errbmp error
)
bmp, errbmp = bmp280.NewBMP280(i2cbus, bmp280.Address1,
bmp280PowerMode, bmp280Standby, bmp280FilterCoeff, bmp280TempRes, bmp280PressRes)
if errbmp != nil { // Maybe the BMP280 isn't at Address1, try Address2
bmp, errbmp = bmp280.NewBMP280(i2cbus, bmp280.Address2,
bmp280PowerMode, bmp280Standby, bmp280FilterCoeff, bmp280TempRes, bmp280PressRes)
}
if errbmp != nil {
return nil, errbmp
}
newbmp := BMP280{sensor: bmp, data: new(bmp280.BMPData)}
go newbmp.run()
return &newbmp, nil
}
func (bmp *BMP280) run() {
bmp.running = true
for bmp.running {
bmp.data = <-bmp.sensor.C
}
}
// Temperature returns the current temperature in degrees C measured by the BMP280
func (bmp *BMP280) Temperature() (float64, error) {
if !bmp.running {
return 0, errBMP
}
return bmp.data.Temperature, nil
}
// Pressure returns the current pressure in mbar measured by the BMP280
func (bmp *BMP280) Pressure() (float64, error) {
if !bmp.running {
return 0, errBMP
}
return bmp.data.Pressure, nil
}
// Close stops the measurements of the BMP280
func (bmp *BMP280) Close() {
bmp.running = false
bmp.sensor.Close()
}

15
sensors/imu.go 100644
Wyświetl plik

@ -0,0 +1,15 @@
// Package sensors provides a stratux interface to sensors used for AHRS calculations.
package sensors
// IMUReader provides an interface to various Inertial Measurement Unit sensors,
// such as the InvenSense MPU9150 or MPU9250.
type IMUReader interface {
// ReadRaw returns the time, Gyro X-Y-Z, Accel X-Y-Z, Mag X-Y-Z, error reading Gyro/Accel, and error reading Mag.
ReadRaw() (T int64, G1, G2, G3, A1, A2, A3, M1, M2, M3 float64, GAError, MagError error)
Calibrate(duration, retries int) error // Calibrate kicks off a calibration for specified duration (s) and retries.
Close() // Close stops reading the MPU.
MagHeading() (hdg float64, MagError error) // MagHeading returns the magnetic heading in degrees.
SlipSkid() (slipSkid float64, err error) // SlipSkid returns the slip/skid angle in degrees.
RateOfTurn() (turnRate float64, err error) // RateOfTurn returns the turn rate in degrees per second.
GLoad() (gLoad float64, err error) // GLoad returns the current G load, in G's.
}

Wyświetl plik

@ -1,21 +1,24 @@
// Package MPU9250 provides a stratux interface to the MPU9250 IMU
package mpu
// Package sensors provides a stratux interface to sensors used for AHRS calculations.
package sensors
import (
"errors"
"github.com/westphae/goflying/mpu9250"
"log"
"math"
"time"
"github.com/westphae/goflying/mpu9250"
"log"
)
const (
DECAY = 0.8
GYRORANGE = 250
ACCELRANGE = 4
UPDATEFREQ = 1000
decay = 0.8 // decay is the decay constant used for exponential smoothing of sensor values.
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 = 1000 // updateFreq is the rate at which to update the sensor values.
)
// MPU9250 represents an InvenSense MPU9250 attached to the I2C bus and satisfies
// the IMUReader interface.
type MPU9250 struct {
mpu *mpu9250.MPU9250
pitch, roll, heading float64
@ -29,6 +32,8 @@ type MPU9250 struct {
quit chan 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) {
var (
m MPU9250
@ -36,13 +41,14 @@ func NewMPU9250() (*MPU9250, error) {
err error
)
mpu, err = mpu9250.NewMPU9250(GYRORANGE, ACCELRANGE, UPDATEFREQ, true, false)
log.Println("AHRS Info: Making new MPU9250")
mpu, err = mpu9250.NewMPU9250(gyroRange, accelRange, updateFreq, true, false)
if err != nil {
log.Println("AHRS Error: couldn't initialize MPU9250")
return nil, err
}
// Set Gyro (Accel) LPFs to 20 (21) Hz to filter out prop/glareshield vibrations above 1200 (1260) RPM
log.Println("AHRS Info: Setting MPU9250 LPF")
mpu.SetGyroLPF(21)
mpu.SetAccelLPF(21)
@ -50,6 +56,7 @@ func NewMPU9250() (*MPU9250, error) {
m.valid = true
time.Sleep(100 * time.Millisecond)
log.Println("AHRS Info: monitoring IMU")
m.run()
return &m, nil
@ -74,8 +81,8 @@ func (m *MPU9250) run() {
}
if data.MagError == nil && data.NM > 0 {
hM := math.Atan2(-data.M2, data.M1)*180/math.Pi
if hM - m.headingMag < -180 {
hM := math.Atan2(-data.M2, data.M1) * 180 / math.Pi
if hM-m.headingMag < -180 {
hM += 360
}
smooth(&m.headingMag, hM)
@ -95,45 +102,42 @@ func (m *MPU9250) run() {
}
func smooth(val *float64, new float64) {
*val = DECAY**val + (1-DECAY)*new
}
func (m *MPU9250) ResetHeading(newHeading float64, gain float64) {
m.heading = newHeading
*val = decay**val + (1-decay)*new
}
// MagHeading returns the magnetic heading in degrees.
func (m *MPU9250) MagHeading() (float64, error) {
if m.valid {
return m.headingMag, nil
} else {
return 0, errors.New("MPU error: data not available")
}
return 0, errors.New("MPU error: data not available")
}
// SlipSkid returns the slip/skid angle in degrees.
func (m *MPU9250) SlipSkid() (float64, error) {
if m.valid {
return m.slipSkid, nil
} else {
return 0, errors.New("MPU error: data not available")
}
return 0, errors.New("MPU error: data not available")
}
// RateOfTurn returns the turn rate in degrees per second.
func (m *MPU9250) RateOfTurn() (float64, error) {
if m.valid {
return m.turnRate, nil
} else {
return 0, errors.New("MPU error: data not available")
}
return 0, errors.New("MPU error: data not available")
}
// GLoad returns the current G load, in G's.
func (m *MPU9250) GLoad() (float64, error) {
if m.valid {
return m.gLoad, nil
} else {
return 0, errors.New("MPU error: data not available")
}
return 0, errors.New("MPU error: data not available")
}
// ReadRaw returns the time, Gyro X-Y-Z, Accel X-Y-Z, Mag X-Y-Z, error reading Gyro/Accel, and error reading Mag.
func (m *MPU9250) ReadRaw() (T int64, G1, G2, G3, A1, A2, A3, M1, M2, M3 float64, GAError, MAGError error) {
data := <-m.mpu.C
T = data.T.UnixNano()
@ -151,18 +155,23 @@ func (m *MPU9250) ReadRaw() (T int64, G1, G2, G3, A1, A2, A3, M1, M2, M3 float64
return
}
// Calibrate kicks off a calibration for specified duration (s) and retries.
func (m *MPU9250) Calibrate(dur, retries int) (err error) {
for i:=0; i<retries; i++ {
m.mpu.CCal<- dur
for i := 0; i < retries; i++ {
m.mpu.CCal <- dur
log.Printf("AHRS Info: Waiting for calibration result try %d of %d\n", i, retries)
err = <-m.mpu.CCalResult
if err == nil {
log.Println("AHRS Info: MPU9250 calibrated")
break
}
time.Sleep(time.Duration(50) * time.Millisecond)
log.Println("AHRS Info: MPU9250 wasn't inertial, retrying calibration")
}
return
}
// Close stops reading the MPU.
func (m *MPU9250) Close() {
if m.quit != nil {
m.quit <- struct{}{}

Wyświetl plik

@ -0,0 +1,10 @@
// Package sensors provides a stratux interface to sensors used for AHRS calculations.
package sensors
// PressureReader provides an interface to a sensor reading pressure and maybe
// temperature or humidity, like the BMP180 or BMP280.
type PressureReader interface {
Temperature() (temp float64, tempError error) // Temperature returns the temperature in degrees C.
Pressure() (press float64, pressError error) // Pressure returns the atmospheric pressure in mBar.
Close() // Close stops reading from the sensor.
}

Wyświetl plik

@ -70,7 +70,7 @@ func icao2reg(icao_addr uint32) (string, bool) {
} else if (icao_addr >= 0xC00001) && (icao_addr <= 0xC3FFFF) {
nation = "CA"
} else {
// future national decoding is TO-DO
//TODO: future national decoding.
return "NON-NA", false
}

Wyświetl plik

@ -9,69 +9,80 @@ import urllib2
import json
import time
font2 = ImageFont.truetype('/root/stratux/test/screen/CnC_Red_Alert.ttf', 12)
oled = ssd1306(port=1, address=0x3C)
from daemon import runner
with canvas(oled) as draw:
logo = Image.open('/root/stratux/test/screen/logo.bmp')
draw.bitmap((32, 0), logo, fill=1)
class StratuxScreen():
def __init__(self):
self.stdin_path = '/dev/null'
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)
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
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()

Wyświetl plik

Przed

Szerokość:  |  Wysokość:  |  Rozmiar: 642 B

Po

Szerokość:  |  Wysokość:  |  Rozmiar: 642 B

Wyświetl plik

@ -1,38 +0,0 @@
package main
import (
"../mpu"
"fmt"
"net"
"time"
)
var attSensor mpu.MPU
func readMPU6050() (float64, float64) {
pitch, _ := attSensor.Pitch()
roll, _ := attSensor.Roll()
return pitch, roll
}
func initMPU6050() {
attSensor = mpu.NewMPU6050()
}
func main() {
initMPU6050()
addr, err := net.ResolveUDPAddr("udp", "192.168.1.255:49002")
if err != nil {
panic(err)
}
outConn, err := net.DialUDP("udp", nil, addr)
for {
pitch, roll := readMPU6050()
heading, _ := attSensor.Heading()
s := fmt.Sprintf("XATTMy Sim,%f,%f,%f", heading, pitch, roll)
fmt.Printf("%f, %f\n", pitch, roll)
outConn.Write([]byte(s))
time.Sleep(50 * time.Millisecond)
}
}

147
uatparse/nexrad.go 100644
Wyświetl plik

@ -0,0 +1,147 @@
package uatparse
import ()
const (
BLOCK_WIDTH = float64(48.0 / 60.0)
WIDE_BLOCK_WIDTH = float64(96.0 / 60.0)
BLOCK_HEIGHT = float64(4.0 / 60.0)
BLOCK_THRESHOLD = 405000
BLOCKS_PER_RING = 450
)
type NEXRADBlock struct {
Radar_Type uint32
Scale int
LatNorth float64
LonWest float64
Height float64
Width float64
Intensity []uint16 // Really only 4-bit values, but using this as a hack for the JSON encoding.
}
func block_location(block_num int, ns_flag bool, scale_factor int) (float64, float64, float64, float64) {
var realScale float64
if scale_factor == 1 {
realScale = float64(5.0)
} else if scale_factor == 2 {
realScale = float64(9.0)
} else {
realScale = float64(1.0)
}
if block_num >= BLOCK_THRESHOLD {
block_num = block_num & ^1
}
raw_lat := float64(BLOCK_HEIGHT * float64(int(float64(block_num)/float64(BLOCKS_PER_RING))))
raw_lon := float64(block_num%BLOCKS_PER_RING) * BLOCK_WIDTH
var lonSize float64
if block_num >= BLOCK_THRESHOLD {
lonSize = WIDE_BLOCK_WIDTH * realScale
} else {
lonSize = BLOCK_WIDTH * realScale
}
latSize := BLOCK_HEIGHT * realScale
if ns_flag { // Southern hemisphere.
raw_lat = 0 - raw_lat
} else {
raw_lat = raw_lat + BLOCK_HEIGHT
}
if raw_lon > 180.0 {
raw_lon = raw_lon - 360.0
}
return raw_lat, raw_lon, latSize, lonSize
}
func (f *UATFrame) decodeNexradFrame() {
if len(f.FISB_data) < 4 { // Short read.
return
}
rle_flag := (uint32(f.FISB_data[0]) & 0x80) != 0
ns_flag := (uint32(f.FISB_data[0]) & 0x40) != 0
block_num := ((int(f.FISB_data[0]) & 0x0f) << 16) | (int(f.FISB_data[1]) << 8) | (int(f.FISB_data[2]))
scale_factor := (int(f.FISB_data[0]) & 0x30) >> 4
if rle_flag { // Single bin, RLE encoded.
lat, lon, h, w := block_location(block_num, ns_flag, scale_factor)
var tmp NEXRADBlock
tmp.Radar_Type = f.Product_id
tmp.Scale = scale_factor
tmp.LatNorth = lat
tmp.LonWest = lon
tmp.Height = h
tmp.Width = w
tmp.Intensity = make([]uint16, 0)
intensityData := f.FISB_data[3:]
for _, v := range intensityData {
intensity := uint16(v) & 0x7
runlength := (uint16(v) >> 3) + 1
for runlength > 0 {
tmp.Intensity = append(tmp.Intensity, intensity)
runlength--
}
}
f.NEXRAD = []NEXRADBlock{tmp}
} else {
var row_start int
var row_size int
if block_num >= 405000 {
row_start = block_num - ((block_num - 405000) % 225)
row_size = 225
} else {
row_start = block_num - (block_num % 450)
row_size = 450
}
row_offset := block_num - row_start
L := int(f.FISB_data[3] & 15)
if len(f.FISB_data) < L+3 { // Short read.
return
}
for i := 0; i < L; i++ {
var bb int
if i == 0 {
bb = (int(f.FISB_data[3]) & 0xF0) | 0x08
} else {
bb = int(f.FISB_data[i+3])
}
for j := 0; j < 8; j++ {
if bb&(1<<uint(j)) != 0 {
row_x := (row_offset + 8*i + j - 3) % row_size
bn := row_start + row_x
lat, lon, h, w := block_location(bn, ns_flag, scale_factor)
var tmp NEXRADBlock
tmp.Radar_Type = f.Product_id
tmp.Scale = scale_factor
tmp.LatNorth = lat
tmp.LonWest = lon
tmp.Height = h
tmp.Width = w
tmp.Intensity = make([]uint16, 0)
for k := 0; k < 128; k++ {
z := uint16(0)
if f.Product_id == 64 {
z = 1
}
tmp.Intensity = append(tmp.Intensity, z)
}
f.NEXRAD = append(f.NEXRAD, tmp)
}
}
}
}
}

Wyświetl plik

@ -61,6 +61,9 @@ type UATFrame struct {
RecordFormat uint8
ReportStart string
ReportEnd string
// For NEXRAD.
NEXRAD []NEXRADBlock
}
type UATMsg struct {
@ -500,6 +503,9 @@ func (f *UATFrame) decodeInfoFrame() {
case 8, 11, 13:
f.decodeAirmet()
*/
case 63, 64:
f.decodeNexradFrame()
default:
fmt.Fprintf(ioutil.Discard, "don't know what to do with product id: %d\n", f.Product_id)
}

Wyświetl plik

@ -1,5 +1,6 @@
ifeq ($(statuxBuild),)
stratuxBuild=`git log -n 1 --pretty=%H`
buildtime=`date +%s`
endif
all:
@ -34,4 +35,5 @@ all:
cp index.html /var/www
cp stratux.appcache /var/www
# Mark the manifest with the git hash.
echo "# build time: " ${buildtime} >>/var/www/stratux.appcache
echo "# Stratux build: " ${stratuxBuild} >>/var/www/stratux.appcache

49
web/css/main.css 100755 → 100644
Wyświetl plik

@ -5,22 +5,22 @@
.modal {
}
.vertical-alignment-helper {
display:table;
height: 100%;
width: 75%;
display:table;
height: 100%;
width: 75%;
}
.vertical-align-center {
/* To center vertically */
display: table-cell;
vertical-align: middle;
/* To center vertically */
display: table-cell;
vertical-align: middle;
}
.modal-content {
/* Bootstrap sets the size of the modal in the modal-dialog class, we need to inherit it */
width:inherit;
height:inherit;
/* To center horizontally */
margin: 0 auto;
/* Bootstrap sets the size of the modal in the modal-dialog class, we need to inherit it */
width:inherit;
height:inherit;
/* To center horizontally */
margin: 0 auto;
}
.traffic-page {}
@ -131,22 +131,44 @@
content: "\f1d9";
}
.report_TAF {
border-radius: 5px;
background-color: cornsilk;
color: black;
}
.report_PIREP {
border-radius: 5px;
background-color: gainsboro;
color: black;
}
.report_WINDS {
border-radius: 5px;
background-color: lavender;
color: black;
}
.flight_condition_VFR {
border-radius: 5px;
background-color: forestgreen;
color: white;
}
.flight_condition_MVFR {
border-radius: 5px;
background-color: blue;
color: white;
}
.flight_condition_IFR {
border-radius: 5px;
background-color: crimson;
color: white;
}
.flight_condition_LIFR {
border-radius: 5px;
background-color: darkorchid;
color: white;
}
@ -237,7 +259,7 @@
/* ***************************************************************************
everything below this comment represents tweeks to the mobile-angular-uis CSS
everything below this comment represents tweaks to the mobile-angular-uis CSS
*************************************************************************** */
@font-face {
@ -396,6 +418,9 @@ pre {
border-radius: 0px;
}
body {
font-weight: 400;
}
/* change right sidebar behavior to always push */

Wyświetl plik

@ -64,6 +64,7 @@
<script src="js/j3di-all.min.js"></script>
<script src="plates/js/ahrs.js"></script>
<script src="plates/js/gps.js"></script>
<script src="plates/js/developer.js"></script>
</head>
<body ng-app="stratux" ng-controller="MainCtrl" ui-prevent-touchmove-defaults>
@ -83,6 +84,9 @@
<a class="list-group-item" href="#/towers"><i class="fa fa-signal"></i> Towers <i class="fa fa-chevron-right pull-right"></i></a>
<a class="list-group-item" href="#/logs"><i class="fa fa-file-text-o"></i> Logs <i class="fa fa-chevron-right pull-right"></i></a>
<a class="list-group-item" href="#/settings"><i class="fa fa-gear"></i> Settings <i class="fa fa-chevron-right pull-right"></i></a>
<div ng-show="DeveloperMode">
<a class="list-group-item" href="#/developer"><i class="fa fa-tasks"></i> Developer <i class="fa fa-chevron-right pull-right"></i></a>
</div>
</div>
</div>
</div>

18
web/js/main.js 100755 → 100644
Wyświetl plik

@ -9,9 +9,12 @@ var URL_SATELLITES_GET = "http://" + URL_HOST_BASE + "/getSatellites"
var URL_STATUS_WS = "ws://" + URL_HOST_BASE + "/status"
var URL_TRAFFIC_WS = "ws://" + URL_HOST_BASE + "/traffic";
var URL_WEATHER_WS = "ws://" + URL_HOST_BASE + "/weather";
var URL_DEVELOPER_GET = "ws://" + URL_HOST_BASE + "/developer";
var URL_UPDATE_UPLOAD = "http://" + URL_HOST_BASE + "/updateUpload";
var URL_REBOOT = "http://" + URL_HOST_BASE + "/reboot";
var URL_SHUTDOWN = "http://" + URL_HOST_BASE + "/shutdown";
var URL_RESTARTAPP = "http://" + URL_HOST_BASE + "/restart";
var URL_DEV_TOGGLE_GET = "http://" + URL_HOST_BASE + "/develmodetoggle";
// define the module with dependency on mobile-angular-ui
//var app = angular.module('stratux', ['ngRoute', 'mobile-angular-ui', 'mobile-angular-ui.gestures', 'appControllers']);
@ -62,6 +65,12 @@ app.config(function ($stateProvider, $urlRouterProvider) {
templateUrl: 'plates/settings.html',
controller: 'SettingsCtrl',
reloadOnSearch: false
})
.state('developer', {
url: '/developer',
templateUrl: 'plates/developer.html',
controller: 'DeveloperCtrl',
reloadOnSearch: false
});
$urlRouterProvider.otherwise('/');
});
@ -72,6 +81,13 @@ app.run(function ($transform) {
});
// For this app we have a MainController for whatever and individual controllers for each page
app.controller('MainCtrl', function ($rootScope, $scope) {
app.controller('MainCtrl', function ($scope, $http) {
// any logic global logic
$http.get(URL_SETTINGS_GET)
.then(function(response) {
settings = angular.fromJson(response.data);
$scope.DeveloperMode = settings.DeveloperMode;
}, function(response) {
//Second function handles error
});
});

Wyświetl plik

@ -6373,50 +6373,62 @@ a.label:focus {
.label-default {
background-color: #777777;
border-radius: 5px;
}
.label-default[href]:focus {
background-color: #5e5e5e;
border-radius: 5px;
}
.label-primary {
background-color: #007aff;
border-radius: 5px;
}
.label-primary[href]:focus {
background-color: #0062cc;
border-radius: 5px;
}
.label-success {
background-color: #4cd964;
border-radius: 5px;
}
.label-success[href]:focus {
background-color: #2ac845;
border-radius: 5px;
}
.label-info {
background-color: #34aadc;
border-radius: 5px;
}
.label-info[href]:focus {
background-color: #218ebd;
border-radius: 5px;
}
.label-warning {
background-color: #ffcc00;
border-radius: 5px;
}
.label-warning[href]:focus {
background-color: #cca300;
border-radius: 5px;
}
.label-danger {
background-color: #ff3b30;
border-radius: 5px;
}
.label-danger[href]:focus {
background-color: #fc0d00;
border-radius: 5px;
}
.badge {

Wyświetl plik

@ -100,6 +100,10 @@ a.bg-danger:hover {
text-decoration: none;
}
.btn-hidden:hover {
color: #000000;
}
.btn-default:hover {
color: #333333;
background-color: #e6e6e6;

Wyświetl plik

@ -0,0 +1,4 @@
<div class="section text-left help-page">
<p>The <strong>Developer</strong> page provides basic access to developer options</p>
<p></p>
</div>

Wyświetl plik

@ -0,0 +1,21 @@
<div class="col-sm-12">
<div class="panel panel-default">
<div class="panel-heading">
<span class="panel_label">Developer Mode Items</span>
</div>
<div class="panel-body">
<div class="panel-group col-sm-6">
<div class="panel panel-default">
<div class="panel-heading">Restart Stratux application</div>
<div class="panel-body">
<div class="form-group reset-flow">
<div class="col-xs-12">
<a ng-click="postRestart()" ui-turn-off="modalRestartApp" class="btn btn-primary">Restart Application</a>
</div>
</div>
</div>
</div>
</div>
</div>
</div>
</div>

Wyświetl plik

@ -0,0 +1,18 @@
angular.module('appControllers').controller('DeveloperCtrl', DeveloperCtrl); // get the main module contollers set
DeveloperCtrl.$inject = ['$rootScope', '$scope', '$state', '$http', '$interval']; // Inject my dependencies
// create our controller function with all necessary logic
function DeveloperCtrl($rootScope, $scope, $state, $http, $interval) {
$scope.$parent.helppage = 'plates/developer-help.html';
$scope.postRestart = function () {
$http.post(URL_RESTARTAPP).
then(function (response) {
// do nothing
// $scope.$apply();
}, function (response) {
// do nothing
});
};
};

Wyświetl plik

@ -6,7 +6,7 @@ function SettingsCtrl($rootScope, $scope, $state, $location, $window, $http) {
$scope.$parent.helppage = 'plates/settings-help.html';
var toggles = ['UAT_Enabled', 'ES_Enabled', 'Ping_Enabled', 'GPS_Enabled', 'AHRS_Enabled', 'DisplayTrafficSource', 'DEBUG', 'ReplayLog'];
var toggles = ['UAT_Enabled', 'ES_Enabled', 'Ping_Enabled', 'GPS_Enabled', 'DisplayTrafficSource', 'DEBUG', 'ReplayLog'];
var settings = {};
for (i = 0; i < toggles.length; i++) {
settings[toggles[i]] = undefined;
@ -17,17 +17,22 @@ 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;
$scope.Ping_Enabled = settings.Ping_Enabled;
$scope.GPS_Enabled = settings.GPS_Enabled;
$scope.AHRS_Enabled = settings.AHRS_Enabled;
$scope.DisplayTrafficSource = settings.DisplayTrafficSource;
$scope.DEBUG = settings.DEBUG;
$scope.ReplayLog = settings.ReplayLog;
$scope.PPM = settings.PPM;
$scope.WatchList = settings.WatchList;
$scope.OwnshipModeS = settings.OwnshipModeS;
$scope.DeveloperMode = settings.DeveloperMode;
}
function getSettings() {
@ -91,6 +96,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 +197,4 @@ function SettingsCtrl($rootScope, $scope, $state, $location, $window, $http) {
});
};
};
};

45
web/plates/js/status.js 100755 → 100644
Wyświetl plik

@ -54,9 +54,14 @@ function StatusCtrl($rootScope, $scope, $state, $http, $interval) {
$scope.GPS_satellites_tracked = status.GPS_satellites_tracked;
$scope.GPS_satellites_seen = status.GPS_satellites_seen;
$scope.GPS_solution = status.GPS_solution;
$scope.GPS_position_accuracy = String(status.GPS_solution ? ", " + status.GPS_position_accuracy.toFixed(1) : "");
$scope.RY835AI_connected = status.RY835AI_connected;
$scope.GPS_position_accuracy = String(status.GPS_solution ? ", " + status.GPS_position_accuracy.toFixed(1) + " m" : " ");
$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;
@ -95,6 +100,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;
@ -103,7 +109,6 @@ function StatusCtrl($rootScope, $scope, $state, $http, $interval) {
$scope.visible_es = true;
}
$scope.visible_gps = settings.GPS_Enabled;
$scope.visible_ahrs = settings.AHRS_Enabled;
}, function (response) {
// nop
});
@ -133,7 +138,16 @@ function StatusCtrl($rootScope, $scope, $state, $http, $interval) {
getTowers();
}, (5 * 1000), 0, false);
var clicks = 0;
var clickSeconds = 0;
var DeveloperModeClick = 0;
var clickInterval = $interval(function () {
if ((clickSeconds >= 3))
clicks=0;
clickSeconds++;
}, 1000);
$state.get('home').onEnter = function () {
// everything gets handled correctly by the controller
};
@ -144,7 +158,26 @@ function StatusCtrl($rootScope, $scope, $state, $http, $interval) {
}
$interval.cancel(updateTowers);
};
$scope.VersionClick = function() {
if (clicks==0)
{
clickSeconds = 0;
}
++clicks;
if ((clicks > 7) && (clickSeconds < 3))
{
clicks=0;
clickSeconds=0;
DeveloperModeClick = 1;
$http.get(URL_DEV_TOGGLE_GET);
location.reload();
}
}
$scope.GetDeveloperModeClick = function() {
return DeveloperModeClick;
}
// Status Controller tasks
setHardwareVisibility();
connect($scope); // connect - opens a socket and listens for messages

12
web/plates/js/weather.js 100755 → 100644
Wyświetl plik

@ -140,7 +140,17 @@ function WeatherCtrl($rootScope, $scope, $state, $http, $interval) {
var dNow = new Date();
var dThen = parseShortDatetime(obj.Time);
data_item.age = dThen.getTime();
data_item.time = deltaTimeString(dNow - dThen) + " old";
var diff_ms = Math.abs(dThen - dNow);
// If time is more than two days away, don't attempt to display data age.
if (diff_ms > (1000*60*60*24*2)) {
data_item.time = "?";
} else if (dThen > dNow) {
data_item.time = deltaTimeString(dThen - dNow) + " from now";
} else {
data_item.time = deltaTimeString(dNow - dThen) + " old";
}
// data_item.received = utcTimeString(obj.LocaltimeReceived);
data_item.data = obj.Data;
}

Wyświetl plik

@ -28,12 +28,6 @@
<ui-switch ng-model='GPS_Enabled' settings-change></ui-switch>
</div>
</div>
<div class="form-group">
<label class="control-label col-xs-7">AHRS</label>
<div class="col-xs-5">
<ui-switch ng-model='AHRS_Enabled' settings-change></ui-switch>
</div>
</div>
</div>
</div>
</div>
@ -92,6 +86,13 @@
<input class="col-xs-7" type="number_format" required ng-model="PPM" placeholder="integer" ng-blur="updateppm()" />
</form>
</div>
<div class="form-group reset-flow" ng-class="{ 'section_invisible': (!visible_serialout)}">
<label class="control-label col-xs-5">Serial Output Baudrate</label>
<form name="ppmForm" ng-submit="updateBaud()" novalidate>
<!-- type="number" not supported except on mobile -->
<input class="col-xs-7" type="number_format" required ng-model="Baud" placeholder="integer" ng-blur="updateBaud()" />
</form>
</div>
</div>
</div>
</div>
@ -127,6 +128,19 @@
</div>
</div>
<!-- Developer mode area -->
<div class="col-sm-12">
<div ng-show="DeveloperMode" class="panel-group col-sm-6">
<div class="panel panel-default">
<div class="panel-heading">Developer Options</div>
<div class="panel-body">
<div class="col-xs-12">
<p>Coming soon</p>
</div>
</div>
</div>
</div>
</div>
<!--
@ -194,6 +208,5 @@
</div>
</div>
</div>
</div>

Wyświetl plik

@ -6,7 +6,6 @@
<ul class="list-simple">
<li><strong>Messages</strong> is the number of messages received by the UAT (978 MHz) and 1090 MHz radios. "Current" is the 60-second rolling total for each receiver; "Peak" is the maximum 60-second total. The 1090 total includes all 1090 MHz Mode S messages received, including all-call and TCAS interrogations that do not carry ADS-B position information. If a UAT radio is receiving uplinks from one or more ground-based transceivers (GBT), this will be indicated under <strong>UAT Towers</strong>, with more details available on the Towers page.</li>
<li><strong>GPS</strong> indicates the connection status of any attached GPS receivers. Reported data includes the type of position solution, the number of satellites used in that solution, the number of satellites being received, and the number of satellites tracked in the GPS almanac data. Position and accuracy details can be viewed on the <strong>GPS/AHRS</strong> page.</li>
<li><strong>AHRS</strong> indicates whether the pressure sensor and gyro on an RY835AI or similar 10-axis module are connected and enabled. If connected, attitude and pressure altitude can be viewed on the <strong>GPS/AHRS</strong> page.</li>
</ul>
<p class="text-warning">Devices must be manually enabled on the <strong>Settings</strong> page.</p>

82
web/plates/status.html 100755 → 100644
Wyświetl plik

@ -1,22 +1,13 @@
<div class="col-sm-12">
<div class="text-center">
<p><strong>Version: <span>{{Version}} ({{Build}})</span></strong></p>
</div>
<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" ng-class="{'section_invisible': !visible_errors}">
<span class="panel_label">Errors</span>
</div>
<div class="panel-body" ng-class="{'section_invisible': !visible_errors}">
<ul>
<li class="status-error" ng-repeat="err in Errors">
<span class="fa fa-exclamation-triangle icon-red"></span> <span class="icon-red">{{err}}</span>
</li>
</ul>
</div>
<div class="panel-heading">
<span class="panel_label">Status</span>
<span ng-show="ConnectState == 'Connected'" class="label label-success">{{ConnectState}}</span>
<span ng-hide="ConnectState == 'Connected'" class="label label-danger">{{ConnectState}}</span>
<span ng-show="DeveloperMode == true" class="label label-warning">Developer Mode</span>
</div>
<div class="panel-body">
<div class="form-horizontal">
@ -81,15 +72,48 @@
<label class="col-xs-6">GPS satellites:</label>
<span class="col-xs-6">{{GPS_satellites_locked}} in solution; {{GPS_satellites_seen}} seen; {{GPS_satellites_tracked}} tracked</span>
</div>
<div class="row" ng-class="{'section_invisible': !visible_ahrs}">
<label class="col-xs-6">AHRS:</label>
<div id="RY835AI_connected-container" class="col-xs-6">
<div ng-class="RY835AI_connected ? 'fa fa-check-circle text-success' : 'fa fa-times-circle text-danger'"></div>
</div>
</div>
<div class="row"><span class="col-xs-1">&nbsp;</span></div>
<div class="separator"></div>
<div class="row" ng-class="{'section_invisible': !visible_uat}">
<div class="col-sm-6">
<span><strong>UAT Statistics</strong></span>
</div>
</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">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" style="background-color: #f7f7f7" class="col-xs-3">PIREP</span>
</div>
</div>
<div class="row" ng-class="{'section_invisible': !visible_uat}">
<div class="col-sm-12">
<span align="center" class="col-xs-3">{{UAT_METAR_total}}</span>
<span align="center" class="col-xs-3">{{UAT_TAF_total}}</span>
<span align="center" class="col-xs-3">{{UAT_NEXRAD_total}}</span>
<span align="center" class="col-xs-3">{{UAT_PIREP_total}}</span>
</div>
</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">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>
</div>
</div>
<div class="row" ng-class="{'section_invisible': !visible_uat}">
<div class="col-sm-12">
<span align="center" class="col-xs-3">{{UAT_SIGMET_total}}</span>
<span align="center" class="col-xs-3">{{UAT_NOTAM_total}}</span>
<span align="center" class="col-xs-3">{{UAT_OTHER_total}}</span>
</div>
</div>
</div>
<div class="row" ng-class="{'section_invisible': !visible_uat}">
<div class="separator"></div>
<div class="row"><span class="col-xs-1">&nbsp;</span></div>
<div class="separator"></div>
<div class="row">
<div class="col-sm-4 label_adj">
<span class="col-xs-5"><strong>Uptime:</strong></span>
@ -101,6 +125,24 @@
</div>
</div>
</div>
</div>
</div>
</div>
<div class="panel panel-default">
<div class="panel-heading" ng-class="{'section_invisible': !visible_errors}">
<span class="panel_label">Errors</span>
</div>
<div class="panel-body" ng-class="{'section_invisible': !visible_errors}">
<ul>
<li class="status-error" ng-repeat="err in Errors">
<span class="fa fa-exclamation-triangle icon-red"></span> <span class="icon-red">{{err}}</span>
</li>
</ul>
</div>
</div>
</div>

14
web/plates/weather.html 100755 → 100644
Wyświetl plik

@ -29,8 +29,11 @@
<div class="separator"></div>
<div class="col-sm-12">
<span class="col-xs-3"><strong>{{weather.location}}</strong></span>
<span ng-class="weather.flight_condition ? 'col-xs-3 label label-success flight_condition_{{weather.flight_condition}}' : 'col-xs-3'">{{weather.type}}</span>
<span class="col-xs-6 text-right">{{weather.time}}</span>
<span class="col-xs-3" align="center">
<div align="center" ng-class="weather.flight_condition ? ' label label-success flight_condition_{{weather.flight_condition}}' : 'label label-success report_{{weather.type}}'">{{weather.type}}</div>
</span>
<span class="col-xs-4">&nbsp;</span>
<span class="col-xs-2 text-right" style="background-color: {{weather.backcolor}}">{{weather.time}}</span>
</div>
<div class="col-sm-12">
<span class="col-xs-10">{{weather.data}}</span>
@ -62,8 +65,11 @@
<div class="separator"></div>
<div class="col-sm-12">
<span class="col-xs-3"><strong>{{weather.location}}</strong></span>
<span ng-class="weather.flight_condition ? 'col-xs-3 label label-success flight_condition_{{weather.flight_condition}}' : 'col-xs-3'">{{weather.type}}</span>
<span class="col-xs-6 text-right">{{weather.time}}</span>
<span class="col-xs-3" align="center">
<div align="center" ng-class="weather.flight_condition ? ' label label-success flight_condition_{{weather.flight_condition}}' : 'label label-success report_{{weather.type}}'">{{weather.type}}</div>
</span>
<span class="col-xs-4">&nbsp;</span>
<span class="col-xs-2 text-right" style="background-color: {{weather.backcolor}}">{{weather.time}}</span>
</div>
<div class="col-sm-12">
<span class="col-xs-10">{{weather.data}}</span>