Merge pull request #1 from cyoung/master

Update fork
pull/444/head
Eric Gideon 2016-06-21 08:56:35 -07:00 zatwierdzone przez GitHub
commit 50027d416c
54 zmienionych plików z 15590 dodań i 663 usunięć

Wyświetl plik

@ -14,7 +14,7 @@ all:
xgen_gdl90:
go get -t -d -v ./main ./test ./linux-mpu9150/mpu ./godump978 ./mpu6050 ./uatparse
go build $(BUILDINFO) main/gen_gdl90.go main/traffic.go main/ry835ai.go main/network.go main/managementinterface.go main/sdr.go main/uibroadcast.go main/monotonic.go
go build $(BUILDINFO) -p 4 main/gen_gdl90.go main/traffic.go main/ry835ai.go main/network.go main/managementinterface.go main/sdr.go main/uibroadcast.go main/monotonic.go main/datalog.go main/equations.go
xdump1090:
git submodule update --init
@ -39,6 +39,7 @@ install:
cp -f gen_gdl90 /usr/bin/gen_gdl90
chmod 755 /usr/bin/gen_gdl90
cp init.d-stratux /etc/init.d/stratux
cp image/10-stratux.rules /etc/udev/rules.d/10-stratux.rules
chmod 755 /etc/init.d/stratux
ln -sf /etc/init.d/stratux /etc/rc2.d/S01stratux
ln -sf /etc/init.d/stratux /etc/rc6.d/K01stratux

Wyświetl plik

@ -1,6 +1,8 @@
[![stratux version](https://img.shields.io/github/tag/cyoung/stratux.svg?style=flat&label=stratux)](https://github.com/cyoung/stratux/releases)
[![Build Status](http://circleci-badges-max.herokuapp.com/img/cyoung/stratux/master?token=:circle-ci-token)](https://circleci.com/gh/cyoung/stratux/tree/master)
[![BSD3 License](http://img.shields.io/badge/license-BSD3-brightgreen.svg)](https://tldrlegal.com/license/bsd-3-clause-license-%28revised%29)
[![Stratux Slack](http://slack.stratux.me:3000/badge.svg)](http://slack.stratux.me/)
# stratux
RTL-SDR UAT tools

Wyświetl plik

@ -7,7 +7,7 @@ dependencies:
pre:
- sudo apt-get update; sudo apt-get install libusb-1.0-0-dev; cd ~/; git clone https://github.com/jpoirier/librtlsdr; cd librtlsdr; mkdir build; cd build; cmake ../; make; sudo make install; sudo ldconfig; cd ~/; mkdir gopath; cd ~/; mkdir gopath; wget https://storage.googleapis.com/golang/go1.6.src.tar.gz; tar -zxvf go1.6.src.tar.gz; cd go/src; export GOROOT_BOOTSTRAP=/usr/local/go; ./make.bash; echo $PATH; echo $GOPATH; go version; env
override:
- cd .. ; rm -rf stratux ; git clone --recursive https://github.com/cyoung/stratux ; cd stratux ; git fetch origin ; git checkout $CIRCLE_BRANCH ; make
- cd .. ; rm -rf stratux ; git clone --recursive https://github.com/cyoung/stratux ; cd stratux ; git config --add remote.origin.fetch "+refs/pull/*/head:refs/remotes/origin/pr/*" ; git fetch origin ; BRANCH=`echo "$CIRCLE_BRANCH" | sed 's/pull\//pr\//g'` ; git checkout $BRANCH ; make
test:
override:

Wyświetl plik

@ -0,0 +1,23 @@
# To be placed in /etc/udev/rules.d.
# Auto-detect common USB stratux peripherals.
# u-blox devices. Known devices include
# ublox8: RY835AI, RY836AI
# ublox7: VK-172, RY725AI
# ublox6: VK-162
SUBSYSTEMS=="usb", ATTRS{idVendor}=="1546", ATTRS{idProduct}=="01a8", SYMLINK+="ublox8"
SUBSYSTEMS=="usb", ATTRS{idVendor}=="1546", ATTRS{idProduct}=="01a7", SYMLINK+="ublox7"
SUBSYSTEMS=="usb", ATTRS{idVendor}=="1546", ATTRS{idProduct}=="01a6", SYMLINK+="ublox6"
#SUBSYSTEMS=="usb", ATTRS{idVendor}=="1546", ATTRS{idProduct}=="01a7", SYMLINK+="vk172"
#SUBSYSTEMS=="usb", ATTRS{idVendor}=="1546", ATTRS{idProduct}=="01a6", SYMLINK+="vk162"
# pl2303 devices are indistinguishable using idVendor and idProduct.
# Currently the BU-353-S4 and the TU-S9 (serialout) use the pl2303.
SUBSYSTEMS=="usb", ATTRS{idVendor}=="067b", ATTRS{idProduct}=="2303", SYMLINK+="prolific%n"
#SUBSYSTEMS=="usb", ATTRS{idVendor}=="067b", ATTRS{idProduct}=="2303", SYMLINK+="bu353s4"
#SUBSYSTEMS=="usb", ATTRS{idVendor}=="067b", ATTRS{idProduct}=="2303", SYMLINK+="tu-s9"

Wyświetl plik

@ -19,3 +19,13 @@
export PATH=/root/go/bin:${PATH}
export GOROOT=/root/go
export GOPATH=/root/go_path
# This will allow users to keep an alias file after this file is added
if [ -f /root/.aliases ]; then
. /root/.aliases
fi
# Uesful aliases for stratux debugging
if [ -f /root/.stxAliases ]; then
. /root/.stxAliases
fi

Wyświetl plik

@ -5,3 +5,6 @@ max_usb_current=1
dtparam=i2c1=on
dtparam=i2c1_baudrate=400000
dtparam=i2c_arm_baudrate=400000
# move RPi3 Bluetooth off of hardware UART to free up connection for GPS
dtoverlay=pi3-miniuart-bt

Wyświetl plik

@ -0,0 +1,263 @@
#!/bin/bash
######################################################################
# STRATUX HOSTAPD MANAGER #
######################################################################
#Set Script Name variable
SCRIPT=`basename ${BASH_SOURCE[0]}`
#Initialize variables to default values.
OPT_S=false
OPT_C=false
OPT_E=false
OPT_O=false
defaultPass="Squawk1200"
parm="*"
err="####"
att="+++"
#Set fonts for Help.
BOLD=$(tput bold)
STOT=$(tput smso)
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)
#Help function
function HELP {
echo -e \\n"Help documentation for ${BOLD}${SCRIPT}.${NORM}"\\n
echo -e "${REV}Basic usage:${NORM} ${BOLD}$SCRIPT -s ssid -c chan -e pass ${NORM}"\\n
echo "Command line switches are optional. The following switches are recognized."
echo "${REV}-s${NORM} --Sets the SSID to ${BOLD}ssid${NORM}. \"-s stratux\""
echo "${REV}-c${NORM} --Sets the channel to ${BOLD}chan${NORM}. \"-c 1\""
echo "${REV}-e${NORM} --Turns on encryption with passphrase ${BOLD}pass${NORM}. 8-63 Printable Characters(ascii 32-126). Cannot be used with -o. \"-e password!\""
echo "${REV}-o${NORM} --Turns off encryption and sets network to open. Cannot be used with -e."
# echo "${REV}-q${NORM} --Run silently."
echo -e "${REV}-h${NORM} --Displays this help message. No further functions are performed."\\n
echo -e "Example: ${BOLD}$SCRIPT -s stratux -c 1 -e N3558D${NORM}"\\n
exit 1
}
clear
echo ""
echo "#### Stratux HOSTAPD Settings ####"
echo ""
if [ $(whoami) != 'root' ]; then
echo "${BOLD}${RED}This script must be executed as root, exiting...${WHITE}${NORMAL}"
echo "${BOLD}${RED}USAGE${WHITE}${NORMAL}"
exit 1
fi
#Check the number of arguments. If none are passed, print help and exit.
NUMARGS=$#
if [ $NUMARGS -eq 0 ]; then
HELP
fi
### Start getopts code ###
#Parse command line flags
#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'
while getopts $options option; do
case $option in
s) #set option "s"
if [[ -z "${OPTARG}" || "${OPTARG}" == *[[:space:]]* || "${OPTARG}" == -* ]]; then
echo "${BOLD}${RED}$err No SSID for -s, exiting...${WHITE}${NORMAL}"
exit 1
else
OPT_S=$OPTARG
echo "$parm SSID Option -s used: $OPT_S"
echo "${GREEN} SSID will now be ${BOLD}${UNDR}$OPT_S${NORMAL}.${WHITE}"
fi
;;
c) #set option "c"
if [[ -z "${OPTARG}" || "${OPTARG}" == *[[:space:]]* || "${OPTARG}" == -* ]]; then
echo "${BOLD}${RED}$err Channel option(-c) used without value, exiting... ${WHITE}${NORMAL}"
exit 1
else
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}"
else
echo "${BOLD}${RED}$err Channel is not within acceptable values, exiting...${WHITE}${NORMAL}"
exit 1
fi
fi
;;
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
else
OPT_E=$OPTARG
echo "$parm Encryption option -e used:"
if [ -z `echo $OPT_E | tr -d "[:print:]"` ] && [ ${#OPT_E} -ge 8 ] && [ ${#OPT_E} -le 63 ]; then
echo "${GREEN} Passphrase will now be ${BOLD}${UNDR}$OPT_E${NORMAL}.${WHITE}${NORMAL}"
else
echo "${BOLD}${RED}$err Invalid PASSWORD: 8 - 63 printable characters, exiting...${WHITE}${NORMAL}"
exit
fi
fi
;;
o) #set option "o"
if [[ -z "${OPTARG}" || "${OPTARG}" == *[[:space:]]* || "${OPTARG}" == -* ]]; then
echo "$parm Open WiFI Option -o used."
echo "${GREEN} WiFi will be set to ${BOLD}${UNDR}OPEN${NORMAL}${GREEN} or ${BOLD}${UNDR}UNSECURE${WHITE}${NORMAL}"
OPT_O=true
else
echo "${BOLD}${RED}$err Option -o does not require arguement.${WHITE}${NORMAL}"
exit 1
fi
;;
h) #show help
HELP
;;
\?) # invalid option
echo "${BOLD}${RED}$err Invalid option -$OPTARG" >&2
exit 1
;;
:) # Missing Arg
echo "${BOLD}${RED}$err Missing option for argument -$OPTARG ${WHITE}${NORMAL}" >&2
exit 1
;;
*) # Invalid
echo "${BOLD}${RED}$err Unimplemented option -$OPTARG ${WHITE}${NORMAL}" >&2
exit 1
;;
esac
done
shift $((OPTIND-1)) #This tells getopts to move on to the next argument.
### End getopts code ###
### Main loop to process files ###
#This is where your main file processing will take place. This example is just
#printing the files and extensions to the terminal. You should place any other
#file processing tasks within the while-do loop.
if [ $OPT_O = true ] && [ $OPT_E != false ]; then
echo "${BOLD}${RED}$err Option -e and -o cannot be used simultaneously ${WHITE}${NORMAL}"
exit 1
fi
echo ""
echo "${BOLD}No errors found. Continuning...${NORMAL}"
echo ""
# files to edit
HOSTAPD=('/etc/hostapd/hostapd.conf' '/etc/hostapd/hostapd-edimax.conf')
####
#### File modification loop
####
for i in "${HOSTAPD[@]}"
do
if [ -f ${i} ]; then
echo "Working on $i..."
if [ $OPT_S != false ]; then
echo "${MAGENTA}Setting ${YELLOW}SSID${MAGENTA} to ${YELLOW}$OPT_S ${MAGENTA}in $i...${WHITE}"
if grep -q "^ssid=" ${HOSTAPD[$x]}; then
sed -i "s/^ssid=.*/ssid=${OPT_S}/" ${i}
else
echo ${OPT_S} >> ${i}
fi
fi
if [ $OPT_C != false ]; then
echo "${MAGENTA}Setting ${YELLOW}Channel${MAGENTA} to ${YELLOW}$OPT_C ${MAGENTA}in $i...${WHITE}"
if grep -q "^channel=" ${i}; then
sed -i "s/^channel=.*/channel=${OPT_C}/" ${i}
else
echo ${OPT_C} >> ${i}
fi
fi
if [ $OPT_E != false ]; then
echo "${MAGENTA}Adding WPA encryption with passphrase: ${YELLOW}$OPT_E ${MAGENTA}to $i...${WHITE}"
if grep -q "^#auth_algs=" ${i}; then
#echo "uncomenting wpa"
sed -i "s/^#auth_algs=.*/auth_algs=1/" ${i}
sed -i "s/^#wpa=.*/wpa=3/" ${i}
sed -i "s/^#wpa_passphrase=.*/wpa_passphrase=$OPT_E/" ${i}
sed -i "s/^#wpa_key_mgmt=.*/wpa_key_mgmt=WPA-PSK/" ${i}
sed -i "s/^#wpa_pairwise=.*/wpa_pairwise=TKIP/" ${i}
sed -i "s/^#rsn_pairwise=.*/rsn_pairwise=CCMP/" ${i}
elif grep -q "^auth_algs=" ${i}; then
#echo "rewriting existing wpa"
sed -i "s/^auth_algs=.*/auth_algs=1/" ${i}
sed -i "s/^wpa=.*/wpa=3/" ${i}
sed -i "s/^wpa_passphrase=.*/wpa_passphrase=$OPT_E/" ${i}
sed -i "s/^wpa_key_mgmt=.*/wpa_key_mgmt=WPA-PSK/" ${i}
sed -i "s/^wpa_pairwise=.*/wpa_pairwise=TKIP/" ${i}
sed -i "s/^rsn_pairwise=.*/rsn_pairwise=CCMP/" ${i}
else
#echo "adding wpa"
echo "" >> ${i}
echo "auth_algs=1" >> ${i}
echo "wpa=3" >> ${i}
echo "wpa_passphrase=$OPT_E" >> ${i}
echo "wpa_key_mgmt=WPA-PSK" >> ${i}
echo "wpa_pairwise=TKIP" >> ${i}
echo "rsn_pairwise=CCMP" >> ${i}
fi
fi
if [ $OPT_O != false ]; then
echo "${MAGENTA}Removing WPA encryption in $i...${WHITE}"
if grep -q "^auth_algs=" ${i}; then
#echo "comenting out wpa"
sed -i "s/^auth_algs=.*/#auth_algs=1/" ${i}
sed -i "s/^wpa=.*/#wpa=3/" ${i}
sed -i "s/^wpa_passphrase=.*/#wpa_passphrase=$defaultPass/" ${i}
sed -i "s/^wpa_key_mgmt=.*/#wpa_key_mgmt=WPA-PSK/" ${i}
sed -i "s/^wpa_pairwise=.*/#wpa_pairwise=TKIP/" ${i}
sed -i "s/^rsn_pairwise=.*/#rsn_pairwise=CCMP/" ${i}
elif grep -q "^#auth_algs=" ${i}; then
#echo "rewriting comentied out wpa"
sed -i "s/^#auth_algs=.*/#auth_algs=1/" ${i}
sed -i "s/^#wpa=.*/#wpa=3/" ${i}
sed -i "s/^#wpa_passphrase=.*/#wpa_passphrase=$defaultPass/" ${i}
sed -i "s/^#wpa_key_mgmt=.*/#wpa_key_mgmt=WPA-PSK/" ${i}
sed -i "s/^#wpa_pairwise=.*/#wpa_pairwise=TKIP/" ${i}
sed -i "s/^#rsn_pairwise=.*/#rsn_pairwise=CCMP/" ${i}
else
#echo "adding commented out WPA"
echo "" >> ${i}
echo "#auth_algs=1" >> ${i}
echo "#wpa=3" >> ${i}
echo "#wpa_passphrase=$defaultPass" >> ${i}
echo "#wpa_key_mgmt=WPA-PSK" >> ${i}
echo "#wpa_pairwise=TKIP" >> ${i}
echo "#rsn_pairwise=CCMP" >> ${i}
fi
fi
echo "${GREEN}Modified ${i}...done${WHITE}"
echo ""
else
echo "${MAGENTA}No ${i} file found...${WHITE}${NORMAL}"
echo ""
fi
done
echo "${YELLOW}$att Don't forget to reboot... $att ${WHITE}"
echo ""
echo ""
### End main loop ###
exit 0

Wyświetl plik

@ -16,7 +16,7 @@ iface wlan0 inet static
##
## Second Wifi Dongle for local work and internet access
## wifi mist be open for these settings to work
## wifi must be open for these settings to work
##
## uncomment the next two lines to activate the service as well as modify the settings and comments below
#allow-hotplug wlan1

Wyświetl plik

@ -31,12 +31,18 @@ cp -f root mnt/etc/ssh/authorized_keys/root
chown root.root mnt/etc/ssh/authorized_keys/root
chmod 644 mnt/etc/ssh/authorized_keys/root
#motd
cp -f motd mnt/etc/motd
#dhcpd config
cp -f dhcpd.conf mnt/etc/dhcp/dhcpd.conf
#hostapd config
cp -f hostapd.conf mnt/etc/hostapd/hostapd.conf
cp -f hostapd-edimax.conf mnt/etc/hostapd/hostapd-edimax.conf
#hostapd manager script
cp -f hostapd_manager.sh mnt/usr/sbin/hostapd_manager.sh
chmod 755 mnt/usr/sbin/hostapd_manager.sh
#hostapd
cp -f hostapd-edimax mnt/usr/sbin/hostapd-edimax
chmod 755 mnt/usr/sbin/hostapd-edimax
@ -54,6 +60,9 @@ cp -f isc-dhcp-server mnt/etc/default/isc-dhcp-server
#sshd config
cp -f sshd_config mnt/etc/ssh/sshd_config
#udev config
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
@ -62,6 +71,9 @@ cp -f ../linux-mpu9150/libimu.so mnt/usr/lib/libimu.so
cp -rf /root/go mnt/root/
cp -f bashrc.txt mnt/root/.bashrc
#debug aliases
cp -f stxAliases.txt mnt/root/.stxAliases
#rtl-sdr setup
cp -f rtl-sdr-blacklist.conf mnt/etc/modprobe.d/

18
image/motd 100644
Wyświetl plik

@ -0,0 +1,18 @@
ad88888ba 888888888888 88888888ba db 888888888888 88 88 8b d8
d8" "8b 88 88 "8b d88b 88 88 88 Y8, ,8P
Y8, 88 88 ,8P d8'`8b 88 88 88 `8b d8'
`Y8aaaaa, 88 88aaaaaa8P' d8' `8b 88 88 88 Y88P
`"""""8b, 88 88""""88' d8YaaaaY8b 88 88 88 d88b
`8b 88 88 `8b d8""""""""8b 88 88 88 ,8P Y8,
Y8a a8P 88 88 `8b d8' `8b 88 Y8a. .a8P d8' `8b
"Y88888P" 88 88 `8b d8' `8b 88 `"Y8888Y"' 8P Y8
NOTE TO DEVELOPERS: Make sure that your system has an acceptable clock source, i.e., a GPS
with sufficient signal or enable ntpd (internet connection required).
Everything here comes with ABSOLUTELY NO WARRANTY, to the extent
permitted by applicable law.

Wyświetl plik

@ -11,14 +11,13 @@
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" ] ; then
# This is a RPi2B.
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
fi
if [ "$RPI_REV" = "a02082" ] || [ "$RPI_REV" = "a22082" ]; then
# This is a RPi3B.
else
DAEMON_CONF=/etc/hostapd/hostapd.conf
fi

Wyświetl plik

@ -0,0 +1,56 @@
alias stratux-off='shutdown -P now'
alias eeprom='rtl_eeprom'
alias sa='service --status-all'
alias stxrestart='service stratux restart'
alias stxstop='service stratux stop'
alias stxstart='service stratux start'
alias sdr0='rtl_eeprom -d 0'
alias sdr1='rtl_eeprom -d 1'
alias sdrs='sdr0 || sdr1'
alias d90='dump1090'
alias d900='dump1090 --device-index 0 --interactive'
alias d901='dump1090 --device-index 1 --interactive'
alias kal0='kal -d 0 -s GSM850 -g 47'
alias kal1='kal -d 1 -s GSM850 -g 47'
alias kalChan0='function _kalChan0 () { kal -d 0 -g 47 -c $1; unset -f _kalChan0; }; _kalChan0'
alias kalChan1='function _kalChan1 () { kal -d 1 -g 47 -c $1; unset -f _kalChan1; }; _kalChan1'
alias setSerial0='function _setSerial0 () { rtl_eeprom -d 0 -s stx:0:$1; unset -f _setSerial0; }; _setSerial0'
alias setSerial1='function _setSerial0 () { rtl_eeprom -d 1 -s stx:0:$1; unset -f _setSerial1; }; _setSerial1'
alias stratux-help='_stxhelp'
function _stxhelp() {
echo ""
echo "###################################################"
echo ""
echo "These are commands avalible to you to debug Stratux"
echo ""
echo "###################################################"
echo ""
echo "stratux-off Shutdown Stratux"
echo "sa List all services running, check for '[+] stratux'"
echo "stxrestart Restart Startux service only"
echo "stxstop Stop Stratux Service."
echo "stxstart Start Stratux Service."
echo "sdr0 Test to see if sdr0 is in use by Stratux."
echo "sdr1 Test to see if sdr1 is in use by Startux."
echo "sdrs Test to see if both SDRs are in use by Stratux."
echo "d90 List my SDRs with serials"
echo "d900 Run dump1090 on SDR0 in interactive mode."
echo "d901 Run dump1090 on SDR0 in interactive mode."
echo "kal0 Find Channels for calibrating PPM of SDR0."
echo "kal1 Find Channels for calibrating PPM of SDR1."
echo "kalChan0 Use the Chan from above to get ppm pf SDR0. Example: kalChan0 151"
echo "kalChan1 Use the Chan from above to get ppm pf SDR1. Example: kalChan1 151"
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: setSerial0 23"
}

635
main/datalog.go 100644
Wyświetl plik

@ -0,0 +1,635 @@
/*
Copyright (c) 2015-2016 Christopher Young
Distributable under the terms of The "BSD New"" License
that can be found in the LICENSE file, herein included
as part of this header.
datalog.go: Log stratux data as it is received. Bucket data into timestamp time slots.
*/
package main
import (
"database/sql"
"errors"
"fmt"
_ "github.com/mattn/go-sqlite3"
"log"
"os"
"reflect"
"strconv"
"strings"
"time"
)
const (
LOG_TIMESTAMP_RESOLUTION = 250 * time.Millisecond
)
type StratuxTimestamp struct {
id int64
Time_type_preference int // 0 = stratuxClock, 1 = gpsClock, 2 = gpsClock extrapolated via stratuxClock.
StratuxClock_value time.Time
GPSClock_value time.Time // The value of this is either from the GPS or extrapolated from the GPS via stratuxClock if pref is 1 or 2. It is time.Time{} if 0.
PreferredTime_value time.Time
StartupID int64
}
// 'startup' table creates a new entry each time the daemon is started. This keeps track of sequential starts, even if the
// timestamp is ambiguous (units with no GPS). This struct is just a placeholder for an empty table (other than primary key).
type StratuxStartup struct {
id int64
Fill string
}
var dataLogStarted bool
var dataLogReadyToWrite bool
var stratuxStartupID int64
var dataLogTimestamps []StratuxTimestamp
var dataLogCurTimestamp int64 // Current timestamp bucket. This is an index on dataLogTimestamps which is not necessarily the db id.
/*
checkTimestamp().
Verify that our current timestamp is within the LOG_TIMESTAMP_RESOLUTION bucket.
Returns false if the timestamp was changed, true if it is still valid.
This is where GPS timestamps are extrapolated, if the GPS data is currently valid.
*/
func checkTimestamp() bool {
thisCurTimestamp := dataLogCurTimestamp
if stratuxClock.Since(dataLogTimestamps[thisCurTimestamp].StratuxClock_value) >= LOG_TIMESTAMP_RESOLUTION {
var ts StratuxTimestamp
ts.id = 0
ts.Time_type_preference = 0 // stratuxClock.
ts.StratuxClock_value = stratuxClock.Time
ts.GPSClock_value = time.Time{}
ts.PreferredTime_value = stratuxClock.Time
// Extrapolate from GPS timestamp, if possible.
if isGPSClockValid() && thisCurTimestamp > 0 {
// Was the last timestamp either extrapolated or GPS time?
last_ts := dataLogTimestamps[thisCurTimestamp]
if last_ts.Time_type_preference == 1 || last_ts.Time_type_preference == 2 {
// Extrapolate via stratuxClock.
timeSinceLastTS := ts.StratuxClock_value.Sub(last_ts.StratuxClock_value) // stratuxClock ticks since last timestamp.
extrapolatedGPSTimestamp := last_ts.PreferredTime_value.Add(timeSinceLastTS)
// Re-set the preferred timestamp type to '2' (extrapolated time).
ts.Time_type_preference = 2
ts.PreferredTime_value = extrapolatedGPSTimestamp
ts.GPSClock_value = extrapolatedGPSTimestamp
}
}
dataLogTimestamps = append(dataLogTimestamps, ts)
dataLogCurTimestamp = int64(len(dataLogTimestamps) - 1)
return false
}
return true
}
type SQLiteMarshal struct {
FieldType string
Marshal func(v reflect.Value) string
}
func boolMarshal(v reflect.Value) string {
b := v.Bool()
if b {
return "1"
}
return "0"
}
func intMarshal(v reflect.Value) string {
return strconv.FormatInt(v.Int(), 10)
}
func uintMarshal(v reflect.Value) string {
return strconv.FormatUint(v.Uint(), 10)
}
func floatMarshal(v reflect.Value) string {
return strconv.FormatFloat(v.Float(), 'f', 10, 64)
}
func stringMarshal(v reflect.Value) string {
return v.String()
}
func notsupportedMarshal(v reflect.Value) string {
return ""
}
func structCanBeMarshalled(v reflect.Value) bool {
m := v.MethodByName("String")
if m.IsValid() && !m.IsNil() {
return true
}
return false
}
func structMarshal(v reflect.Value) string {
if structCanBeMarshalled(v) {
m := v.MethodByName("String")
in := make([]reflect.Value, 0)
ret := m.Call(in)
if len(ret) > 0 {
return ret[0].String()
}
}
return ""
}
var sqliteMarshalFunctions = map[string]SQLiteMarshal{
"bool": {FieldType: "INTEGER", Marshal: boolMarshal},
"int": {FieldType: "INTEGER", Marshal: intMarshal},
"uint": {FieldType: "INTEGER", Marshal: uintMarshal},
"float": {FieldType: "REAL", Marshal: floatMarshal},
"string": {FieldType: "TEXT", Marshal: stringMarshal},
"struct": {FieldType: "STRING", Marshal: structMarshal},
"notsupported": {FieldType: "notsupported", Marshal: notsupportedMarshal},
}
var sqlTypeMap = map[reflect.Kind]string{
reflect.Bool: "bool",
reflect.Int: "int",
reflect.Int8: "int",
reflect.Int16: "int",
reflect.Int32: "int",
reflect.Int64: "int",
reflect.Uint: "uint",
reflect.Uint8: "uint",
reflect.Uint16: "uint",
reflect.Uint32: "uint",
reflect.Uint64: "uint",
reflect.Uintptr: "notsupported",
reflect.Float32: "float",
reflect.Float64: "float",
reflect.Complex64: "notsupported",
reflect.Complex128: "notsupported",
reflect.Array: "notsupported",
reflect.Chan: "notsupported",
reflect.Func: "notsupported",
reflect.Interface: "notsupported",
reflect.Map: "notsupported",
reflect.Ptr: "notsupported",
reflect.Slice: "notsupported",
reflect.String: "string",
reflect.Struct: "struct",
reflect.UnsafePointer: "notsupported",
}
func makeTable(i interface{}, tbl string, db *sql.DB) {
val := reflect.ValueOf(i)
fields := make([]string, 0)
for i := 0; i < val.NumField(); i++ {
kind := val.Field(i).Kind()
fieldName := val.Type().Field(i).Name
sqlTypeAlias := sqlTypeMap[kind]
// Check that if the field is a struct that it can be marshalled.
if sqlTypeAlias == "struct" && !structCanBeMarshalled(val.Field(i)) {
continue
}
if sqlTypeAlias == "notsupported" || fieldName == "id" {
continue
}
sqlType := sqliteMarshalFunctions[sqlTypeAlias].FieldType
s := fieldName + " " + sqlType
fields = append(fields, s)
}
// Add the timestamp_id field to link up with the timestamp table.
if tbl != "timestamp" && tbl != "startup" {
fields = append(fields, "timestamp_id INTEGER")
}
tblCreate := fmt.Sprintf("CREATE TABLE %s (id INTEGER NOT NULL PRIMARY KEY AUTOINCREMENT, %s)", tbl, strings.Join(fields, ", "))
_, err := db.Exec(tblCreate)
if err != nil {
fmt.Printf("ERROR: %s\n", err.Error())
}
}
/*
bulkInsert().
Reads insertBatch and insertBatchIfs. This is called after a group of insertData() calls.
*/
func bulkInsert(tbl string, db *sql.DB) (res sql.Result, err error) {
if _, ok := insertString[tbl]; !ok {
return nil, errors.New("no insert statement")
}
batchVals := insertBatchIfs[tbl]
numColsPerRow := len(batchVals[0])
maxRowBatch := int(999 / numColsPerRow) // SQLITE_MAX_VARIABLE_NUMBER = 999.
// log.Printf("table %s. %d cols per row. max batch %d\n", tbl, numColsPerRow, maxRowBatch)
for len(batchVals) > 0 {
// timeInit := time.Now()
i := int(0) // Variable number of rows per INSERT statement.
stmt := ""
vals := make([]interface{}, 0)
querySize := uint64(0) // Size of the query in bytes.
for len(batchVals) > 0 && i < maxRowBatch && querySize < 750000 { // Maximum of 1,000,000 bytes per query.
if len(stmt) == 0 { // The first set will be covered by insertString.
stmt = insertString[tbl]
querySize += uint64(len(insertString[tbl]))
} else {
addStr := ", (" + strings.Join(strings.Split(strings.Repeat("?", len(batchVals[0])), ""), ",") + ")"
stmt += addStr
querySize += uint64(len(addStr))
}
for _, val := range batchVals[0] {
querySize += uint64(len(val.(string)))
}
vals = append(vals, batchVals[0]...)
batchVals = batchVals[1:]
i++
}
// log.Printf("inserting %d rows to %s. querySize=%d\n", i, tbl, querySize)
res, err = db.Exec(stmt, vals...)
// timeBatch := time.Since(timeInit) // debug
// log.Printf("SQLite: bulkInserted %d rows to %s. Took %f msec to build and insert query. querySize=%d\n", i, tbl, 1000*timeBatch.Seconds(), querySize) // debug
if err != nil {
log.Printf("sqlite INSERT error: '%s'\n", err.Error())
return
}
}
// Clear the buffers.
delete(insertString, tbl)
delete(insertBatchIfs, tbl)
return
}
/*
insertData().
Inserts an arbitrary struct into an SQLite table.
Inserts the timestamp first, if its 'id' is 0.
*/
// Cached 'VALUES' statements. Indexed by table name.
var insertString map[string]string // INSERT INTO tbl (col1, col2, ...) VALUES(?, ?, ...). Only for one value.
var insertBatchIfs map[string][][]interface{}
func insertData(i interface{}, tbl string, db *sql.DB, ts_num int64) int64 {
val := reflect.ValueOf(i)
keys := make([]string, 0)
values := make([]string, 0)
for i := 0; i < val.NumField(); i++ {
kind := val.Field(i).Kind()
fieldName := val.Type().Field(i).Name
sqlTypeAlias := sqlTypeMap[kind]
if sqlTypeAlias == "notsupported" || fieldName == "id" {
continue
}
v := sqliteMarshalFunctions[sqlTypeAlias].Marshal(val.Field(i))
keys = append(keys, fieldName)
values = append(values, v)
}
// Add the timestamp_id field to link up with the timestamp table.
if tbl != "timestamp" && tbl != "startup" {
keys = append(keys, "timestamp_id")
if dataLogTimestamps[ts_num].id == 0 {
//FIXME: This is somewhat convoluted. When insertData() is called for a ts_num that corresponds to a timestamp with no database id,
// then it inserts that timestamp via the same interface and the id is updated in the structure via the below lines
// (dataLogTimestamps[ts_num].id = id).
dataLogTimestamps[ts_num].StartupID = stratuxStartupID
insertData(dataLogTimestamps[ts_num], "timestamp", db, ts_num) // Updates dataLogTimestamps[ts_num].id.
}
values = append(values, strconv.FormatInt(dataLogTimestamps[ts_num].id, 10))
}
if _, ok := insertString[tbl]; !ok {
// Prepare the statement.
tblInsert := fmt.Sprintf("INSERT INTO %s (%s) VALUES(%s)", tbl, strings.Join(keys, ","),
strings.Join(strings.Split(strings.Repeat("?", len(keys)), ""), ","))
insertString[tbl] = tblInsert
}
// Make the values slice into a slice of interface{}.
ifs := make([]interface{}, len(values))
for i := 0; i < len(values); i++ {
ifs[i] = values[i]
}
insertBatchIfs[tbl] = append(insertBatchIfs[tbl], ifs)
if tbl == "timestamp" || tbl == "startup" { // Immediate insert always for "timestamp" and "startup" table.
res, err := bulkInsert(tbl, db) // Bulk insert of 1, always.
if err == nil {
id, err := res.LastInsertId()
if err == nil && tbl == "timestamp" { // Special handling for timestamps. Update the timestamp ID.
ts := dataLogTimestamps[ts_num]
ts.id = id
dataLogTimestamps[ts_num] = ts
}
return id
}
}
return 0
}
type DataLogRow struct {
tbl string
data interface{}
ts_num int64
}
var dataLogChan chan DataLogRow
var shutdownDataLog chan bool
var shutdownDataLogWriter chan bool
var dataLogWriteChan chan DataLogRow
func dataLogWriter(db *sql.DB) {
dataLogWriteChan = make(chan DataLogRow, 10240)
shutdownDataLogWriter = make(chan bool)
// The write queue. As data comes in via dataLogChan, it is timestamped and stored.
// When writeTicker comes up, the queue is emptied.
writeTicker := time.NewTicker(10 * time.Second)
rowsQueuedForWrite := make([]DataLogRow, 0)
for {
select {
case r := <-dataLogWriteChan:
// Accept timestamped row.
rowsQueuedForWrite = append(rowsQueuedForWrite, r)
case <-writeTicker.C:
// for i := 0; i < 1000; i++ {
// logSituation()
// }
timeStart := stratuxClock.Time
nRows := len(rowsQueuedForWrite)
if globalSettings.DEBUG {
log.Printf("Writing %d rows\n", nRows)
}
// Write the buffered rows. This will block while it is writing.
// Save the names of the tables affected so that we can run bulkInsert() on after the insertData() calls.
tblsAffected := make(map[string]bool)
// Start transaction.
tx, err := db.Begin()
if err != nil {
log.Printf("db.Begin() error: %s\n", err.Error())
break // from select {}
}
for _, r := range rowsQueuedForWrite {
tblsAffected[r.tbl] = true
insertData(r.data, r.tbl, db, r.ts_num)
}
// Do the bulk inserts.
for tbl, _ := range tblsAffected {
bulkInsert(tbl, db)
}
// Close the transaction.
tx.Commit()
rowsQueuedForWrite = make([]DataLogRow, 0) // Zero the queue.
timeElapsed := stratuxClock.Since(timeStart)
if globalSettings.DEBUG {
rowsPerSecond := float64(nRows) / float64(timeElapsed.Seconds())
log.Printf("Writing finished. %d rows in %.2f seconds (%.1f rows per second).\n", nRows, float64(timeElapsed.Seconds()), rowsPerSecond)
}
if timeElapsed.Seconds() > 10.0 {
log.Printf("WARNING! SQLite logging is behind. Last write took %.1f seconds.\n", float64(timeElapsed.Seconds()))
dataLogCriticalErr := fmt.Errorf("WARNING! SQLite logging is behind. Last write took %.1f seconds.\n", float64(timeElapsed.Seconds()))
addSystemError(dataLogCriticalErr)
}
case <-shutdownDataLogWriter: // Received a message on the channel to initiate a graceful shutdown, and to command dataLog() to shut down
log.Printf("datalog.go: dataLogWriter() received shutdown message with rowsQueuedForWrite = %d\n", len(rowsQueuedForWrite))
shutdownDataLog <- true
return
}
}
log.Printf("datalog.go: dataLogWriter() shutting down\n")
}
func dataLog() {
dataLogStarted = true
log.Printf("datalog.go: dataLog() started\n")
dataLogChan = make(chan DataLogRow, 10240)
shutdownDataLog = make(chan bool)
dataLogTimestamps = make([]StratuxTimestamp, 0)
var ts StratuxTimestamp
ts.id = 0
ts.Time_type_preference = 0 // stratuxClock.
ts.StratuxClock_value = stratuxClock.Time
ts.GPSClock_value = time.Time{}
ts.PreferredTime_value = stratuxClock.Time
dataLogTimestamps = append(dataLogTimestamps, ts)
dataLogCurTimestamp = 0
// Check if we need to create a new database.
createDatabase := false
if _, err := os.Stat(dataLogFilef); os.IsNotExist(err) {
createDatabase = true
log.Printf("creating new database '%s'.\n", dataLogFilef)
}
db, err := sql.Open("sqlite3", dataLogFilef)
if err != nil {
log.Printf("sql.Open(): %s\n", err.Error())
}
defer func() {
db.Close()
dataLogStarted = false
//close(dataLogChan)
log.Printf("datalog.go: dataLog() has closed DB in %s\n", dataLogFilef)
}()
_, err = db.Exec("PRAGMA journal_mode=WAL")
if err != nil {
log.Printf("db.Exec('PRAGMA journal_mode=WAL') err: %s\n", err.Error())
}
_, err = db.Exec("PRAGMA synchronous=OFF")
if err != nil {
log.Printf("db.Exec('PRAGMA journal_mode=WAL') err: %s\n", err.Error())
}
//log.Printf("Starting dataLogWriter\n") // REMOVE -- DEBUG
go dataLogWriter(db)
// Do we need to create the database?
if createDatabase {
makeTable(StratuxTimestamp{}, "timestamp", db)
makeTable(mySituation, "mySituation", db)
makeTable(globalStatus, "status", db)
makeTable(globalSettings, "settings", db)
makeTable(TrafficInfo{}, "traffic", db)
makeTable(msg{}, "messages", db)
makeTable(esmsg{}, "es_messages", db)
makeTable(Dump1090TermMessage{}, "dump1090_terminal", db)
makeTable(StratuxStartup{}, "startup", db)
}
// The first entry to be created is the "startup" entry.
stratuxStartupID = insertData(StratuxStartup{}, "startup", db, 0)
dataLogReadyToWrite = true
//log.Printf("Entering dataLog read loop\n") //REMOVE -- DEBUG
for {
select {
case r := <-dataLogChan:
// When data is input, the first step is to timestamp it.
// Check if our time bucket has expired or has never been entered.
checkTimestamp()
// Mark the row with the current timestamp ID, in case it gets entered later.
r.ts_num = dataLogCurTimestamp
// Queue it for the scheduled write.
dataLogWriteChan <- r
case <-shutdownDataLog: // Received a message on the channel to complete a graceful shutdown (see the 'defer func()...' statement above).
log.Printf("datalog.go: dataLog() received shutdown message\n")
return
}
}
log.Printf("datalog.go: dataLog() shutting down\n")
close(shutdownDataLog)
}
/*
setDataLogTimeWithGPS().
Create a timestamp entry using GPS time.
*/
func setDataLogTimeWithGPS(sit SituationData) {
if isGPSClockValid() {
var ts StratuxTimestamp
// Piggyback a GPS time update from this update.
ts.id = 0
ts.Time_type_preference = 1 // gpsClock.
ts.StratuxClock_value = stratuxClock.Time
ts.GPSClock_value = sit.GPSTime
ts.PreferredTime_value = sit.GPSTime
dataLogTimestamps = append(dataLogTimestamps, ts)
dataLogCurTimestamp = int64(len(dataLogTimestamps) - 1)
}
}
/*
logSituation(), logStatus(), ... pass messages from other functions to the logging
engine. These are only read into `dataLogChan` if the Replay Log is toggled on,
and if the log system is ready to accept writes.
*/
func isDataLogReady() bool {
return dataLogReadyToWrite
}
func logSituation() {
if globalSettings.ReplayLog && isDataLogReady() {
dataLogChan <- DataLogRow{tbl: "mySituation", data: mySituation}
}
}
func logStatus() {
if globalSettings.ReplayLog && isDataLogReady() {
dataLogChan <- DataLogRow{tbl: "status", data: globalStatus}
}
}
func logSettings() {
if globalSettings.ReplayLog && isDataLogReady() {
dataLogChan <- DataLogRow{tbl: "settings", data: globalSettings}
}
}
func logTraffic(ti TrafficInfo) {
if globalSettings.ReplayLog && isDataLogReady() {
dataLogChan <- DataLogRow{tbl: "traffic", data: ti}
}
}
func logMsg(m msg) {
if globalSettings.ReplayLog && isDataLogReady() {
dataLogChan <- DataLogRow{tbl: "messages", data: m}
}
}
func logESMsg(m esmsg) {
if globalSettings.ReplayLog && isDataLogReady() {
dataLogChan <- DataLogRow{tbl: "es_messages", data: m}
}
}
func logDump1090TermMessage(m Dump1090TermMessage) {
if globalSettings.DEBUG && globalSettings.ReplayLog && isDataLogReady() {
dataLogChan <- DataLogRow{tbl: "dump1090_terminal", data: m}
}
}
func initDataLog() {
//log.Printf("dataLogStarted = %t. dataLogReadyToWrite = %t\n", dataLogStarted, dataLogReadyToWrite) //REMOVE -- DEBUG
insertString = make(map[string]string)
insertBatchIfs = make(map[string][][]interface{})
go dataLogWatchdog()
//log.Printf("datalog.go: initDataLog() complete.\n") //REMOVE -- DEBUG
}
/*
dataLogWatchdog(): Watchdog function to control startup / shutdown of data logging subsystem.
Called by initDataLog as a goroutine. It iterates once per second to determine if
globalSettings.ReplayLog has toggled. If logging was switched from off to on, it starts
datalog() as a goroutine. If the log is running and we want it to stop, it calls
closeDataLog() to turn off the input channels, close the log, and tear down the dataLog
and dataLogWriter goroutines.
*/
func dataLogWatchdog() {
for {
if !dataLogStarted && globalSettings.ReplayLog { // case 1: sqlite logging isn't running, and we want to start it
log.Printf("datalog.go: Watchdog wants to START logging.\n")
go dataLog()
} else if dataLogStarted && !globalSettings.ReplayLog { // case 2: sqlite logging is running, and we want to shut it down
log.Printf("datalog.go: Watchdog wants to STOP logging.\n")
closeDataLog()
}
//log.Printf("Watchdog iterated.\n") //REMOVE -- DEBUG
time.Sleep(1 * time.Second)
//log.Printf("Watchdog sleep over.\n") //REMOVE -- DEBUG
}
}
/*
closeDataLog(): Handler for graceful shutdown of data logging goroutines. It is called by
by dataLogWatchdog(), gracefulShutdown(), and by any other function (disk space monitor?)
that needs to be able to shut down sqlite logging without corrupting data or blocking
execution.
This function turns off log message reads into the dataLogChan receiver, and sends a
message to a quit channel ('shutdownDataLogWriter`) in dataLogWriter(). dataLogWriter()
then sends a message to a quit channel to 'shutdownDataLog` in dataLog() to close *that*
goroutine. That function sets dataLogStarted=false once the logfile is closed. By waiting
for that signal, closeDataLog() won't exit until the log is safely written. This prevents
data loss on shutdown.
*/
func closeDataLog() {
//log.Printf("closeDataLog(): dataLogStarted = %t\n", dataLogStarted) //REMOVE -- DEBUG
dataLogReadyToWrite = false // prevent any new messages from being sent down the channels
log.Printf("datalog.go: Starting data log shutdown\n")
shutdownDataLogWriter <- true //
defer close(shutdownDataLogWriter) // ... and close the channel so subsequent accidental writes don't stall execution
log.Printf("datalog.go: Waiting for shutdown signal from dataLog()")
for dataLogStarted {
//log.Printf("closeDataLog(): dataLogStarted = %t\n", dataLogStarted) //REMOVE -- DEBUG
time.Sleep(50 * time.Millisecond)
}
log.Printf("datalog.go: Data log shutdown successful.\n")
}

324
main/equations.go 100644
Wyświetl plik

@ -0,0 +1,324 @@
/*
Copyright (c) 2016 AvSquirrel (https://github.com/AvSquirrel)
Distributable under the terms of the "BSD New" License
that can be found in the LICENSE file, herein included
as part of this header.
equations.go: Math and statistics library used to support AHRS
and other fuctions of Stratux package
*/
package main
import (
"fmt"
"math"
)
// linReg calculates slope and intercept for a least squares linear regression of y[] vs x[]
// Returns error if fewer than two data points in each series, or if series lengths are different
func linReg(x, y []float64) (slope, intercept float64, valid bool) {
n := len(x)
nf := float64(n)
if n != len(y) {
fmt.Printf("linReg: Lengths not equal\n")
return math.NaN(), math.NaN(), false
}
if n < 2 {
fmt.Printf("linReg: Lengths too short\n")
return math.NaN(), math.NaN(), false
}
var Sx, Sy, Sxx, Sxy, Syy float64
for i := range x {
Sx += x[i]
Sy += y[i]
Sxx += x[i] * x[i]
Sxy += x[i] * y[i]
Syy += y[i] * y[i]
}
if nf*Sxx == Sx*Sx {
fmt.Printf("linReg: Infinite slope\n")
return math.NaN(), math.NaN(), false
}
// Calculate slope and intercept
slope = (nf*Sxy - Sx*Sy) / (nf*Sxx - Sx*Sx)
intercept = Sy/nf - slope*Sx/nf
valid = true
return
}
// linRegWeighted calculates slope and intercept for a weighted least squares
// linear regression of y[] vs x[], given weights w[] for each point.
// Returns error if fewer than two data points in each series, if series lengths are different,
// if weights sum to zero, or if slope is infinite
func linRegWeighted(x, y, w []float64) (slope, intercept float64, valid bool) {
n := len(x)
if n != len(y) || n != len(w) {
fmt.Printf("linRegWeighted: Lengths not equal\n")
return math.NaN(), math.NaN(), false
}
if n < 2 {
fmt.Printf("linRegWeighted: Lengths too short\n")
return math.NaN(), math.NaN(), false
}
//var Sx, Sy, Sxx, Sxy, Syy float64
var Sw, Swx, Swy, Swxx, Swxy, Swyy float64
for i := range x {
Sw += w[i]
Swxy += w[i] * x[i] * y[i]
Swx += w[i] * x[i]
Swy += w[i] * y[i]
Swxx += w[i] * x[i] * x[i]
Swyy += w[i] * y[i] * y[i]
/*
Sx += x[i]
Sy += y[i]
Sxx += x[i]*x[i]
Sxy += x[i]*y[i]
Syy += y[i]*y[i]
*/
}
if Sw == 0 {
fmt.Printf("linRegWeighted: Sum of weights is zero\n")
return math.NaN(), math.NaN(), false
}
if Sw*Swxx == Swx*Swx {
fmt.Printf("linRegWeighted: Infinite slope\n")
return math.NaN(), math.NaN(), false
}
// Calculate slope and intercept
slope = (Sw*Swxy - Swx*Swy) / (Sw*Swxx - Swx*Swx)
intercept = Swy/Sw - slope*Swx/Sw
valid = true
return
}
// triCubeWeight returns the value of the tricube weight function
// at point x, for the given center and halfwidth.
func triCubeWeight(center, halfwidth, x float64) float64 {
var weight, x_t float64
x_t = math.Abs((x - center) / halfwidth)
if x_t < 1 {
weight = math.Pow((1 - math.Pow(x_t, 3)), 3)
} else {
weight = 0
}
return weight
}
// arrayMin calculates the minimum value in array x
func arrayMin(x []float64) (float64, bool) {
if len(x) < 1 {
fmt.Printf("arrayMin: Length too short\n")
return math.NaN(), false
}
min := x[0]
for i := range x {
if x[i] < min {
min = x[i]
}
}
return min, true
}
// arrayMax calculates the maximum value in array x
func arrayMax(x []float64) (float64, bool) {
if len(x) < 1 {
fmt.Printf("arrayMax: Length too short\n")
return math.NaN(), false
}
max := x[0]
for i := range x {
if x[i] > max {
max = x[i]
}
}
return max, true
}
// arrayRange calculates the range of values in array x
func arrayRange(x []float64) (float64, bool) {
max, err1 := arrayMax(x)
min, err2 := arrayMin(x)
if !err1 || !err2 {
fmt.Printf("Error calculating range\n")
return math.NaN(), false
}
return (max - min), true
}
// mean returns the arithmetic mean of array x
func mean(x []float64) (float64, bool) {
if len(x) < 1 {
fmt.Printf("mean: Length too short\n")
return math.NaN(), false
}
sum := 0.0
nf := float64(len(x))
for i := range x {
sum += x[i]
}
return sum / nf, true
}
// stdev estimates the sample standard deviation of array x
func stdev(x []float64) (float64, bool) {
if len(x) < 2 {
fmt.Printf("stdev: Length too short\n")
return math.NaN(), false
}
nf := float64(len(x))
xbar, xbarValid := mean(x)
if !xbarValid {
fmt.Printf("stdev: Error calculating xbar\n")
return math.NaN(), false
}
sumsq := 0.0
for i := range x {
sumsq += (x[i] - xbar) * (x[i] - xbar)
}
return math.Pow(sumsq/(nf-1), 0.5), true
}
// radians converts angle from degrees, and returns its value in radians
func radians(angle float64) float64 {
return angle * math.Pi / 180.0
}
// degrees converts angle from radians, and returns its value in degrees
func degrees(angle float64) float64 {
return angle * 180.0 / math.Pi
}
// radiansRel converts angle from degrees, and returns its value in radians in the range -Pi to + Pi
func radiansRel(angle float64) float64 {
for angle > 180 {
angle -= 360
}
for angle < -180 {
angle += 360
}
return angle * math.Pi / 180.0
}
// degreesRel converts angle from radians, and returns its value in the range of -180 to +180 degrees
func degreesRel(angle float64) float64 {
for angle > math.Pi {
angle -= 2 * math.Pi
}
for angle < -math.Pi {
angle += 2 * math.Pi
}
return angle * 180.0 / math.Pi
}
// degreesHdg converts angle from radians, and returns its value in the range of 0+ to 360 degrees
func degreesHdg(angle float64) float64 {
for angle < 0 {
angle += 2 * math.Pi
}
return angle * 180.0 / math.Pi
}
/*
Distance functions based on rectangular coordinate systems
Simple calculations and "good enough" on small scale (± 1° of lat / lon)
suitable for relative distance to nearby traffic
*/
// distRect returns distance and bearing to target #2 (e.g. traffic) from target #1 (e.g. ownship)
// Inputs are lat / lon of both points in decimal degrees
// Outputs are distance in meters and bearing in degrees (0° = north, 90° = east)
// Secondary outputs are north and east components of distance in meters (north, east positive)
func distRect(lat1, lon1, lat2, lon2 float64) (dist, bearing, distN, distE float64) {
radius_earth := 6371008.8 // meters; mean radius
dLat := radiansRel(lat2 - lat1)
avgLat := radiansRel((lat2 + lat1) / 2)
dLon := radiansRel(lon2 - lon1)
distN = dLat * radius_earth
distE = dLon * radius_earth * math.Abs(math.Cos(avgLat))
dist = math.Pow(distN*distN+distE*distE, 0.5)
bearing = math.Atan2(distE, distN)
bearing = degreesHdg(bearing)
return
}
// distRectNorth returns north-south distance from point 1 to point 2.
// Inputs are lat in decimal degrees. Output is distance in meters (east positive)
func distRectNorth(lat1, lat2 float64) float64 {
var dist float64
radius_earth := 6371008.8 // meters; mean radius
dLat := radiansRel(lat2 - lat1)
dist = dLat * radius_earth
return dist
}
// distRectEast returns east-west distance from point 1 to point 2.
// Inputs are lat/lon in decimal degrees. Output is distance in meters (north positive)
func distRectEast(lat1, lon1, lat2, lon2 float64) float64 {
var dist float64
radius_earth := 6371008.8 // meters; mean radius
//dLat := radiansRel(lat2 - lat1) // unused
avgLat := radiansRel((lat2 + lat1) / 2)
dLon := radiansRel(lon2 - lon1)
dist = dLon * radius_earth * math.Abs(math.Cos(avgLat))
return dist
}
/*
Distance functions: Polar coordinate systems
More accurate over longer distances
*/
// distance calculates distance between two points using the law of cosines.
// Inputs are lat / lon of both points in decimal degrees
// Outputs are distance in meters and bearing to the target from origin in degrees (0° = north, 90° = east)
func distance(lat1, lon1, lat2, lon2 float64) (dist, bearing float64) {
radius_earth := 6371008.8 // meters; mean radius
lat1 = radians(lat1)
lon1 = radians(lon1)
lat2 = radians(lat2)
lon2 = radians(lon2)
dist = math.Acos(math.Sin(lat1)*math.Sin(lat2)+math.Cos(lat1)*math.Cos(lat2)*math.Cos(lon2-lon1)) * radius_earth
var x, y float64
x = math.Cos(lat1)*math.Sin(lat2) - math.Sin(lat1)*math.Cos(lat2)*math.Cos(lon2-lon1)
y = math.Sin(lon2-lon1) * math.Cos(lat2)
bearing = degreesHdg(math.Atan2(y, x))
return
}

Wyświetl plik

@ -26,24 +26,30 @@ import (
"runtime"
"strconv"
"strings"
"sync"
"syscall"
"time"
humanize "github.com/dustin/go-humanize"
"../uatparse"
humanize "github.com/dustin/go-humanize"
"github.com/ricochet2200/go-disk-usage/du"
)
// http://www.faa.gov/nextgen/programs/adsb/wsa/media/GDL90_Public_ICD_RevA.PDF
var debugLogf string // Set according to OS config.
var dataLogFilef string // Set according to OS config.
const (
configLocation = "/etc/stratux.conf"
indexFilename = "/var/log/stratux/LOGINDEX"
managementAddr = ":80"
debugLog = "/var/log/stratux.log"
configLocation = "/etc/stratux.conf"
managementAddr = ":80"
debugLog = "/var/log/stratux.log"
dataLogFile = "/var/log/stratux.sqlite"
//FlightBox: log to /root.
debugLog_FB = "/root/stratux.log"
dataLogFile_FB = "/var/log/stratux.sqlite"
maxDatagramSize = 8192
maxUserMsgQueueSize = 25000 // About 10MB per port per connected client.
logDirectory = "/var/log/stratux"
UPLINK_BLOCK_DATA_BITS = 576
UPLINK_BLOCK_BITS = (UPLINK_BLOCK_DATA_BITS + 160)
@ -64,23 +70,16 @@ const (
MSGTYPE_BASIC_REPORT = 0x1E
MSGTYPE_LONG_REPORT = 0x1F
MSGCLASS_UAT = 0
MSGCLASS_ES = 1
MSGCLASS_GPS = 3
MSGCLASS_AHRS = 4
MSGCLASS_DUMP1090 = 5
MSGCLASS_UAT = 0
MSGCLASS_ES = 1
LON_LAT_RESOLUTION = float32(180.0 / 8388608.0)
TRACK_RESOLUTION = float32(360.0 / 256.0)
)
var maxSignalStrength int
var usage *du.DiskUsage
var uatReplayLog string
var esReplayLog string
var gpsReplayLog string
var ahrsReplayLog string
var dump1090ReplayLog string
var maxSignalStrength int
var stratuxBuild string
var stratuxVersion string
@ -101,23 +100,17 @@ type ReadCloser interface {
io.Closer
}
// File handles for replay logging.
var uatReplayWriter WriteCloser
var esReplayWriter WriteCloser
var gpsReplayWriter WriteCloser
var ahrsReplayWriter WriteCloser
var dump1090ReplayWriter WriteCloser
var developerMode bool
type msg struct {
MessageClass uint
TimeReceived time.Time
Data []byte
Data string
Products []uint32
Signal_amplitude int
Signal_strength float64
ADSBTowerID string // Index in the 'ADSBTowers' map, if this is a parseable uplink message.
uatMsg *uatparse.UATMsg
}
// Raw inputs.
@ -134,53 +127,10 @@ type ADSBTower struct {
Energy_last_minute uint64 // Summation of power observed for this tower across all messages last minute
Signal_strength_last_minute float64 // Average RSSI (dB) observed for this tower last minute
Messages_last_minute uint64
Messages_total uint64
}
var ADSBTowers map[string]ADSBTower // Running list of all towers seen. (lat,lng) -> ADSBTower
func constructFilenames() {
var fileIndexNumber uint
// First, create the log file directory if it does not exist
os.Mkdir(logDirectory, 0755)
f, err := os.Open(indexFilename)
if err != nil {
log.Printf("Unable to open index file %s using index of 0\n", indexFilename)
fileIndexNumber = 0
} else {
_, err := fmt.Fscanf(f, "%d\n", &fileIndexNumber)
if err != nil {
log.Printf("Unable to read index file %s using index of 0\n", indexFilename)
}
f.Close()
fileIndexNumber++
}
fo, err := os.Create(indexFilename)
if err != nil {
log.Printf("Error creating index file %s\n", indexFilename)
}
_, err2 := fmt.Fprintf(fo, "%d\n", fileIndexNumber)
if err2 != nil {
log.Printf("Error writing to index file %s\n", indexFilename)
}
fo.Sync()
fo.Close()
if developerMode == true {
uatReplayLog = fmt.Sprintf("%s/%04d-uat.log", logDirectory, fileIndexNumber)
esReplayLog = fmt.Sprintf("%s/%04d-es.log", logDirectory, fileIndexNumber)
gpsReplayLog = fmt.Sprintf("%s/%04d-gps.log", logDirectory, fileIndexNumber)
ahrsReplayLog = fmt.Sprintf("%s/%04d-ahrs.log", logDirectory, fileIndexNumber)
dump1090ReplayLog = fmt.Sprintf("%s/%04d-dump1090.log", logDirectory, fileIndexNumber)
} else {
uatReplayLog = fmt.Sprintf("%s/%04d-uat.log.gz", logDirectory, fileIndexNumber)
esReplayLog = fmt.Sprintf("%s/%04d-es.log.gz", logDirectory, fileIndexNumber)
gpsReplayLog = fmt.Sprintf("%s/%04d-gps.log.gz", logDirectory, fileIndexNumber)
ahrsReplayLog = fmt.Sprintf("%s/%04d-ahrs.log.gz", logDirectory, fileIndexNumber)
dump1090ReplayLog = fmt.Sprintf("%s/%04d-dump1090.log.gz", logDirectory, fileIndexNumber)
}
}
var ADSBTowerMutex *sync.Mutex
// Construct the CRC table. Adapted from FAA ref above.
func crcInit() {
@ -297,7 +247,7 @@ func makeOwnshipReport() bool {
msg[11] = byte((alt & 0xFF0) >> 4) // Altitude.
msg[12] = byte((alt & 0x00F) << 4)
if isGPSGroundTrackValid() {
msg[12] = msg[12] | 0x0B // "Airborne" + "True Heading"
msg[12] = msg[12] | 0x09 // "Airborne" + "True Track"
}
msg[13] = byte(0x80 | (mySituation.NACp & 0x0F)) //Set NIC = 8 and use NACp from ry835ai.go.
@ -317,12 +267,24 @@ func makeOwnshipReport() bool {
msg[15] = msg[15] | byte((verticalVelocity&0x0F00)>>8)
msg[16] = byte(verticalVelocity & 0xFF)
// Showing magnetic (corrected) on ForeFlight. Needs to be True Heading.
groundTrack := uint16(0)
// Track is degrees true, set from GPS true course.
groundTrack := float32(0)
if isGPSGroundTrackValid() {
groundTrack = mySituation.TrueCourse
}
trk := uint8(float32(groundTrack) / TRACK_RESOLUTION) // Resolution is ~1.4 degrees.
tempTrack := groundTrack + TRACK_RESOLUTION/2 // offset by half the 8-bit resolution to minimize binning error
for tempTrack > 360 {
tempTrack -= 360
}
for tempTrack < 0 {
tempTrack += 360
}
trk := uint8(tempTrack / TRACK_RESOLUTION) // Resolution is ~1.4 degrees.
//log.Printf("For groundTrack = %.2f°, tempTrack= %.2f, trk = %d (%f°)\n",groundTrack,tempTrack,trk,float32(trk)*TRACK_RESOLUTION)
msg[17] = byte(trk)
@ -347,11 +309,10 @@ func makeOwnshipGeometricAltitudeReport() bool {
}
msg := make([]byte, 5)
// See p.28.
msg[0] = 0x0B // Message type "Ownship Geo Alt".
alt := int16(mySituation.Alt) // GPS Altitude.
alt = alt / 5
msg[1] = byte(alt >> 8) // Altitude.
msg[2] = byte(alt & 0x00FF) // Altitude.
msg[0] = 0x0B // Message type "Ownship Geo Alt".
alt := int16(mySituation.Alt / 5) // GPS Altitude, encoded to 16-bit int using 5-foot resolution
msg[1] = byte(alt >> 8) // Altitude.
msg[2] = byte(alt & 0x00FF) // Altitude.
//TODO: "Figure of Merit". 0x7FFF "Not available".
msg[3] = 0x00
@ -417,7 +378,7 @@ func makeStratuxStatus() []byte {
// Valid and enabled flags.
// Valid/Enabled: GPS portion.
if isGPSValid() {
switch mySituation.quality {
switch mySituation.Quality {
case 1: // 1 = 3D GPS.
msg[13] = 1
case 2: // 2 = DGPS (SBAS /WAAS).
@ -508,7 +469,8 @@ func makeStratuxStatus() []byte {
msg[26] = byte((v & 0xFF00) >> 8)
msg[27] = byte(v & 0xFF)
// Number of ADS-B towers.
// Number of ADS-B towers. Map structure is protected by ADSBTowerMutex.
ADSBTowerMutex.Lock()
num_towers := uint8(len(ADSBTowers))
msg[28] = byte(num_towers)
@ -525,7 +487,7 @@ func makeStratuxStatus() []byte {
msg = append(msg, tmp[1]) // Longitude.
msg = append(msg, tmp[2]) // Longitude.
}
ADSBTowerMutex.Unlock()
return prepareMessage(msg)
}
@ -641,7 +603,9 @@ func updateMessageStats() {
m := len(MsgLog)
UAT_messages_last_minute := uint(0)
ES_messages_last_minute := uint(0)
products_last_minute := make(map[string]uint32)
ADSBTowerMutex.Lock()
defer ADSBTowerMutex.Unlock()
// Clear out ADSBTowers stats.
for t, tinf := range ADSBTowers {
@ -655,12 +619,20 @@ func updateMessageStats() {
t = append(t, MsgLog[i])
if MsgLog[i].MessageClass == MSGCLASS_UAT {
UAT_messages_last_minute++
for _, p := range MsgLog[i].Products {
products_last_minute[getProductNameFromId(int(p))]++
}
if len(MsgLog[i].ADSBTowerID) > 0 { // Update tower stats.
tid := MsgLog[i].ADSBTowerID
if _, ok := ADSBTowers[tid]; !ok { // First time we've seen the tower? Start tracking.
var newTower ADSBTower
newTower.Lat = MsgLog[i].uatMsg.Lat
newTower.Lng = MsgLog[i].uatMsg.Lon
newTower.Signal_strength_max = -999 // dBmax = 0, so this needs to initialize below scale ( << -48 dB)
ADSBTowers[tid] = newTower
}
twr := ADSBTowers[tid]
twr.Signal_strength_now = MsgLog[i].Signal_strength
twr.Energy_last_minute += uint64((MsgLog[i].Signal_amplitude) * (MsgLog[i].Signal_amplitude))
twr.Messages_last_minute++
if MsgLog[i].Signal_strength > twr.Signal_strength_max { // Update alltime max signal strength.
@ -676,7 +648,6 @@ func updateMessageStats() {
MsgLog = t
globalStatus.UAT_messages_last_minute = UAT_messages_last_minute
globalStatus.ES_messages_last_minute = ES_messages_last_minute
globalStatus.uat_products_last_minute = products_last_minute
// Update "max messages/min" counters.
if globalStatus.UAT_messages_max < UAT_messages_last_minute {
@ -714,42 +685,49 @@ func cpuTempMonitor() {
<-timer.C
// Update CPUTemp.
globalStatus.CPUTemp = float32(-99.0) // Default value - in case code below hangs.
temp, err := ioutil.ReadFile("/sys/class/thermal/thermal_zone0/temp")
tempStr := strings.Trim(string(temp), "\n")
t := float32(-99.0)
if err == nil {
tInt, err := strconv.Atoi(tempStr)
if err == nil {
if tInt > 1000 {
globalStatus.CPUTemp = float32(tInt) / float32(1000.0)
t = float32(tInt) / float32(1000.0)
} else {
globalStatus.CPUTemp = float32(tInt) // case where Temp is returned as simple integer
t = float32(tInt) // case where Temp is returned as simple integer
}
}
}
if t >= -99.0 { // Only update if valid value was obtained.
globalStatus.CPUTemp = t
}
}
}
func updateStatus() {
if mySituation.quality == 2 {
globalStatus.GPS_solution = "DGPS (SBAS / WAAS)"
} else if mySituation.quality == 1 {
if mySituation.Quality == 2 {
globalStatus.GPS_solution = "GPS + SBAS (WAAS / EGNOS)"
} else if mySituation.Quality == 1 {
globalStatus.GPS_solution = "3D GPS"
} else if mySituation.quality == 6 {
} else if mySituation.Quality == 6 {
globalStatus.GPS_solution = "Dead Reckoning"
} else if mySituation.quality == 0 {
} else if mySituation.Quality == 0 {
globalStatus.GPS_solution = "No Fix"
} else {
globalStatus.GPS_solution = "Unknown"
}
if !(globalStatus.GPS_connected) || !(isGPSConnected()) { // isGPSConnected looks for valid NMEA messages. GPS_connected is set by gpsSerialReader and will immediately fail on disconnected USB devices, or in a few seconds after "blocked" comms on ttyAMA0.
satelliteMutex.Lock()
Satellites = make(map[string]SatelliteInfo)
satelliteMutex.Unlock()
mySituation.Satellites = 0
mySituation.SatellitesSeen = 0
mySituation.SatellitesTracked = 0
mySituation.quality = 0
mySituation.Quality = 0
globalStatus.GPS_solution = "Disconnected"
globalStatus.GPS_connected = false
}
@ -762,51 +740,9 @@ func updateStatus() {
globalStatus.Uptime = int64(stratuxClock.Milliseconds)
globalStatus.UptimeClock = stratuxClock.Time
globalStatus.Clock = time.Now()
}
type ReplayWriter struct {
fp *os.File
}
func (r ReplayWriter) Write(p []byte) (n int, err error) {
return r.fp.Write(p)
}
func (r ReplayWriter) Close() error {
return r.fp.Close()
}
func makeReplayLogEntry(msg string) string {
return fmt.Sprintf("%d,%s\n", time.Since(timeStarted).Nanoseconds(), msg)
}
func replayLog(msg string, msgclass int) {
if !globalSettings.ReplayLog { // Logging disabled.
return
}
msg = strings.Trim(msg, " \r\n")
if len(msg) == 0 { // Blank message.
return
}
var fp WriteCloser
switch msgclass {
case MSGCLASS_UAT:
fp = uatReplayWriter
case MSGCLASS_ES:
fp = esReplayWriter
case MSGCLASS_GPS:
fp = gpsReplayWriter
case MSGCLASS_AHRS:
fp = ahrsReplayWriter
case MSGCLASS_DUMP1090:
fp = dump1090ReplayWriter
}
if fp != nil {
s := makeReplayLogEntry(msg)
fp.Write([]byte(s))
}
usage = du.NewDiskUsage("/")
globalStatus.DiskBytesFree = usage.Free()
}
type WeatherMessage struct {
@ -839,8 +775,7 @@ func registerADSBTextMessageReceived(msg string) {
}
func parseInput(buf string) ([]byte, uint16) {
replayLog(buf, MSGCLASS_UAT) // Log the raw message.
//FIXME: We're ignoring all invalid format UAT messages (not sending to datalog).
x := strings.Split(buf, ";") // Discard everything after the first ';'.
s := x[0]
if len(s) == 0 {
@ -904,7 +839,7 @@ func parseInput(buf string) ([]byte, uint16) {
var thisMsg msg
thisMsg.MessageClass = MSGCLASS_UAT
thisMsg.TimeReceived = stratuxClock.Time
thisMsg.Data = frame
thisMsg.Data = buf
thisMsg.Signal_amplitude = thisSignalStrength
thisMsg.Signal_strength = 20 * math.Log10((float64(thisSignalStrength))/1000)
thisMsg.Products = make([]uint32, 0)
@ -915,18 +850,6 @@ func parseInput(buf string) ([]byte, uint16) {
uatMsg.DecodeUplink()
towerid := fmt.Sprintf("(%f,%f)", uatMsg.Lat, uatMsg.Lon)
thisMsg.ADSBTowerID = towerid
if _, ok := ADSBTowers[towerid]; !ok { // First time we've seen the tower. Start tracking.
var newTower ADSBTower
newTower.Lat = uatMsg.Lat
newTower.Lng = uatMsg.Lon
newTower.Signal_strength_now = thisMsg.Signal_strength
newTower.Signal_strength_max = -999 // dBmax = 0, so this needs to initialize below scale ( << -48 dB)
ADSBTowers[towerid] = newTower
}
twr := ADSBTowers[towerid]
twr.Messages_total++
twr.Signal_strength_now = thisMsg.Signal_strength
ADSBTowers[towerid] = twr
// Get all of the "product ids".
for _, f := range uatMsg.Frames {
thisMsg.Products = append(thisMsg.Products, f.Product_id)
@ -936,10 +859,12 @@ func parseInput(buf string) ([]byte, uint16) {
for _, r := range textReports {
registerADSBTextMessageReceived(r)
}
thisMsg.uatMsg = uatMsg
}
}
MsgLog = append(MsgLog, thisMsg)
logMsg(thisMsg)
return frame, msgtype
}
@ -1017,16 +942,17 @@ func getProductNameFromId(product_id int) string {
}
type settings struct {
UAT_Enabled bool
ES_Enabled bool
GPS_Enabled bool
NetworkOutputs []networkConnection
AHRS_Enabled bool
DEBUG bool
ReplayLog bool
PPM int
OwnshipModeS string
WatchList string
UAT_Enabled bool
ES_Enabled bool
GPS_Enabled bool
NetworkOutputs []networkConnection
AHRS_Enabled bool
DisplayTrafficSource bool
DEBUG bool
ReplayLog bool
PPM int
OwnshipModeS string
WatchList string
}
type status struct {
@ -1035,8 +961,8 @@ type status struct {
HardwareBuild string
Devices uint32
Connected_Users uint
DiskBytesFree uint64
UAT_messages_last_minute uint
uat_products_last_minute map[string]uint32
UAT_messages_max uint
ES_messages_last_minute uint
ES_messages_max uint
@ -1075,6 +1001,7 @@ func defaultSettings() {
}
globalSettings.AHRS_Enabled = false
globalSettings.DEBUG = false
globalSettings.DisplayTrafficSource = false
globalSettings.ReplayLog = false //TODO: 'true' for debug builds.
globalSettings.OwnshipModeS = "F00000"
}
@ -1123,36 +1050,6 @@ func saveSettings() {
log.Printf("wrote settings.\n")
}
func replayMark(active bool) {
var t string
if !active {
t = fmt.Sprintf("PAUSE,%d\n", time.Since(timeStarted).Nanoseconds())
} else {
t = fmt.Sprintf("UNPAUSE,%d\n", time.Since(timeStarted).Nanoseconds())
}
if uatReplayWriter != nil {
uatReplayWriter.Write([]byte(t))
}
if esReplayWriter != nil {
esReplayWriter.Write([]byte(t))
}
if gpsReplayWriter != nil {
gpsReplayWriter.Write([]byte(t))
}
if ahrsReplayWriter != nil {
ahrsReplayWriter.Write([]byte(t))
}
if dump1090ReplayWriter != nil {
dump1090ReplayWriter.Write([]byte(t))
}
}
func openReplay(fn string, compressed bool) (WriteCloser, error) {
fp, err := os.OpenFile(fn, os.O_CREATE|os.O_WRONLY|os.O_APPEND, 0666)
@ -1177,18 +1074,27 @@ func openReplay(fn string, compressed bool) (WriteCloser, error) {
func printStats() {
statTimer := time.NewTicker(30 * time.Second)
diskUsageWarning := false
for {
<-statTimer.C
var memstats runtime.MemStats
runtime.ReadMemStats(&memstats)
log.Printf("stats [started: %s]\n", humanize.RelTime(time.Time{}, stratuxClock.Time, "ago", "from now"))
log.Printf(" - Disk bytes used = %s (%.1f %%), Disk bytes free = %s (%.1f %%)\n", humanize.Bytes(usage.Used()), 100*usage.Usage(), humanize.Bytes(usage.Free()), 100*(1-usage.Usage()))
log.Printf(" - CPUTemp=%.02f deg C, MemStats.Alloc=%s, MemStats.Sys=%s, totalNetworkMessagesSent=%s\n", globalStatus.CPUTemp, humanize.Bytes(uint64(memstats.Alloc)), humanize.Bytes(uint64(memstats.Sys)), humanize.Comma(int64(totalNetworkMessagesSent)))
log.Printf(" - UAT/min %s/%s [maxSS=%.02f%%], ES/min %s/%s\n, Total traffic targets tracked=%s", humanize.Comma(int64(globalStatus.UAT_messages_last_minute)), humanize.Comma(int64(globalStatus.UAT_messages_max)), float64(maxSignalStrength)/10.0, humanize.Comma(int64(globalStatus.ES_messages_last_minute)), humanize.Comma(int64(globalStatus.ES_messages_max)), humanize.Comma(int64(len(seenTraffic))))
log.Printf(" - UAT/min %s/%s [maxSS=%.02f%%], ES/min %s/%s, Total traffic targets tracked=%s", humanize.Comma(int64(globalStatus.UAT_messages_last_minute)), humanize.Comma(int64(globalStatus.UAT_messages_max)), float64(maxSignalStrength)/10.0, humanize.Comma(int64(globalStatus.ES_messages_last_minute)), humanize.Comma(int64(globalStatus.ES_messages_max)), humanize.Comma(int64(len(seenTraffic))))
log.Printf(" - Network data messages sent: %d total, %d nonqueueable. Network data bytes sent: %d total, %d nonqueueable.\n", globalStatus.NetworkDataMessagesSent, globalStatus.NetworkDataMessagesSentNonqueueable, globalStatus.NetworkDataBytesSent, globalStatus.NetworkDataBytesSentNonqueueable)
if globalSettings.GPS_Enabled {
log.Printf(" - Last GPS fix: %s, GPS solution type: %d using %d satellites (%d/%d seen/tracked), NACp: %d, est accuracy %.02f m\n", stratuxClock.HumanizeTime(mySituation.LastFixLocalTime), mySituation.quality, mySituation.Satellites, mySituation.SatellitesSeen, mySituation.SatellitesTracked, mySituation.NACp, mySituation.Accuracy)
log.Printf(" - Last GPS fix: %s, GPS solution type: %d using %d satellites (%d/%d seen/tracked), NACp: %d, est accuracy %.02f m\n", stratuxClock.HumanizeTime(mySituation.LastFixLocalTime), mySituation.Quality, mySituation.Satellites, mySituation.SatellitesSeen, mySituation.SatellitesTracked, mySituation.NACp, mySituation.Accuracy)
log.Printf(" - GPS vertical velocity: %.02f ft/sec; GPS vertical accuracy: %v m\n", mySituation.GPSVertVel, mySituation.AccuracyVert)
}
// Check if we're using more than 95% of the free space. If so, throw a warning (only once).
if !diskUsageWarning && usage.Usage() > 95.0 {
err_p := fmt.Errorf("Disk bytes used = %s (%.1f %%), Disk bytes free = %s (%.1f %%)", humanize.Bytes(usage.Used()), 100*usage.Usage(), humanize.Bytes(usage.Free()), 100*(1-usage.Usage()))
addSystemError(err_p)
diskUsageWarning = true
}
logStatus()
}
}
@ -1261,32 +1167,18 @@ func openReplayFile(fn string) ReadCloser {
var stratuxClock *monotonic
var sigs = make(chan os.Signal, 1) // Signal catch channel (shutdown).
// Close replay log file handles.
func closeReplayLogs() {
if uatReplayWriter != nil {
uatReplayWriter.Close()
}
if esReplayWriter != nil {
esReplayWriter.Close()
}
if gpsReplayWriter != nil {
gpsReplayWriter.Close()
}
if ahrsReplayWriter != nil {
ahrsReplayWriter.Close()
}
if dump1090ReplayWriter != nil {
dump1090ReplayWriter.Close()
}
}
// Graceful shutdown.
func gracefulShutdown() {
// Shut down SDRs.
sdrKill()
// Shut down data logging.
if dataLogStarted {
closeDataLog()
}
//TODO: Any other graceful shutdown functions.
closeReplayLogs()
os.Exit(1)
}
@ -1307,8 +1199,14 @@ func main() {
globalStatus.Version = stratuxVersion
globalStatus.Build = stratuxBuild
globalStatus.Errors = make([]string, 0)
//FlightBox: detect via presence of /etc/FlightBox file.
if _, err := os.Stat("/etc/FlightBox"); !os.IsNotExist(err) {
globalStatus.HardwareBuild = "FlightBox"
debugLogf = debugLog_FB
dataLogFilef = dataLogFile_FB
} else { // if not using the FlightBox config, use "normal" log file locations
debugLogf = debugLog
dataLogFilef = dataLogFile
}
// replayESFilename := flag.String("eslog", "none", "ES Log filename")
@ -1329,9 +1227,9 @@ func main() {
}
// Duplicate log.* output to debugLog.
fp, err := os.OpenFile(debugLog, os.O_CREATE|os.O_WRONLY|os.O_APPEND, 0666)
fp, err := os.OpenFile(debugLogf, os.O_CREATE|os.O_WRONLY|os.O_APPEND, 0666)
if err != nil {
err_log := fmt.Errorf("Failed to open '%s': %s", debugLog, err.Error())
err_log := fmt.Errorf("Failed to open '%s': %s", debugLogf, err.Error())
addSystemError(err_log)
log.Printf("%s\n", err_log.Error())
} else {
@ -1341,9 +1239,9 @@ func main() {
}
log.Printf("Stratux %s (%s) starting.\n", stratuxVersion, stratuxBuild)
constructFilenames()
ADSBTowers = make(map[string]ADSBTower)
ADSBTowerMutex = &sync.Mutex{}
MsgLog = make([]msg, 0)
crcInit() // Initialize CRC16 table.
@ -1361,45 +1259,8 @@ func main() {
globalSettings.ReplayLog = true
}
// Set up the replay logs. Keep these files open in any case, even if replay logging is disabled.
if uatwt, err := openReplay(uatReplayLog, !developerMode); err != nil {
globalSettings.ReplayLog = false
} else {
uatReplayWriter = uatwt
defer uatReplayWriter.Close()
}
// 1090ES replay log.
if eswt, err := openReplay(esReplayLog, !developerMode); err != nil {
globalSettings.ReplayLog = false
} else {
esReplayWriter = eswt
defer esReplayWriter.Close()
}
// GPS replay log.
if gpswt, err := openReplay(gpsReplayLog, !developerMode); err != nil {
globalSettings.ReplayLog = false
} else {
gpsReplayWriter = gpswt
defer gpsReplayWriter.Close()
}
// AHRS replay log.
if ahrswt, err := openReplay(ahrsReplayLog, !developerMode); err != nil {
globalSettings.ReplayLog = false
} else {
ahrsReplayWriter = ahrswt
defer ahrsReplayWriter.Close()
}
// Dump1090 replay log.
if dump1090wt, err := openReplay(dump1090ReplayLog, !developerMode); err != nil {
globalSettings.ReplayLog = false
} else {
dump1090ReplayWriter = dump1090wt
defer dump1090ReplayWriter.Close()
}
// Mark the files (whether we're logging or not).
replayMark(globalSettings.ReplayLog)
//FIXME: Only do this if data logging is enabled.
initDataLog()
initRY835AI()

Wyświetl plik

@ -151,6 +151,8 @@ func handleSituationRequest(w http.ResponseWriter, r *http.Request) {
func handleTowersRequest(w http.ResponseWriter, r *http.Request) {
setNoCache(w)
setJSONHeaders(w)
ADSBTowerMutex.Lock()
towersJSON, err := json.Marshal(&ADSBTowers)
if err != nil {
log.Printf("Error sending tower JSON data: %s\n", err.Error())
@ -158,6 +160,20 @@ func handleTowersRequest(w http.ResponseWriter, r *http.Request) {
// for testing purposes, we can return a fixed reply
// towersJSON = []byte(`{"(38.490880,-76.135554)":{"Lat":38.49087953567505,"Lng":-76.13555431365967,"Signal_strength_last_minute":100,"Signal_strength_max":67,"Messages_last_minute":1,"Messages_total":1059},"(38.978698,-76.309276)":{"Lat":38.97869825363159,"Lng":-76.30927562713623,"Signal_strength_last_minute":495,"Signal_strength_max":32,"Messages_last_minute":45,"Messages_total":83},"(39.179285,-76.668413)":{"Lat":39.17928457260132,"Lng":-76.66841268539429,"Signal_strength_last_minute":50,"Signal_strength_max":24,"Messages_last_minute":1,"Messages_total":16},"(39.666309,-74.315300)":{"Lat":39.66630935668945,"Lng":-74.31529998779297,"Signal_strength_last_minute":9884,"Signal_strength_max":35,"Messages_last_minute":4,"Messages_total":134}}`)
fmt.Fprintf(w, "%s\n", towersJSON)
ADSBTowerMutex.Unlock()
}
// AJAX call - /getSatellites. Responds with all GNSS satellites that are being tracked, along with status information.
func handleSatellitesRequest(w http.ResponseWriter, r *http.Request) {
setNoCache(w)
setJSONHeaders(w)
satelliteMutex.Lock()
satellitesJSON, err := json.Marshal(&Satellites)
if err != nil {
log.Printf("Error sending GNSS satellite JSON data: %s\n", err.Error())
}
fmt.Fprintf(w, "%s\n", satellitesJSON)
satelliteMutex.Unlock()
}
// AJAX call - /getSettings. Responds with all stratux.conf data.
@ -205,11 +221,12 @@ func handleSettingsSetRequest(w http.ResponseWriter, r *http.Request) {
globalSettings.AHRS_Enabled = val.(bool)
case "DEBUG":
globalSettings.DEBUG = val.(bool)
case "DisplayTrafficSource":
globalSettings.DisplayTrafficSource = val.(bool)
case "ReplayLog":
v := val.(bool)
if v != globalSettings.ReplayLog { // Don't mark the files unless there is a change.
globalSettings.ReplayLog = v
replayMark(v)
}
case "PPM":
globalSettings.PPM = int(val.(float64))
@ -256,7 +273,11 @@ func doReboot() {
}
func handleRebootRequest(w http.ResponseWriter, r *http.Request) {
doReboot()
setNoCache(w)
setJSONHeaders(w)
w.Header().Set("Access-Control-Allow-Method", "GET, POST, OPTIONS")
w.Header().Set("Access-Control-Allow-Headers", "Origin, X-Requested-With, Content-Type, Accept")
go delayReboot()
}
// AJAX call - /getClients. Responds with all connected clients.
@ -283,6 +304,11 @@ func handleUpdatePostRequest(w http.ResponseWriter, r *http.Request) {
return
}
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) {
w.WriteHeader(404)
return
}
updateFile := fmt.Sprintf("/root/%s", handler.Filename)
f, err := os.OpenFile(updateFile, os.O_WRONLY|os.O_CREATE, 0666)
if err != nil {
@ -378,6 +404,7 @@ type dirlisting struct {
ServerUA string
}
//FIXME: This needs to be switched to show a "sessions log" from the sqlite database.
func viewLogs(w http.ResponseWriter, r *http.Request) {
names, err := ioutil.ReadDir("/var/log/stratux/")
@ -448,6 +475,7 @@ func managementInterface() {
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("/shutdown", handleShutdownRequest)

Wyświetl plik

@ -26,8 +26,8 @@ type monotonic struct {
func (m *monotonic) Watcher() {
for {
<-m.ticker.C
m.Milliseconds += 50
m.Time = m.Time.Add(50 * time.Millisecond)
m.Milliseconds += 10
m.Time = m.Time.Add(10 * time.Millisecond)
}
}
@ -44,7 +44,7 @@ func (m *monotonic) Unix() int64 {
}
func NewMonotonic() *monotonic {
t := &monotonic{Milliseconds: 0, Time: time.Time{}, ticker: time.NewTicker(50 * time.Millisecond)}
t := &monotonic{Milliseconds: 0, Time: time.Time{}, ticker: time.NewTicker(10 * time.Millisecond)}
go t.Watcher()
return t
}

Wyświetl plik

@ -33,11 +33,12 @@ type networkMessage struct {
}
type networkConnection struct {
Conn *net.UDPConn
Ip string
Port uint32
Capability uint8
messageQueue [][]byte // Device message queue.
Conn *net.UDPConn
Ip string
Port uint32
Capability uint8
messageQueue [][]byte // Device message queue.
MessageQueueLen int // Length of the message queue. For debugging.
/*
Sleep mode/throttle variables. "sleep mode" is actually now just a very reduced packet rate, since we don't know positively
when a client is ready to accept packets - we just assume so if we don't receive ICMP Unreachable packets in 5 secs.
@ -292,6 +293,8 @@ func messageQueueSender() {
outSockets[k] = tmpConn
*/
}
netconn.MessageQueueLen = len(netconn.messageQueue)
outSockets[k] = netconn
}
if stratuxClock.Since(lastQueueTimeChange) >= 5*time.Second {
@ -463,11 +466,11 @@ func ffMonitor() {
addr := net.UDPAddr{Port: 50113, IP: net.ParseIP("0.0.0.0")}
conn, err := net.ListenUDP("udp", &addr)
defer conn.Close()
if err != nil {
log.Printf("ffMonitor(): error listening on port 50113: %s\n", err.Error())
return
}
defer conn.Close()
for {
buf := make([]byte, 1024)
n, addr, err := conn.ReadFrom(buf)

13
main/plugin.go 100644
Wyświetl plik

@ -0,0 +1,13 @@
package main
import (
"time"
)
type StratuxPlugin struct {
InitFunc func() bool
ShutdownFunc func() bool
Name string
Clock time.Time
Input chan string
}

Plik diff jest za duży Load Diff

Wyświetl plik

@ -46,6 +46,11 @@ var UATDev *UAT
// ESDev holds a 1090 MHz dongle object
var ESDev *ES
type Dump1090TermMessage struct {
Text string
Source string
}
func (e *ES) read() {
defer e.wg.Done()
log.Println("Entered ES read() ...")
@ -100,7 +105,8 @@ func (e *ES) read() {
default:
n, err := stdout.Read(stdoutBuf)
if err == nil && n > 0 {
replayLog(string(stdoutBuf[:n]), MSGCLASS_DUMP1090)
m := Dump1090TermMessage{Text: string(stdoutBuf[:n]), Source: "stdout"}
logDump1090TermMessage(m)
}
}
}
@ -114,7 +120,8 @@ func (e *ES) read() {
default:
n, err := stderr.Read(stderrBuf)
if err == nil && n > 0 {
replayLog(string(stderrBuf[:n]), MSGCLASS_DUMP1090)
m := Dump1090TermMessage{Text: string(stderrBuf[:n]), Source: "stderr"}
logDump1090TermMessage(m)
}
}
}
@ -222,6 +229,9 @@ func (u *UAT) sdrConfig() (err error) {
}
log.Printf("\tSetTunerGain Successful\n")
tgain := u.dev.GetTunerGain()
log.Printf("\tGetTunerGain: %d\n", tgain)
//---------- Get/Set Sample Rate ----------
err = u.dev.SetSampleRate(SampleRate)
if err != nil {
@ -419,6 +429,8 @@ func configDevices(count int, esEnabled, uatEnabled bool) {
for i := 0; i < count; i++ {
_, _, s, err := rtl.GetDeviceUsbStrings(i)
if err == nil {
//FIXME: Trim NULL from the serial. Best done in gortlsdr, but putting this here for now.
s = strings.Trim(s, "\x00")
// no need to check if createXDev returned an error; if it
// failed to config the error is logged and we can ignore
// it here so it doesn't get queued up again

Wyświetl plik

@ -16,7 +16,7 @@ import (
"log"
"math"
"net"
//"strconv"
"strconv"
"strings"
"sync"
"time"
@ -81,6 +81,7 @@ type TrafficInfo struct {
Addr_type uint8 // UAT address qualifier. Used by GDL90 format, so translations for ES TIS-B/ADS-R are needed.
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)
Lat float32 // decimal degrees, north positive
Lng float32 // decimal degrees, east positive
@ -95,19 +96,22 @@ type TrafficInfo struct {
Vvel int16 // feet per minute
Timestamp time.Time // timestamp of traffic message, UTC
// Parameters starting at 'Age' are calculated after message receipt.
// Parameters starting at 'Age' are calculated from last message receipt on each call of sendTrafficUpdates().
// Mode S transmits position and track in separate messages, and altitude can also be
// received from interrogations.
Age float64 // seconds ago traffic last seen
Last_seen time.Time // time of last position update, relative to Stratux startup. Used for timing out expired data.
Last_alt time.Time // time of last altitude update, relative to Stratux startup
Last_GnssDiff time.Time // time of last GnssDiffFromBaroAlt update, relative to Stratux startup
Last_GnssDiffAlt int32 // altitude at last GnssDiffFromBaroAlt update
Last_speed time.Time // time of last velocity / track update, relative to Stratux startup
Last_source uint8 // last SDR on which this target was observed
Age float64 // Age of last valid position fix, seconds ago.
AgeLastAlt float64 // Age of last altitude message, seconds ago.
Last_seen time.Time // Time of last position update (stratuxClock). Used for timing out expired data.
Last_alt time.Time // Time of last altitude update (stratuxClock).
Last_GnssDiff time.Time // Time of last GnssDiffFromBaroAlt update (stratuxClock).
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.
Bearing float64 // TO-DO: Bearing in degrees true to traffic from ownship
Distance float64 // TO-DO: Distance to traffic from ownship
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.
//FIXME: Rename variables for consistency, especially "Last_".
}
type dump1090Data struct {
@ -136,10 +140,17 @@ type dump1090Data struct {
Timestamp time.Time // time traffic last seen, UTC
}
type esmsg struct {
TimeReceived time.Time
Data string
}
var traffic map[uint32]TrafficInfo
var trafficMutex *sync.Mutex
var seenTraffic map[uint32]bool // Historical list of all ICAO addresses seen.
var OwnshipTrafficInfo TrafficInfo
func cleanupOldEntries() {
for icao_addr, ti := range traffic {
if stratuxClock.Since(ti.Last_seen) > 60*time.Second { // keep it in the database for up to 60 seconds, so we don't lose tail number, etc...
@ -157,7 +168,16 @@ func sendTrafficUpdates() {
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.
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))
ti.Distance = dist
ti.Bearing = bearing
}
ti.Age = stratuxClock.Since(ti.Last_seen).Seconds()
ti.AgeLastAlt = stratuxClock.Since(ti.Last_alt).Seconds()
// DEBUG: Print the list of all tracked targets (with data) to the log every 15 seconds if "DEBUG" option is enabled
if globalSettings.DEBUG && (stratuxClock.Time.Second()%15) == 0 {
@ -169,15 +189,21 @@ func sendTrafficUpdates() {
}
// end of debug block
}
ti.Age = stratuxClock.Since(ti.Last_seen).Seconds()
traffic[icao] = ti
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)
}
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.
msg = append(msg, makeTrafficReportMsg(ti)...)
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
OwnshipTrafficInfo = ti
} else {
msg = append(msg, makeTrafficReportMsg(ti)...)
}
}
}
@ -188,10 +214,12 @@ func sendTrafficUpdates() {
// Send update to attached JSON client.
func registerTrafficUpdate(ti TrafficInfo) {
if !ti.Position_valid { // Don't send unless a valid position exists.
return
}
//logTraffic(ti) // moved to sendTrafficUpdates() to reduce SQLite log size
/*
if !ti.Position_valid { // Don't send unless a valid position exists.
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)
}
@ -288,7 +316,7 @@ func makeTrafficReportMsg(ti TrafficInfo) []byte {
// msg[19] to msg[26] are "call sign" (tail).
for i := 0; i < len(ti.Tail) && i < 8; i++ {
c := byte(ti.Tail[i])
if c != 20 && !((c >= 48) && (c <= 57)) && !((c >= 65) && (c <= 90)) && c != 'e' && c != 'u' { // See p.24, FAA ref.
if c != 20 && !((c >= 48) && (c <= 57)) && !((c >= 65) && (c <= 90)) && c != 'e' && c != 'u' && c != 'a' && c != 'r' && c != 't' { // See p.24, FAA ref.
c = byte(20)
}
msg[19+i] = c
@ -346,13 +374,6 @@ func parseDownlinkReport(s string, signalLevel int) {
ti.Tail = tail
}
if globalSettings.DEBUG {
// This is a hack to show the source of the traffic in ForeFlight.
if len(ti.Tail) == 0 || (len(ti.Tail) != 0 && len(ti.Tail) < 8 && ti.Tail[0] != 'U') {
ti.Tail = "u" + ti.Tail
}
}
// Extract emitter category.
if msg_type == 1 || msg_type == 3 {
v := (uint16(frame[17]) << 8) | (uint16(frame[18]))
@ -387,6 +408,28 @@ func parseDownlinkReport(s string, signalLevel int) {
}
}
// This is a hack to show the source of the traffic on moving maps.
if globalSettings.DisplayTrafficSource {
type_code := " "
switch ti.TargetType {
case TARGET_TYPE_ADSB:
type_code = "a"
case TARGET_TYPE_ADSR, TARGET_TYPE_TISB_S:
type_code = "r"
case TARGET_TYPE_TISB:
type_code = "t"
}
if len(ti.Tail) == 0 {
ti.Tail = "u" + type_code
} else if len(ti.Tail) < 7 && ti.Tail[0] != 'e' && ti.Tail[0] != 'u' {
ti.Tail = "u" + type_code + ti.Tail
} else if len(ti.Tail) == 7 && ti.Tail[0] != 'e' && ti.Tail[0] != 'u' {
ti.Tail = "u" + type_code + ti.Tail[1:]
} else if len(ti.Tail) > 1 { // bounds checking
ti.Tail = "u" + type_code + ti.Tail[2:]
}
}
raw_lat := (uint32(frame[4]) << 15) | (uint32(frame[5]) << 7) | (uint32(frame[6]) >> 1)
raw_lon := ((uint32(frame[6]) & 0x01) << 23) | (uint32(frame[7]) << 15) | (uint32(frame[8]) << 7) | (uint32(frame[9]) >> 1)
@ -405,10 +448,13 @@ func parseDownlinkReport(s string, signalLevel int) {
lng = lng - 360
}
}
ti.Lat = lat
ti.Lng = lng
ti.Position_valid = position_valid
if ti.Position_valid {
ti.Lat = lat
ti.Lng = lng
if isGPSValid() {
ti.Distance, ti.Bearing = distance(float64(mySituation.Lat), float64(mySituation.Lng), float64(ti.Lat), float64(ti.Lng))
}
ti.Last_seen = stratuxClock.Time
ti.ExtrapolatedPosition = false
}
@ -555,8 +601,18 @@ func esListen() {
break
}
buf = strings.Trim(buf, "\r\n")
//log.Printf("%s\n", buf)
replayLog(buf, MSGCLASS_ES) // Log the raw message to nnnn-ES.log
// Log the message to the message counter in any case.
var thisMsg msg
thisMsg.MessageClass = MSGCLASS_ES
thisMsg.TimeReceived = stratuxClock.Time
thisMsg.Data = buf
MsgLog = append(MsgLog, thisMsg)
var eslog esmsg
eslog.TimeReceived = stratuxClock.Time
eslog.Data = buf
logESMsg(eslog) // log raw dump1090:30006 output to SQLite log
var newTi *dump1090Data
err = json.Unmarshal([]byte(buf), &newTi)
@ -565,18 +621,19 @@ func esListen() {
continue
}
if (newTi.Icao_addr & 0xFF000000) != 0 { //24-bit overflow is used to signal heartbeat
log.Printf("No traffic last 60 seconds. Heartbeat message from dump1090: %s\n", buf)
continue
if newTi.Icao_addr == 0x07FFFFFF { // used to signal heartbeat
if globalSettings.DEBUG {
log.Printf("No traffic last 60 seconds. Heartbeat message from dump1090: %s\n", buf)
}
continue // don't process heartbeat messages
}
// Log the message to the message counter as a valid ES if it unmarshalles.
var thisMsg msg
thisMsg.MessageClass = MSGCLASS_ES
thisMsg.TimeReceived = stratuxClock.Time
thisMsg.Data = []byte(buf)
MsgLog = append(MsgLog, thisMsg)
if (newTi.Icao_addr & 0x01000000) != 0 { // bit 25 used by dump1090 to signal non-ICAO address
newTi.Icao_addr = newTi.Icao_addr & 0x00FFFFFF
if globalSettings.DEBUG {
log.Printf("Non-ICAO address %X sent by dump1090. This is typical for TIS-B.\n", newTi.Icao_addr)
}
}
icao := uint32(newTi.Icao_addr)
var ti TrafficInfo
@ -589,8 +646,10 @@ func esListen() {
} else {
//log.Printf("New target %X created for ES update\n",newTi.Icao_addr)
ti.Last_seen = stratuxClock.Time // need to initialize to current stratuxClock so it doesn't get cut before we have a chance to populate a position message
ti.Last_alt = stratuxClock.Time // ditto.
ti.Icao_addr = icao
ti.ExtrapolatedPosition = false
ti.Last_source = TRAFFIC_SOURCE_1090ES
}
ti.SignalLevel = 10 * math.Log10(newTi.SignalLevel)
@ -666,6 +725,9 @@ func esListen() {
if valid_position {
ti.Lat = lat
ti.Lng = lng
if isGPSValid() {
ti.Distance, ti.Bearing = distance(float64(mySituation.Lat), float64(mySituation.Lng), float64(ti.Lat), float64(ti.Lng))
}
ti.Position_valid = true
ti.ExtrapolatedPosition = false
ti.Last_seen = stratuxClock.Time // only update "last seen" data on position updates
@ -754,6 +816,9 @@ func esListen() {
ti.Emitter_category = uint8(*newTi.Emitter_category) // validate dump1090 on live traffic
}
if newTi.Squawk != nil {
ti.Squawk = int(*newTi.Squawk) // only provided by Mode S messages, so we don't do this in parseUAT.
}
// Set the target type. DF=18 messages are sent by ground station, so we look at CA
// (repurposed to Control Field in DF18) to determine if it's ADS-R or TIS-B.
if newTi.DF == 17 {
@ -776,19 +841,41 @@ func esListen() {
ti.OnGround = bool(*newTi.OnGround)
}
if newTi.Tail != nil { // DF=17 or DF=18, Type Code 1-4
if (newTi.Tail != nil) && ((newTi.DF == 17) || (newTi.DF == 18)) { // DF=17 or DF=18, Type Code 1-4
ti.Tail = *newTi.Tail
// This is a hack to show the source of the traffic in ForeFlight.
ti.Tail = strings.Trim(ti.Tail, " ")
if globalSettings.DEBUG {
if len(ti.Tail) == 0 || (len(ti.Tail) != 0 && len(ti.Tail) < 8 && ti.Tail[0] != 'E') {
ti.Tail = "e" + ti.Tail
}
ti.Tail = strings.Trim(ti.Tail, " ") // remove extraneous spaces
}
// This is a hack to show the source of the traffic on moving maps.
if globalSettings.DisplayTrafficSource {
type_code := " "
switch ti.TargetType {
case TARGET_TYPE_ADSB:
type_code = "a"
case TARGET_TYPE_ADSR:
type_code = "r"
case TARGET_TYPE_TISB:
type_code = "t"
}
if len(ti.Tail) == 0 {
ti.Tail = "e" + type_code
} else if len(ti.Tail) < 7 && ti.Tail[0] != 'e' && ti.Tail[0] != 'u' {
ti.Tail = "e" + type_code + ti.Tail
} else if len(ti.Tail) == 7 && ti.Tail[0] != 'e' && ti.Tail[0] != 'u' {
ti.Tail = "e" + type_code + ti.Tail[1:]
} else if len(ti.Tail) > 1 { // bounds checking
ti.Tail = "e" + type_code + ti.Tail[2:]
}
}
if newTi.DF == 17 || newTi.DF == 18 {
ti.Last_source = TRAFFIC_SOURCE_1090ES // only update traffic source on ADS-B messages. Prevents source on UAT ADS-B targets with Mode S transponders from "flickering" every time we get an altitude or DF11 update.
}
ti.Timestamp = newTi.Timestamp // only update "last seen" data on position updates
ti.Last_source = TRAFFIC_SOURCE_1090ES
/*
s_out, err := json.Marshal(ti)
if err != nil {
@ -824,6 +911,16 @@ and speed invalid flag is set for headings 135-150 to allow testing of response
func updateDemoTraffic(icao uint32, tail string, relAlt float32, gs float64, offset int32) {
var ti TrafficInfo
// Retrieve previous information on this ICAO code.
if val, ok := traffic[icao]; ok { // if we've already seen it, copy it in to do updates
ti = val
//log.Printf("Existing target %X imported for ES update\n", icao)
} else {
//log.Printf("New target %X created for ES update\n",newTi.Icao_addr)
ti.Last_seen = stratuxClock.Time // need to initialize to current stratuxClock so it doesn't get cut before we have a chance to populate a position message
ti.Icao_addr = icao
ti.ExtrapolatedPosition = false
}
hdg := float64((int32(stratuxClock.Milliseconds/1000)+offset)%720) / 2
// gs := float64(220) // knots
radius := gs * 0.2 / (2 * math.Pi)
@ -862,6 +959,9 @@ func updateDemoTraffic(icao uint32, tail string, relAlt float32, gs float64, off
ti.Emitter_category = 1
ti.Lat = float32(lat + traffRelLat)
ti.Lng = float32(lng + traffRelLng)
ti.Distance, ti.Bearing = distance(float64(lat), float64(lng), float64(ti.Lat), float64(ti.Lng))
ti.Position_valid = true
ti.ExtrapolatedPosition = false
ti.Alt = int32(mySituation.Alt + relAlt)

Wyświetl plik

@ -26,6 +26,10 @@ 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/10-stratux.rules work/bin/
cp image/motd work/bin/
#TODO: librtlsdr.
cd work/

Wyświetl plik

@ -8,7 +8,11 @@ ssh -i ~/.ssh/id_rsa.updates stratux-updates@updates.stratux.me 'ls -1 queue/' |
cd selfupdate
./makeupdate.sh
cd ..
scp -i ~/.ssh/id_rsa.updates work/update*.sh stratux-updates@updates.stratux.me:finished/
for fl in `ls -1 work/update*.sh | cut -d/ -f2`
do
scp -i ~/.ssh/id_rsa.updates work/${fl} stratux-updates@updates.stratux.me:uploading/
ssh -i ~/.ssh/id_rsa.updates stratux-updates@updates.stratux.me "mv uploading/${fl} finished/"
done
cd ..
ssh -i ~/.ssh/id_rsa.updates stratux-updates@updates.stratux.me "rm -f queue/${git_hash}"
done

Wyświetl plik

@ -11,6 +11,10 @@ ln -fs /etc/init.d/stratux /etc/rc6.d/K01stratux
#wifi config
cp -f hostapd.conf /etc/hostapd/hostapd.conf
cp -f hostapd-edimax.conf /etc/hostapd/hostapd-edimax.conf
#WiFi Config Manager
cp -f hostapd_manager.sh /usr/sbin/
#boot config
cp -f config.txt /boot/config.txt
@ -18,13 +22,24 @@ cp -f config.txt /boot/config.txt
#modprobe.d blacklist
cp -f rtl-sdr-blacklist.conf /etc/modprobe.d/
#udev config
cp -f 10-stratux.rules /etc/udev/rules.d
#go setup
cp -f bashrc.txt /root/.bashrc
cp -f stxAliases /root/.stxAliases
# /etc/modules
cp -f modules.txt /etc/modules
#motd
cp -f motd /etc/motd
cp -f dump1090 /usr/bin/
# Web files install.
cd web/ && make stratuxBuild=${stratuxBuild}
cd web/ && make stratuxBuild=${stratuxBuild}
# Remove old Wi-Fi watcher script.
rm -f /usr/sbin/wifi_watch.sh
sed -i "/\bwifi_watch\b/d" /etc/rc.local

Wyświetl plik

@ -3,4 +3,5 @@
rm -rf /root/stratux-update
mkdir -p /root/stratux-update
cd /root/stratux-update
mv -f /var/log/stratux.sqlite /var/log/stratux.sqlite.`date +%s`
rm -f /var/log/stratux.sqlite-wal /var/log/stratux.sqlite-shm

134
test/es_dump_csv.go 100644
Wyświetl plik

@ -0,0 +1,134 @@
package main
import (
"database/sql"
"encoding/csv"
"encoding/json"
"fmt"
_ "github.com/mattn/go-sqlite3"
"os"
"time"
)
type dump1090Data struct {
Icao_addr uint32
DF int // Mode S downlink format.
CA int // Lowest 3 bits of first byte of Mode S message (DF11 and DF17 capability; DF18 control field, zero for all other DF types)
TypeCode int // Mode S type code
SubtypeCode int // Mode S subtype code
SBS_MsgType int // type of SBS message (used in "old" 1090 parsing)
SignalLevel float64 // Decimal RSSI (0-1 nominal) as reported by dump1090-mutability. Convert to dB RSSI before setting in TrafficInfo.
Tail *string
Squawk *int // 12-bit squawk code in octal format
Emitter_category *int
OnGround *bool
Lat *float32
Lng *float32
Position_valid bool
NACp *int
Alt *int
AltIsGNSS bool //
GnssDiffFromBaroAlt *int16 // GNSS height above baro altitude in feet; valid range is -3125 to 3125. +/- 3138 indicates larger difference.
Vvel *int16
Speed_valid bool
Speed *uint16
Track *uint16
Timestamp time.Time // time traffic last seen, UTC
}
func main() {
if len(os.Args) < 2 {
fmt.Printf("es_dump_csv <sqlite file>\n")
return
}
db, err := sql.Open("sqlite3", os.Args[1])
if err != nil {
fmt.Printf("sql.Open(): %s\n", err.Error())
return
}
defer db.Close()
rows, err := db.Query("SELECT Data FROM es_messages")
if err != nil {
fmt.Printf("db.Exec(): %s\n", err.Error())
return
}
defer rows.Close()
csvOut := make([][]string, 0)
for rows.Next() {
var Data string
if err := rows.Scan(&Data); err != nil {
fmt.Printf("rows.Scan(): %s\n", err.Error())
continue
}
var d dump1090Data
err := json.Unmarshal([]byte(Data), &d)
if err != nil {
fmt.Printf("json.Unmarshal(): %s\n", err.Error())
continue
}
r := make([]string, 23)
r[0] = fmt.Sprintf("%06x", d.Icao_addr)
r[1] = fmt.Sprintf("%d", d.DF)
r[2] = fmt.Sprintf("%d", d.CA)
r[3] = fmt.Sprintf("%d", d.TypeCode)
r[4] = fmt.Sprintf("%d", d.SubtypeCode)
r[5] = fmt.Sprintf("%d", d.SBS_MsgType)
r[6] = fmt.Sprintf("%f", d.SignalLevel)
if d.Tail != nil {
r[7] = fmt.Sprintf("%s", *d.Tail)
}
if d.Squawk != nil {
r[8] = fmt.Sprintf("%d", *d.Squawk)
}
if d.Emitter_category != nil {
r[9] = fmt.Sprintf("%d", *d.Emitter_category)
}
if d.OnGround != nil {
r[10] = fmt.Sprintf("%t", *d.OnGround)
}
if d.Lat != nil {
r[11] = fmt.Sprintf("%f", *d.Lat)
}
if d.Lng != nil {
r[12] = fmt.Sprintf("%f", *d.Lng)
}
r[13] = fmt.Sprintf("%t", d.Position_valid)
if d.NACp != nil {
r[14] = fmt.Sprintf("%d", *d.NACp)
}
if d.Alt != nil {
r[15] = fmt.Sprintf("%d", *d.Alt)
}
r[16] = fmt.Sprintf("%t", d.AltIsGNSS)
if d.GnssDiffFromBaroAlt != nil {
r[17] = fmt.Sprintf("%d", *d.GnssDiffFromBaroAlt)
}
if d.Vvel != nil {
r[18] = fmt.Sprintf("%d", *d.Vvel)
}
r[19] = fmt.Sprintf("%t", d.Speed_valid)
if d.Speed != nil {
r[20] = fmt.Sprintf("%d", *d.Speed)
}
if d.Track != nil {
r[21] = fmt.Sprintf("%d", *d.Track)
}
r[22] = fmt.Sprintf("%s", d.Timestamp)
csvOut = append(csvOut, r)
}
w := csv.NewWriter(os.Stdout)
w.WriteAll(csvOut)
if err := rows.Err(); err != nil {
fmt.Printf("rows.Scan(): %s\n", err.Error())
return
}
}

Wyświetl plik

@ -0,0 +1,3 @@
all:
gcc -o metar_to_text src/*.c

Wyświetl plik

@ -0,0 +1,382 @@
/* ref: http://limulus.net/mdsplib */
/*
METAR Decoder Software Package Library: Parses Aviation Routine Weather Reports
Copyright (C) 2003 Eric McCarthy
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
/********************************************************************/
/* */
/* Title: metar.h */
/* Organization: W/OSO242 - GRAPHICS AND DISPLAY SECTION */
/* Date: 19 Jan 1996 */
/* Programmer: CARL MCCALLA */
/* Language: C/370 */
/* */
/* Abstract: METAR Decoder Header File. */
/* */
/* Modification History: */
/* 7 Jul 2001 by Eric McCarthy: Made suitable for */
/* use as header for the metar.a library. */
/* */
/********************************************************************/
/* Used in the METAR structs. */
typedef unsigned short int MDSP_BOOL;
/*********************************************/
/* */
/* RUNWAY VISUAL RANGE STRUCTURE DECLARATION */
/* AND VARIABLE TYPE DEFINITION */
/* */
/*********************************************/
typedef struct runway_VisRange {
char runway_designator[6];
MDSP_BOOL vrbl_visRange;
MDSP_BOOL below_min_RVR;
MDSP_BOOL above_max_RVR;
int visRange;
int Max_visRange;
int Min_visRange;
} Runway_VisRange;
/***********************************************/
/* */
/* DISPATCH VISUAL RANGE STRUCTURE DECLARATION */
/* AND VARIABLE TYPE DEFINITION */
/* */
/***********************************************/
typedef struct dispatch_VisRange {
MDSP_BOOL vrbl_visRange;
MDSP_BOOL below_min_DVR;
MDSP_BOOL above_max_DVR;
int visRange;
int Max_visRange;
int Min_visRange;
} Dispatch_VisRange;
/*****************************************/
/* */
/* CLOUD CONDITION STRUCTURE DECLARATION */
/* AND VARIABLE TYPE DEFINITION */
/* */
/*****************************************/
typedef struct cloud_Conditions {
char cloud_type[5];
char cloud_hgt_char[4];
char other_cld_phenom[4];
int cloud_hgt_meters;
} Cloud_Conditions;
/*****************************************/
/* */
/* WIND GROUP DATA STRUCTURE DECLARATION */
/* AND VARIABLE TYPE DEFINITION */
/* */
/*****************************************/
typedef struct windstruct {
char windUnits[ 4 ];
MDSP_BOOL windVRB;
int windDir;
int windSpeed;
int windGust;
} WindStruct;
/*****************************************/
/* */
/* RECENT WX GROUP STRUCTURE DECLARATION */
/* AND VARIABLE TYPE DEFINITION */
/* */
/*****************************************/
typedef struct recent_wx {
char Recent_weather[ 5 ];
int Bhh;
int Bmm;
int Ehh;
int Emm;
} Recent_Wx;
/***************************************/
/* */
/* DECODED METAR STRUCTURE DECLARATION */
/* AND VARIABLE TYPE DEFINITION */
/* */
/***************************************/
typedef struct decoded_METAR {
char synoptic_cloud_type[ 6 ];
char snow_depth_group[ 6 ];
char codeName[ 6 ];
char stnid[5];
char horiz_vsby[5];
char dir_min_horiz_vsby[3];
char vsby_Dir[ 3 ];
char WxObstruct[10][8];
char autoIndicator[5];
char VSBY_2ndSite_LOC[10];
char SKY_2ndSite_LOC[10];
char SKY_2ndSite[10];
char SectorVsby_Dir[ 3 ];
char ObscurAloft[ 12 ];
char ObscurAloftSkyCond[ 12 ];
char VrbSkyBelow[ 4 ];
char VrbSkyAbove[ 4 ];
char LTG_DIR[ 3 ];
char CloudLow;
char CloudMedium;
char CloudHigh;
char CIG_2ndSite_LOC[10];
char VIRGA_DIR[3];
char TornadicType[15];
char TornadicLOC[10];
char TornadicDIR[4];
char TornadicMovDir[3];
char CHINO_LOC[6];
char VISNO_LOC[6];
char PartialObscurationAmt[2][7];
char PartialObscurationPhenom[2][12];
char SfcObscuration[6][10];
char charPrevailVsby[12];
char charVertVsby[10];
char TS_LOC[3];
char TS_MOVMNT[3];
MDSP_BOOL Indeterminant3_6HrPrecip;
MDSP_BOOL Indeterminant_24HrPrecip;
MDSP_BOOL CIGNO;
MDSP_BOOL SLPNO;
MDSP_BOOL ACFTMSHP;
MDSP_BOOL NOSPECI;
MDSP_BOOL FIRST;
MDSP_BOOL LAST;
MDSP_BOOL SunSensorOut;
MDSP_BOOL AUTO;
MDSP_BOOL COR;
MDSP_BOOL NIL_rpt;
MDSP_BOOL CAVOK;
MDSP_BOOL RVRNO;
MDSP_BOOL A_altstng;
MDSP_BOOL Q_altstng;
MDSP_BOOL VIRGA;
MDSP_BOOL VOLCASH;
MDSP_BOOL GR;
MDSP_BOOL CHINO;
MDSP_BOOL VISNO;
MDSP_BOOL PNO;
MDSP_BOOL PWINO;
MDSP_BOOL FZRANO;
MDSP_BOOL TSNO;
MDSP_BOOL DollarSign;
MDSP_BOOL PRESRR;
MDSP_BOOL PRESFR;
MDSP_BOOL Wshft_FROPA;
MDSP_BOOL OCNL_LTG;
MDSP_BOOL FRQ_LTG;
MDSP_BOOL CNS_LTG;
MDSP_BOOL CG_LTG;
MDSP_BOOL IC_LTG;
MDSP_BOOL CC_LTG;
MDSP_BOOL CA_LTG;
MDSP_BOOL DSNT_LTG;
MDSP_BOOL AP_LTG;
MDSP_BOOL VcyStn_LTG;
MDSP_BOOL OVHD_LTG;
MDSP_BOOL LightningVCTS;
MDSP_BOOL LightningTS;
int TornadicDistance;
int ob_hour;
int ob_minute;
int ob_date;
int minWnDir;
int maxWnDir;
int VertVsby;
int temp;
int dew_pt_temp;
int QFE;
int hectoPasc_altstng;
int char_prestndcy;
int minCeiling;
int maxCeiling;
int WshfTime_hour;
int WshfTime_minute;
int min_vrbl_wind_dir;
int max_vrbl_wind_dir;
int PKWND_dir;
int PKWND_speed;
int PKWND_hour;
int PKWND_minute;
int SKY_2ndSite_Meters;
int Ceiling;
int Estimated_Ceiling;
int SNINCR;
int SNINCR_TotalDepth;
int SunshineDur;
int ObscurAloftHgt;
int VrbSkyLayerHgt;
int Num8thsSkyObscured;
int CIG_2ndSite_Meters;
int snow_depth;
int BTornadicHour;
int BTornadicMinute;
int ETornadicHour;
int ETornadicMinute;
float SectorVsby;
float WaterEquivSnow;
float VSBY_2ndSite;
float prevail_vsbySM;
float prevail_vsbyM;
float prevail_vsbyKM;
float prestndcy;
float precip_amt;
float precip_24_amt;
float maxtemp;
float mintemp;
float max24temp;
float min24temp;
float minVsby;
float maxVsby;
float hourlyPrecip;
float TWR_VSBY;
float SFC_VSBY;
float Temp_2_tenths;
float DP_Temp_2_tenths;
float SLP;
float GR_Size;
double inches_altstng;
Runway_VisRange RRVR[12];
Dispatch_VisRange DVR;
Recent_Wx ReWx[3];
WindStruct winData;
Cloud_Conditions cldTypHgt[6];
} Decoded_METAR;
/********************************************************************/
/* */
/* Title: DcdMETAR */
/* Organization: W/OSO242 - GRAPHICS AND DISPLAY SECTION */
/* Date: 14 Sep 1994 */
/* Programmer: CARL MCCALLA */
/* Language: C/370 */
/* */
/* Abstract: DcdMETAR takes a pointer to a METAR report char- */
/* acter string as input, decodes the report, and */
/* puts the individual decoded/parsed groups into */
/* a structure that has the variable type */
/* Decoded_METAR. */
/* */
/* Input: string - a pointer to a METAR report character */
/* string. */
/* */
/* Output: Mptr - a pointer to a structure that has the */
/* variable type Decoded_METAR. */
/* */
/* Modification History: */
/* 3 Jul 2001 by Eric McCarthy: Added stringCpy */
/* so cosnt char *'s could be passed in. */
/* */
/********************************************************************/
int DcdMETAR( char *string , Decoded_METAR *Mptr );
/********************************************************************/
/* */
/* Title: prtDMETR */
/* Organization: W/OSO242 - GRAPHICS AND DISPLAY SECTION */
/* Date: 15 Sep 1994 */
/* Programmer: CARL MCCALLA */
/* Language: C/370 */
/* */
/* Abstract: prtDMETR prints, in order of the ASOS METAR */
/* format, all non-initialized members of the structure */
/* addressed by the Decoded_METAR pointer. */
/* */
/* External Functions Called: */
/* None. */
/* */
/* Input: Mptr - ptr to a decoded_METAR structure. */
/* */
/* Output: NONE */
/* */
/* Modification History: */
/* None. */
/* */
/********************************************************************/
void prtDMETR( Decoded_METAR *Mptr );
/********************************************************************/
/* */
/* Title: dcdNetMETAR */
/* Date: 24 Jul 2001 */
/* Programmer: Eric McCarthy */
/* Language: C */
/* */
/* Abstract: dcdNetMETAR */
/* The METARs supplied by the NWS server need to */
/* be reformatted before they can be sent through */
/* dcdMETAR. This calls dcdMETAR on the correctly */
/* formated METAR. */
/* */
/* Input: a pointer to a METAR string from a NWS server */
/* */
/* Output: Mptr - a pointer to a structure that has the */
/* variable type Decoded_METAR. */
/* */
/* Modification History: */
/* None. */
/* */
/********************************************************************/
int dcdNetMETAR (char *string, Decoded_METAR *Mptr);
/********************************************************************/
/* */
/* Title: sprint_metar */
/* Date: 24 Jul 2001 */
/* Programmer: Eric McCarthy */
/* Language: C */
/* */
/* Abstract: sprtDMETR */
/* Does what prtDMETR does, but into a string. */
/* */
/* Input: string containing the printout, decoded METAR */
/* */
/* Modification History: */
/* None. */
/* */
/********************************************************************/
void sprint_metar( char *string, Decoded_METAR *Mptr );

Wyświetl plik

@ -0,0 +1,92 @@
/*
METAR Decoder Software Package Library: Parses Aviation Routine Weather Reports
Copyright (C) 2003 Eric McCarthy
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#pragma comment(compiler)
#pragma comment(date)
#pragma comment(timestamp)
#include <stdlib.h>
#pragma title("antoi - char array to integer")
#pragma pagesize (80)
#pragma page(1)
/********************************************************************/
/* */
/* Title: antoi */
/* Date: Jan 28, 1991 */
/* Organization: W/OSO242 - Graphics and Display Section */
/* Programmer: Allan Darling */
/* Language: C/370 */
/* */
/* Abstract: This function will convert a character array */
/* (string) of length (len) into an integer. */
/* The integer is created via a call to the */
/* function atoi. This function extends the */
/* functionality of atoi by removing the */
/* requirement for a sentinal delimited string */
/* as input. */
/* */
/* Input: - Pointer to an array of characters. */
/* - Integer indicating the number of character to include */
/* in the conversion. */
/* */
/* Output:- An integer corresponding to the value in the character */
/* array or MAXNEG (-2147483648) if the function is */
/* unable to acquire system storage. */
/* */
/* Modification History: */
/* None */
/* */
/********************************************************************/
int antoi(char * string, int len)
{
/*******************/
/* local variables */
/*******************/
char * tmpstr;
int i,
retval;
/*****************/
/* function body */
/*****************/
tmpstr = malloc((len+1) * sizeof(char));
if (tmpstr == NULL) return (-2147483648);
for (i = 0; i < len; i++)
tmpstr[i] = string[i];
tmpstr[len] = '\0';
retval = atoi(tmpstr);
free(tmpstr);
return(retval);
} /* end antoi */
#pragma page(1)

Wyświetl plik

@ -0,0 +1,191 @@
/*
METAR Decoder Software Package Library: Parses Aviation Routine Weather Reports
Copyright (C) 2003 Eric McCarthy
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#pragma comment (compiler)
#pragma comment (date)
#pragma comment (timestamp)
#pragma pagesize(80)
#include "local.h" /* standard header file */
#pragma subtitle(" ")
#pragma page(1)
#pragma subtitle("charcmp - characters compare with patterns ")
/********************************************************************/
/* */
/* Title: charcmp */
/* Organization: W/OSO242 - GRAPHICS AND DISPLAY SECTION */
/* Date: 12 Dec 1995 */
/* Programmer: CINDY L. CHONG */
/* Language: C/370 */
/* */
/* Abstract: This function will compare each character in the */
/* string match with each character in the pattern */
/* which is made up of characters. The str can */
/* be longer than the pattern. */
/* */
/* External Functions Called: */
/* None. */
/* */
/* Input: str is a pointer to char */
/* pattern is a pointer to char */
/* */
/* Output: Return true if str matches pattern, */
/* otherwise, return false */
/* */
/* Modification History: */
/* None. */
/* */
/********************************************************************/
#pragma page(1)
MDSP_BOOL charcmp(char *str, char *pattern)
{
/**********************************************************/
/* Loop while str and pattern is not equal to null, then */
/* inscreases str and pattern by one */
/**********************************************************/
for (; *pattern != '\0'; pattern++)
{
if (*str == '\0')
return FALSE;
/************************************************************/
/* If pattern match str, then increase str and jump out the */
/* case and read next char of the str and pattern */
/************************************************************/
if ( isspace(*pattern) )
pattern = nxtalpha(pattern);
switch( *pattern )
{
case 'c':
if ( !isalnum(*str++) )
{
return FALSE;
}
break;
case 'a':
if ( !isalpha(*str) )
{
return FALSE;
}
str++;
break;
case 'n':
if ( !iscntrl(*str++) )
{
return FALSE;
}
break;
case 'd':
if ( !isdigit(*str) )
{
return FALSE;
}
str++;
break;
case 'g':
if ( !isgraph(*str++) )
{
return FALSE;
}
break;
case 'i':
if ( !islower(*str++) )
{
return FALSE;
}
break;
case 'p':
if ( !isprint(*str++) )
{
return FALSE;
}
break;
case 't':
if ( !ispunct(*str++) )
{
return FALSE;
}
break;
case 'w':
if ( !isspace(*str++) )
{
return FALSE;
}
break;
case 'u':
if ( !isupper(*str++) )
{
return FALSE;
}
break;
case 's':
if (*str++ != ' ')
{
return FALSE;
}
break;
case 'm':
if ( !isspace(*str) )
{
return FALSE;
}
else
{
while ( isspace(*str) )
str++;
}
break;
case '\'':
pattern++;
if (*pattern != *str)
{
return FALSE;
}
pattern++;
str++;
break;
default:
return FALSE;
} /* end switch */
} /* end for */
return (TRUE);
}

Wyświetl plik

@ -0,0 +1,685 @@
/*
METAR Decoder Software Package Library: Parses Aviation Routine Weather Reports
Copyright (C) 2003 Eric McCarthy
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "metar_structs.h"
#ifdef SYNOPTIC
char *BldSynop( Decoded_METAR * , char * );
/*char *Sec0MeSm(Decoded_METAR *);*/
/*char *Sec1MeSm(Decoded_METAR *, char *);*/
/*char *Sec3MeSm(Decoded_METAR *, char *);*/
/*char *Sec5MeSm(Decoded_METAR *, char *);*/
#endif
void prtDMETR( Decoded_METAR *);
int DcdMETAR( char *, Decoded_METAR * );
#pragma page(1)
#pragma subtitle(" ")
#pragma subtitle("subtitle - description ")
/********************************************************************/
/* */
/* Title: dRVMETAR */
/* Organization: W/OSO242 - GRAPHICS AND DISPLAY SECTION */
/* Date: 28 Oct 1994 */
/* Programmer: CARL MCCALLA */
/* Language: C/370 */
/* */
/* Abstract: DRVMETAR is a main routine that acts a driver */
/* for testing the METAR Decoder function. */
/* */
/* External Functions Called: */
/* None. */
/* DcdMETAR */
/* prtDcdMetar */
/* Sec0MTSm */
/* Sec1MTSm */
/* */
/* Input: None */
/* */
/* Output: None */
/* */
/* Modification History: */
/* None. */
/* */
/********************************************************************/
#pragma page(1)
main()
{
static char *string[] =
{
"KMKG 18022G29KT 3SM BR BKN018 BR 24/22 A2995 RMK A02 VIS 2",
"KPIT 132351Z 33013KT 4SM +TSRA BR BKN018CB OVC031 12/11 A2977 RMK "
"AO2 PK WND 31041/2305 WSHFT 2300 PRESSRR SLP090 FRQ LTGCGCC OHD "
"TS OHD MOV E CB OHD MOV E 8/3// P0051 60052 T01170111 10222 20122 "
"53030",
"KCAK 132351Z 28016G22KT 10SM BKN021 OVC030 11/09 A2981 RMK AO2 "
"TSE00RAE10 PRESRR SLP093 TS MOV NE CIG RGD 8/5// P0002 60066 "
"T01110094 10217 20111 51053",
"KBUF 132354Z 21007KT 3SM +TSRA BR FEW009 OVC 12/11 A2959 RMK "
"AO2 PRESFR SLP021 8/9// TS ALQDS MOV E OCNL LTGICCCCG P0031 "
"60073 T01170111 10233 20111 50000 0",
"KPIT 132356Z 32012G21KT 4SM TSRA BR BKN018CB OVC031 12/11 A2978 "
"RMK AO2 WSHFT 2338 PRESFR FRQ LTGCGCC OHD TS OHD MOV E CB OHD MOV "
"E P0001",
"KCAK 132358Z 28015G22KT 10SM BKN013 OVC023 11/10 A2982 RMK AO2",
"KBUF 140001Z 22008KT 3SM +TSRA BR BKN009 BKN013 OVC022 12/12 A2959 "
"RMK AO2 P0003",
"KRIL 031853Z AUTO 33008KT 10SM SCT022 BKN032 OVC060 07/01 A3004 "
"RMK AO2 SLP157 T00720006 TSNO",
"METAR KCLE 091657Z COR 35021KT 3SM -PL SHPL VV004 M03/M04 A2964 "
"RMK VIS S M1/4=",
"METAR KCLE 091657Z COR 35021KT 3SM -PE SHPE VV004 M03/M04 A2964 "
"RMK VIS S M1/4=",
"METAR KCLE 091657Z COR 35021KT 3SM -PE TSPL VV004 M03/M04 A2964 "
"RMK VIS S M1/4=",
"METAR KCLE 091657Z COR 35021KT 3SM -PL TSPE VV004 M03/M04 A2964 "
"RMK VIS S M1/4=",
"KMLB 200450Z 18006KT 7SM OVC100 23/22 A2986 RMK FQT LTGIG W-N",
"KMLB 200450Z 18006KT 7SM OVC100 23/22 A2986 RMK FQT LTGIG W-N=",
"KMLB 200450Z 18006KT 7SM OVC100 23/22 A2986 RMK FRQ LTGIC NW",
"KMLB 200450Z 18006KT 7SM OVC100 23/22 A2986 RMK FRQ LTGCC NW=",
"SPECI KEKO 151609Z 00000KT 5SM BR FEW003 SCT013 M04/M06 A3018 "
"RMK VIS N-NE M1/4",
"KPIT 1935Z 22015G25KT 1 3/4SM R22L/2700FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB 18/MM A2992",
"KPIT 1935Z 22015G25KT 1 3/4SM R22L/2700FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB MM/M12 A2992",
"METAR KLAX 281156Z AUTO VRB100G135KT 130V210 3 9999 "
"R15L/0500FT R22L/2700FT R16/1200FT R34/1000V1600FT R01L/P6000FT FC "
"+TS VCTS FEW/// SCT000 BKN050 SCT150 OVC250 3/M1 A2991 RMK "
"TORNADO B13 DSNT NE A01 PK WND 18515/45 "
"WSHFT 1350 FROPA TWR VIS 1 1/2 SFC VIS 1/4 VIS 1/4V1 1/4 "
"VIS 2 1/2 RWY11 "
"DVR/1000V1600FT "
"SHRAB05E30SHSNB20E55 FZDZB1057E1059 CIG 1000V1500 CIG 020 RWY11 "
"PRESFR PRESRR SLP013 FG FEW/// HZ SCT000 VIS NW 2 1/2 GR 3/4 "
"VIRGA SE -XRAFG3 CIGE005 BKN014 V OVC "
"FU BKN020 NOSPECI LAST 8/365 SNINCR 2/10 4/178 "
"933125 98096 P0125 60225 70565 "
"T00261015 10369 21026 "
"404800360 52101 VISNO RWY05 CHINO RWY27 PNO RVRNO "
"PWINO FZRANO TSNO $",
"METAR KAFF 091657Z COR 35021KT 3SM -SG BR VV004 M03/M04 A2964 "
"RMK SLP046 ESTMD SLP VIS SW-NW 2 "
"PWINO FZRANO TSNO $",
"METAR KAFF 091657Z COR 35021KT 3SM -SG BR VV004 M03/M04 A2964 "
"RMK SLP046 ESTMD SLP VIS SW-NW 2 1/2 "
"PWINO FZRANO TSNO $",
"METAR KAFF 091657Z COR 35021KT 3SM -SG BR VV004 M03/M04 A2964 "
"RMK SLP046 ESTMD SLP VIS SW-NW 2",
"METAR KAFF 091657Z COR 35021KT 3SM -SG BR VV004 M03/M04 A2964 "
"RMK SLP046 ESTMD SLP VIS SW-NW 2 1/2=",
"METAR KAFF 091657Z COR 35021KT 3SM -SG BR VV004 M03/M04 A2964 "
"RMK SLP046 ESTMD SLP VIS SW-NW 2",
"METAR KAFF 091657Z COR 35021KT 3SM -SG BR VV004 M03/M04 A2964 "
"RMK CIG 003V026 SLP046 ESTMD SLP VIS SW-NW 2",
"METAR KAFF 091657Z COR 35021KT 3SM -SG BR VV004 M03/M04 A2964 "
"RMK VIS S 2",
"SPECI KEKO 151609Z 00000KT 5SM BR FEW003 SCT013 M04/M06 A3018 "
"RMK VIS N-NE 1",
"KPIT 1935Z 22015G25KT 1 3/4SM R22L/2700FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB 18/MM A2992",
"KPIT 1935Z 22015G25KT 1 3/4SM R22L/2700FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB MM/M12 A2992",
"KPIT 1935Z 22015G25KT 1 3/4SM R22L/2700FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB M18/MM A2992",
"METAR KAFF 091657Z COR 35021KT 3SM -SG BR VV004 M03/M04 A2964 "
"RMK CIG 003V026 SLP046 ESTMD SLP VIS SW-NW 2=",
"METAR KAFF 091657Z COR 35021KT 3SM -SG BR VV004 M03/M04 A2964 "
"RMK VIS S 2=",
"SPECI KEKO 151609Z 00000KT 5SM BR FEW003 SCT013 M04/M06 A3018 "
"RMK VIS N-NE 1=",
"METAR KAFF 091657Z COR 35021KT 3SM -SG BR VV004 M03/M04 A2964 "
"RMK SLP046 ESTMD SLP VIS SW-NW 2",
"METAR KAFF 091657Z COR 35021KT 3SM -SG BR VV004 M03/M04 A2964 "
"RMK CIG 003V026 SLP046 ESTMD SLP VIS SW-NW 2",
"METAR KAFF 091657Z COR 35021KT 3SM -SG BR VV004 M03/M04 A2964 "
"RMK VIS S 2",
"SPECI KEKO 151609Z 00000KT 5SM BR FEW003 SCT013 M04/M06 A3018 "
"RMK VIS N-NE 1",
"METAR KAFF 091657Z COR 35021KT 3SM -SG BR VV004 M03/M04 A2964 "
"RMK SLP046 ESTMD SLP VIS SW 2",
"METAR KAFF 091657Z COR 35021KT 3SM -SG BR VV004 M03/M04 A2964 "
"RMK CIG 003V026 SLP046 ESTMD SLP VIS NW 2",
"METAR KAFF 091657Z COR 35021KT 3SM -SG BR VV004 M03/M04 A2964 "
"RMK VIS S 2",
"SPECI KEKO 151609Z 00000KT 5SM BR FEW003 SCT013 M04/M06 A3018 "
"RMK VIS NE 1",
"KPIT 1935Z 22015G25KT 1/8SM R22L/2700FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB 18/12 A2992",
"KPIT 1935Z 22015G25KT 6SM R22L/2700FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB M12/M18 A2992",
"KPIT 1935Z 22015G25KT 8SM R22L/2700FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB M18/12 A2992",
"KPIT 1935Z 22015G25KT 9SM R22L/2700FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB 18/M01 A2992",
"KPIT 1935Z 22015G25KT 1 3/4SM R22L/2700FT "
"TSRA -DZ FG +SNPE SCT005TCU BKN010ACSL OVC250CB MM/12 A2992",
"KPIT 1935Z 22015G25KT 1 3/4SM R22L/2700FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB 18/MM A2992",
"KPIT 1935Z 22015G25KT 1 3/4SM R22L/2700FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB MM/M12 A2992",
"KPIT 1935Z 22015G25KT 1 3/4SM R22L/2700FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB M18/MM A2992",
"KPIT 1935Z 22015G25KT 1 3/4SM R22L/2700FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB MM/MM A2992",
"SPECI KGFI 041430Z 18045G56KT M1/4SM R15/0200FT FC +TS VV010 20/18 "
"A2900 RMK A02A PK WND 18056/28 OCNL LTG AP "
"RAB15E25TSB20 FCB1430 PRESFR "
"SLP 701 P 0254 T01990182",
"METAR KLAX 281156Z AUTO VRB100G135KT 130V210 3 9999 "
"R15L/0500FT R22L/2700FT R16/1200FT R34/1000V1600FT R01L/P6000FT FC "
"+TS VCTS FEW/// SCT000 BKN050 SCT150 OVC250 3/M1 A2991 RMK "
"TORNADO B13 DSNT NE A01 PK WND 18515/45 "
"WSHFT 1350 FROPA TWR VIS 1 1/2 SFC VIS 1/4 VIS 1/4V1 1/4 "
"VIS 2 1/2 RWY11 "
"DVR/1000V1600FT "
"SHRAB05E30SHSNB20E55 FZDZB1057E1059 CIG 1000V1500 CIG 020 RWY11 "
"PRESFR PRESRR SLP013 FG FEW/// HZ SCT000 VIS NW 2 1/2 GR 3/4 "
"VIRGA SE -XRAFG3 CIGE005 BKN014 V OVC "
"FU BKN020 NOSPECI LAST 8/365 SNINCR 2/10 4/178 "
"933125 98096 P0125 60225 70565 "
"T00261015 10369 21026 "
"404800360 52101 VISNO RWY05 CHINO RWY27 PNO RVRNO "
"PWINO FZRANO TSNO $",
"KP88 1919Z 09001KT 14/03 RMK AO / PKWND 002/RNO 158 Z T01440034",
"K40B 1924Z 29004KT 15/M07 RMK AO PKWND 011/RM MV263 T01501072",
"SPECI KGFI 041430Z COR 18045G56KT "
"M1/4SM R15/0200FT R01L/0600V1000FT R01L/M0600FT R27/P6000FT "
"+FC +TS -FZDZ VV010 04/M02 "
"A2900 RMK TORNADO B13 6 NE A02A PK WND 18056/28 WSHFT 30 FROPA "
"TWR VIS 1 1/2 VIS NE 2 1/2 VIS 2 1/2 RWY11 DVR/0600V1000FT "
"OCNL LTGICCG OVHD RAB15E25 TSB20 FCB1430 TS SE MOV NE GR 1 3/4 "
"VIRGA SW CIG 005V010 FG SCT000 BKN014 V OVC CB DSNT W "
"CIG 002 RWY11 PRESFR PRESRR "
"SLP701 ACFT MSHP NOSPECI SNINCR 2/10 FIRST "
"P0254 60217 70125 4/021 933036 8/903 98096 T00261015 "
"11021 21001 401120084 52032RVRNO PWINO PNO FZRANO TSNO "
"VISNO RWY06 CHINO RWY12 $",
"KPHX 281156Z 12004KT 16KM CLR 15/05 A2996 RMK AOA SLP135 T01500050 "
"10250 20150 53006",
"KFCA 281156Z 30003KT 10SM CLR 06/02 A3009 RMRK AO TNO $ SLP191 "
"T00610023 10167 20056 53003",
"KAST 281156Z 00000KT 10SM BKN095 09/08 A2997 REMARK AOA SLP150 "
"T00940084 10161 20094 52005 ",
"KHVR 281156Z 03003KT 10SM OVC020 09/07 A3010 REMARKS AO TNO ZRNO "
"$ SLP194 T00940073 10156 20089 51005",
"KGGW 281156Z 35006KT 5SM BR OVC010 10/09 A3003 RMK AOA $ SLP177 "
"70003 T01000095 10156 20110 53008",
"KELY 1153Z AUTO 14004KT 10SM SCT075 01/M01 A3011 RMK AOA TNO ZRNO "
"SLP171 70001 T00061011 10139 21006 51005",
"KFLG 281156Z 29006KT 10SM CLR 04/M01 A3012 RMK AO TNO SLP147 "
"T00391011 21006 51004",
"KGTF 281156Z 27005KT 7SM BKN080 04/04 A3010 RMK AOA SLP205 "
"T00440045 10117 20039 51006",
"KHLN 281156Z AUTO 27005KT 10SM OVC023 07/05 A3011 RMK AOA OVC V "
"BKN $ SLP202 60000 70001 T00670050 10122 20061 53003",
"K13A 1918Z 20011KT 26/M06 RMK AO PKWND 020/RNO 644V264 T02611061",
"KGGW 1756Z 33018KT 10SM OVC015 M03/M06 A3041 RMK AOA SLP338 "
"4/007 60002 T10281055 11028 21072 51009",
"KPHX 1756Z 130004KT 10SM CLR 18/M03 A3001 RMK AOA SLP154 "
"T01781033 10178 20067 58007",
"KFCA 1756Z 29005KT 10SM CLR 05/M11 A3049 RMK AOA TNO SLP352 "
"T00501111 10050 21044 50004",
"KAST 1756Z 01006KT 10SM CLR 11/04 A3047 RMK AOA SLP316 "
"T01110045 10111 20000 50002",
"KHVR 1756Z 31007KT 5SM -SN SCT011 BKN024 OVC030 M05/M08 A3056 "
"RMK AOA 933004 "
"BKN V SCT TNO P0000 $ SLP389 4/015 60002 "
"T10501077 11050 21078 51010",
"KELY 1753Z 34010KT 10SM CLR 01/M07 A3022 RMK AOA TNO FZRNO "
"SLP240 T00111066 10011 21078 58007",
"KFLG 1756Z 07006KT 10SM CLR 06/M12 A3009 RMK AO TNO FZRNO "
"SLP178 T00561122 10061 21100 58005",
"KGTF 1756Z 35010KT 1/2SM -SN FG VV09 M06/M08 A3051 RMK AOA "
"933004 SFC VSBY 3/4 "
"P0009 SLP393 60010 T10611077 11044 21067 53013",
"KHLN 1756Z 35012KT 10SM SCT032 OVC060 M02/M09 A3048 RMK AOA "
"SLP369 60000 T10171094 11017 21061 53006",
"KAST 1756Z 01006KT 10SM CLR 11/04 A3047 RMK AOA SLP316 61104 "
"71235 T01110045 10111 20000 401720056 58002",
"METAR KLAX 04281156Z AUTO VRB100G135KT 130V210 3 1/2SM "
"R15L/0500FT R22L/2700FT R16/1200FT R34/1000V1600FT R01L/P6000FT FC "
"+TS BLPY FEW000 BKN050 SCT150 OVC250 3/M1 A2991 RMK "
"TORNADO B13 DSNT NE A02 PK WND 18515/45 "
"WSHFT 1350 FROPA TWR VIS 1 1/2 SFC VIS 1/4 VIS 1/4V1 1/4 "
"VIS 2 1/2 RWY11 OCNL LTG VCY STN "
"RAB1030E1145 FZDZE56 BLPYE57 CIG 1000V1500 CIG 020 RWY11 "
"PRESFR PRESRR SLP013 FG FEW000 VIS NW2 1/2 GR 3/4 "
"VIRGA SE -XRAFG3 CIGE005 BKN014 V OVC "
"FU BKN020 NOSPECI LAST 8/365 SNINCR 2/10 4/178 "
"933125 98096 P0125 60225 70565 "
"T00261015 10369 21026 "
"404800360 52101 PWINO FZRANO TSNO $",
"METAR KGFI 041356Z AUTO 17012KT 130V210 3 1/2SM R15L/0500FT -RA "
"SCT050 OVC110 26/18 A2991 RMK FUNNEL CLOUDS A02 RAB30 "
"SLP 101 GR M1/4 VIRGA SCT V BKN P 0010 T02640178",
"METAR KGFI 041356Z AUTO 05008KT 10SM R15L/P6000FT CLR A2991 "
"RMK WATERSPOUTS VCY STN NW A02 SLP 101 10288 20243 52021 $ ",
"SPECI KGFI 041420Z AUTO 18030KT 3 1/2SM RVRNO TS -RA BKN008 OVC060 "
"26/22 A2991 RMK A02 RA15TSB20 PRESFR SLP 101 P 0000 T02640218",
"KABE 281900Z NIL",
"METAR KPIT NIL",
"METAR KCLE 04281156Z 170100G135KT 110V180 M1/4SM "
"R01L/P6000FT +TSSHRA VCFG "
"BKN025 SCT100 OVC200 M26/ A2991 RMK PK WND 18515/45 A02 "
"WSHFT 1350 TWR VIS 1 1/2 SFC VIS 1/4 VIS 1/4V1 1/4 "
"CIG 1000V1500 PRESFR FRQ LTG CG NW "
"RAB1030E1145 FZDZE56 PRESRR SLP135 GS "
"T1263 "
"VIRGA NW 8/365 4/178 P 0125 60225 7//// 70565 10369 21026 "
"404800360 52101 PWINO FZRANO TSNO $",
"METAR KPHL 040256Z AUTO 170100G135KT 130V210 1/2SM "
"R15L/0500FT R22L/2700FT R16/1200FT R34/1000V1600FT R01L/P6000FT "
"FC +TS BKN050 SCT150 OVC250 M26/ A2991 RMK A02 PK WND 185150/1345 "
"WSHFT 1350 TWR VIS 1 1/2 SFC VIS 1/4 VIS 1/4V1 1/4 LTG DSNT "
"RAB1030E1145 FZDZE56 CIG 1000V1500 PRESFR PRESRR SLP037 GR 2 3/4 "
"VIRGA E 8/365 4/178 P 0125 70565 21026 T0263 10369 60225 "
"404800360 52101 PWINO FZRANO TSNO $",
"SPECI KGFI 041420Z AUTO 18030KT 2 1/2SM RVRNO TS -RA BKN008 "
"OVC060 25/22 A2991 RMK A02 LTG DSNT W "
"RAB15TSB20 PRESFR SLP101 P 0000 "
"254/218",
"METAR KGFI 041356Z AUTO 170100G135KT 130V210 3 1/2SM "
"R15L/0500FT R22L/2700FT R16/1200FT R34/1000V1600FT R01L/P6000FT "
"FC +TS BKN050 SCT150 OVC250 M26/ A2991 RMK A02 PK WND 185150/1345 "
"WSHFT 1350 TWR VIS 1 1/2 SFC VIS 1/4 VIS 1/4V1 1/4 "
"RAB1030E1145 FZDZE56 CIG 1000V1500 PRESFR PRESRR SLP997 GR M1/4 "
"VIRGA SE 8/365 4/178 P 0125 6//// 60225 70565 T0263 10369 21026 "
"404800360 52101 PWINO FZRANO TSNO $",
"METAR KGFI 041356Z AUTO 170100G135KT 130V210 3 1/2SM "
"R15L/0500FT R22L/2700FT R16/1200FT R34/1000V1600FT R01L/P6000FT "
"FC +TS BKN050 SCT150 OVC250 M26/ A2991 RMK A02 PK WND 185150/1345 "
"WSHFT 1350 TWR VIS 1 1/2 SFC VIS 1/4 VIS 1/4V1 1/4 "
"RAB1030E1145 FZDZE56 CIG 1000V1500 PRESFR PRESRR SLP997 GR 25 "
"VIRGA 35 8/365 4/178 P 0125 6//// 60225 70565 T0263 10369 21026 "
"VIRGA 35 8/365 4/178 P 0125 21026 70565 10369 60225 T0263 21026 "
"404800360 52101 PWINO FZRANO TSNO $",
"METAR KGFI 041356Z AUTO 170100G135KT 130V210 3 1/2SM "
"R15L/0500FT R22L/2700FT R16/1200FT R34/1000V1600FT R01L/P6000FT "
"FC +TS BKN050 SCT150 OVC250 3/M1 A2991 RMK A02 PK WND 18515/45 "
"WSHFT 1350 TWR VIS 1 1/2 SFC VIS 1/4 VIS 1/4V1 1/4 "
"RAB1030E1145 FZDZE56 CIG 1000V1500 PRESFR PRESRR SLP997 GR 25 "
"VIRGA 35 8/365 4/178 P 0125 60225 70565 T00261015 10369 21026 "
"404800360 52101 PWINO FZRANO TSNO $",
"METAR KGFI 041356Z AUTO 170100G135KT 130V210 3 1/2SM "
"R15L/0500FT R22L/2700FT R16/1200FT R34/1000V1600FT R01L/P6000FT "
"FC +TS BKN050 SCT150 OVC250 3/M1 A2991 RMK A02 PK WND 185150/1345 "
"WSHFT 1350 TWR VIS 1 1/2 SFC VIS 1/4 VIS 1/4V1 1/4 "
"RAB1030E1145 FZDZE56 CIG 1000V1500 PRESFR PRESRR SLP997 GR 25 "
"VIRGA 35 8/365 4/178 P 0125 60225 70565 T00261015 10369 21026 "
"404800360 52101 PWINO FZRANO TSNO",
"METAR KGFI 041356Z AUTO 05008KT 10SM R15L/P6000FT CLR A2991 RMK "
"A02 SLP 101 10288 20243 52021",
"SPECI DGFI 041430Z 18045G56KT M1/4SM R15/0200FT FC +TS VV010 20/18 "
"M20/M18 A2900 RMK A02A PK WND 18056/28 RAB15E25TSB20 FCB1430 PRESFR "
"SLP 701 P 0254 M199/M182",
"SPECI DGFI 041430Z 18045G56KT M1/4SM R15/0200FT FC +TS VV010 20/18 "
"M20/M18 A2900 RMK A02A PK WND 18056/28 RAB15E25TSB20 FCB1430 PRESFR "
"SLP 701 P 0254 M199/182",
"SPECI DGFI 041430Z 18045G56KT M1/4SM R15/0200FT FC +TS VV010 20/18 "
"M20/M18 A2900 RMK A02A PK WND 18056/28 RAB15E25TSB20 FCB1430 PRESFR "
"SLP 701 P 0254 199/M182",
"METAR APIT 171755Z AUTO 22015G25KT 1 3/4SM R22L/2700FT R16/1200FT "
"R34/1000V1600FT R01L/P6000FT R04RR/900FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB 18/16 A2992 "
"RMK 4/369 58033 6003/ TWELVE 70125 10039 20029 410840112 "
"PCPN 0009 8/563 WSHFT 1715 PK WND 2032/1725 "
"CIG 20V25 WND 12V25 TWR VIS 2 1/2 "
"SFC VIS 1 1/2 VIS 1 1/2V2 SLP875 SGB1213E1225",
"NZWN 1700Z 35030G49KT 320V030 20KM 02 5SC021 7SC046 12/08 "
" Q0994.2 TEMPO 6000 RA 5ST012 2CB015 RMK SLP056 "
"RAE0123",
"SPECI APIT 171755Z 22015G25KT 1 3/4SM R22L/2700FT R16/1200FT "
"R34/1000V1600FT R01L/P6000FT R04RR/900FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB 18/16 A2992 "
"RMK 58033 6003/ TWELVE 70125 8/321 10039 20029 410840112 "
"PCPN 0009 WSHFT 1715 PK WND 2032/1725 "
"CIG 20V25 WND 12V25 TWR VIS 2 1/2 "
"SFC VIS 1 1/2 VIS 1 SLP875 FGB1713",
"APIT 1755Z 22015G25KT 1 3/4SM R22L/2700FT R16/1200FT "
"R34/1000V1600FT R01L/P6000FT R04RR/900FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB 18/16 A2992 "
"RMK 58033 6003/ TWELVE 70125 10039 20029 410840112 "
"PCPN 0009 WSHFT 1715 PK WND 2032/1725 "
"CIG 20V25 WND 12V25 TWR VIS 2 1/2 "
"SFC VIS 1 1/2 VIS 1V2 SLP875",
"APIT 1755Z 22015G25KT 1 3/4SM R22L/2700FT R16/1200FT "
"R34/1000V1600FT R01L/P6000FT R04RR/900FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB 18/16 A2992 "
"RMK 58033 6003/ TWELVE 70125 10039 20029 410840112 "
"PCPN 0009 WSHFT 1715 PK WND 2032/1725 "
"CIG 20V25 WND 12V25 TWR VIS 2 1/2 "
"SFC VIS 1 1/2 VIS 1 1/2V2 1/2 SLP875",
"APIT 1755Z 22015G25KT 1 3/4SM R22L/2700FT R16/1200FT "
"R34/1000V1600FT R01L/P6000FT R04RR/900FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB 18/16 A2992 "
"RMK 58033 6003/ TWELVE 70125 10039 20029 410840112 "
"PCPN 0009 WSHFT 1715 PK WND 2032/1725 "
"CIG 20V25 WND 12V25 TWR VIS 2 1/2 "
"SFC VIS 1 1/2 VIS 1V2 1/2 SLP875",
"EGPF 1720Z 00000KT 9999 -SHRA STC014 SCT020CB BNK024 12/09 "
"Q1003 NOSIG",
"NZAA 1700Z 03010KT 30KM 03 5CU022 7SC035 11/07 Q1006.5 NOSIG",
"NZWN 1700Z 35030G49KT 320V030 20KM 02 5SC021 7SC046 12/08 "
" Q0994.2 TEMPO 6000 RA 5ST012 2CB015 RMK KAUKAU 30050KT",
"DGAA 1800Z 22012KT 9999 SCT009 BKN120 25/21 Q1015",
"DAAT 1830Z 30010KT CAVOK 29/06 Q1019",
"GQPP 1800Z 34023KT 3000 DRSA SKC 24/20 Q1011 NSG",
"DAAG 1830Z 06006KT 9999 SCT020 25/22 Q1015",
"DABB 1830Z 04010KT 9999 SCT030TCU SCT033CB 27/18 Q1017",
"DABC 1830Z 00000KT 9999 SCT026TCU SCT036CB 22/18 Q1020 RETS",
"NZAA 1700Z 03010KT 30KM 03 5CU022 7SC035 11/07 Q1006.5 NOSIG",
"NZWN 1700Z 35030G49KT 320V030 20KM 02 5SC021 7SC046 12/08 "
" Q0994.2 TEMPO 6000 RA 5ST012 2CB015 RMK K",
"NZWN 1700Z 35030G49KT 320V030 20KM 02 5SC021 7SC046 12/08 "
" Q0994.2 TEMPO 6000 RA 5ST012 2CB015 RMK KAUKAU 30050KT",
"DGAA 1800Z 22012KT 9999 SCT009 BKN120 25/21 Q1015",
"GFLL 1900Z NIL",
"GOOY 1800Z 03006G17KT 340V080 6000 TSRA BKN016 BKN030CB "
"BKN133 26/23 Q1013 NOSIG",
"GCXO 1930Z 32018KT 8000 SCT003 SCT007 18/16 Q1019",
"APIT 1755Z 22015G25KT 1 3/4SM R22L/2700FT R16/1200FT "
"R34/1000V1600FT R01L/P6000FT R04RR/900FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB 18/16 A2992 "
"RMK 58033 6003/ TWELVE 70125 10039 20029 410840112 "
"PCPN 0009 WSHFT 1715 PK WND 2032/1725 "
"CIG 20V25 WND 12V25 TWR VIS 2 1/2 "
"SFC VIS 1 1/2 VIS 1 1/2V2",
"BPIT 1755Z 22015G25KT 1 3/4SM R22L/2700FT R16/1200FT "
"R34/1000V1600FT R01L/P6000FT R04RR/900FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB 18/16 A2992 "
"RMK 58033 6003/ TWELVE 70125 10039 20029 410840112 "
"PCPN 0009 WSHFT 1715 PK WND 2032/1725 "
"CIG 20V25 WND 12V25 TWR VIS 2 1/2 "
"SFC VIS 1 1/2 VIS 1V2",
"CPIT 1755Z 22015G25KT 1 3/4SM R22L/2700FT R16/1200FT "
"R34/1000V1600FT R01L/P6000FT R04RR/900FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB 18/16 A2992 "
"RMK 58033 6003/ TWELVE 70125 10039 20029 410840112 "
"PCPN 0009 WSHFT 1715 PK WND 2032/1725 "
"CIG 20V25 WND 12V25 TWR VIS 2 1/2 "
"SFC VIS 1 1/2 VIS 1V2 1/2",
"DPIT 1755Z 22015G25KT 1 3/4SM R22L/2700FT R16/1200FT "
"R34/1000V1600FT R01L/P6000FT R04RR/900FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB 18/16 A2992 "
"RMK 58033 6003/ TWELVE 70125 10039 20029 410840112 "
"PCPN 0009 WSHFT 1715 PK WND 2032/1725 "
"CIG 20V25 WND 12V25 TWR VIS 2 1/2 "
"SFC VIS 1 1/2 VIS 1 1/2V2 1/2",
"EPIT 1755Z 22015G25KT 1 3/4SM R22L/2700FT R16/1200FT "
"R34/1000V1600FT R01L/P6000FT R04RR/900FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB 18/16 A2992 "
"RMK 58033 6003/ TWELVE 70125 10039 20029 410840112 "
"PCPN 0009 WSHFT 1715 PK WND 2032/1725 "
"CIG 20V25 WND 12V25 TWR VIS 2 1/2 "
"SFC VIS 1 1/2 VIS 1/2V3/4",
"FPIT 1755Z 22015G25KT 1 3/4SM R22L/2700FT R16/1200FT "
"R34/1000V1600FT R01L/P6000FT R04RR/900FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB 18/16 A2992 "
"RMK 58033 6003/ TWELVE 70125 10039 20029 410840112 "
"PCPN 0009 WSHFT 1715 PK WND 2032/1725 "
"CIG 20V25 WND 12V25 TWR VIS 2 1/2 "
"SFC VIS 1 1/2 VIS 3/4V2 1/2",
"GPIT 1755Z 22015G25KT 1 3/4SM R22L/2700FT R16/1200FT "
"R34/1000V1600FT R01L/P6000FT R04RR/900FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB 18/16 A2992 "
"RMK 58033 6003/ TWELVE 70125 10039 20029 410840112 "
"PCPN 0009 WSHFT 1715 PK WND 2032/1725 "
"CIG 20V25 WND 12V25 TWR VIS 2 1/2 "
"SFC VIS 1 1/2 VIS 3/4V3",
"KPIT 1935Z 22015G25KT 1 3/4SM R22L/2700FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB M18/M16 A2992",
"KPIT 1935Z 22015G25KT 1 3/4SM R22L/2700FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB M18/16 A2992",
"KPIT 1935Z 22015G25KT 1 3/4SM R22L/2700FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB 18/M16 A2992",
"KPIT 1935Z 22015G25KT 1 3/4SM R22L/2700FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB MM/M16 A2992",
"KPIT 1935Z 22015G25KT 1 3/4SM R22L/2700FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB MM/16 A2992",
"KPIT 1935Z 22015G25KT 1 3/4SM R22L/2700FT "
"TSRA -DZ FG +SNPE SCT005 BKN010 OVC250CB M18/MM A2992",
NULL};
/***************************/
/* DECLARE LOCAL VARIABLES */
/***************************/
Decoded_METAR Metar;
Decoded_METAR *Mptr = &Metar;
int j,
ErReturn;
static char *synopRTRN = NULL;
char bltn_prefix[20];
/***************************************************/
/* START BODY OF MAIN ROUTINE FOR CALLING DcdMETAR */
/***************************************************/
j = 0;
while( string[j] != NULL)
{
/*-- PRINT INPUT METAR REPORT ----------------------------*/
printf("\n\nINPUT METAR REPORT:\n\n %s\n\n",string[j] );
/*-- DECODE INPUT REPORT ---------------------------------*/
if ( (ErReturn = DcdMETAR( string[ j ], Mptr )) != 0 )
printf("DcdMETAR: Error Return Number: %d\n",ErReturn);
/*-- PRINT DECODED METAR REPORT ELEMENTS -----------------*/
printf("\n\nFINAL DECODED PRODUCT...\n\n");
prtDMETR( Mptr );
#ifdef OLDSTUFF
/************************************************/
/* Convert Decoded METAR into Synoptic format */
/************************************************/
printf("Just after call to prtDMETR\n");
sprintf( bltn_prefix, "AAXX YYGGi##," );
synopRTRN = BldSynop( Mptr, bltn_prefix );
printf("After BldSynop, SynopRep =:\n%s\n",synopRTRN);
/**********************************************************/
/*-- ENCODE SECTION 0 OF THE SYNTHETIC SYNOPTIC REPORT ---*/
/**********************************************************/
printf("Just before call to Sec0MeSM\n");
if( (synopRTRN = Sec0MeSm( Mptr )) == NULL )
printf("Sec0MeSm returned a NULL pointer\n");
else
printf("After Sec0MeSm: %s\n",synopRTRN);
/**********************************************************/
/*-- ENCODE SECTION 1 OF THE SYNTHETIC SYNOPTIC REPORT ---*/
/**********************************************************/
if( synopRTRN != NULL )
synopRTRN = Sec1MeSm( Mptr,synopRTRN );
printf("After Sec1MeSm: %s\n",synopRTRN);
/**********************************************************/
/*-- ENCODE SECTION 3 OF THE SYNTHETIC SYNOPTIC REPORT ---*/
/**********************************************************/
if( synopRTRN != NULL )
synopRTRN = Sec3MeSm( Mptr,synopRTRN );
printf("After Sec3MeSm: %s\n",synopRTRN);
/**********************************************************/
/*-- ENCODE SECTION 5 OF THE SYNTHETIC SYNOPTIC REPORT ---*/
/**********************************************************/
if( synopRTRN != NULL )
synopRTRN = Sec5MeSm( Mptr,synopRTRN);
printf("After Sec5MeSm: %s\n",synopRTRN);
/**********************************************************/
/*-- PRINT THE ENCODED SYNTHETIC SYNOPTIC REPORT ---------*/
/**********************************************************/
if( synopRTRN != NULL ) {
printf("\n\nOutput Synoptic Report: %s\n\n",synopRTRN);
free( synopRTRN);
}
#endif
j++;
}
}

Wyświetl plik

@ -0,0 +1,84 @@
/*
METAR Decoder Software Package Library: Parses Aviation Routine Weather Reports
Copyright (C) 2003 Eric McCarthy
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "metar_structs.h"
#pragma subtitle(" ")
#pragma page(1)
#pragma subtitle("subtitle - description ")
/********************************************************************/
/* */
/* Title: fracPart */
/* Organization: W/OSO242 - GRAPHICS AND DISPLAY SECTION */
/* Date: 13 Jun 1995 */
/* Programmer: CARL MCCALLA */
/* Language: C/370 */
/* */
/* Abstract: Convert a character string fraction into a */
/* decimal (floating point) number. */
/* */
/* External Functions Called: */
/* None. */
/* */
/* Input: string - a pointer to a character string frac- */
/* tion. */
/* Output: A decimal (floating point) number. */
/* */
/* Modification History: */
/* None. */
/* */
/********************************************************************/
#pragma page(1)
float fracPart( char *string )
{
/***************************/
/* DECLARE LOCAL VARIABLES */
/***************************/
char buf[ 6 ],
*slash;
float numerator,
denominator;
/*************************/
/* START BODY OF ROUTINE */
/*************************/
slash = strchr(string, '/');
memset(buf , '\0', 6);
strncpy( buf, string, slash-string);
numerator = (float) atoi(buf);
memset(buf , '\0', 6);
strcpy( buf, slash+1);
denominator = (float) atoi(buf);
if( denominator == 0.0 )
return ((float) MAXINT);
else
return (numerator/denominator);
}

Wyświetl plik

@ -0,0 +1,283 @@
/*
METAR Decoder Software Package Library: Parses Aviation Routine Weather Reports
Copyright (C) 2003 Eric McCarthy
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef METARX
#define METARX
/********************************************************************/
/* */
/* Title: METAR H */
/* Organization: W/OSO242 - GRAPHICS AND DISPLAY SECTION */
/* Date: 19 Jan 1996 */
/* Programmer: CARL MCCALLA */
/* Language: C/370 */
/* */
/* Abstract: METAR Decoder Header File. */
/* */
/* Modification History: */
/* None. */
/* */
/********************************************************************/
#include "local.h" /* standard header file */
/*********************************************/
/* */
/* RUNWAY VISUAL RANGE STRUCTURE DECLARATION */
/* AND VARIABLE TYPE DEFINITION */
/* */
/*********************************************/
typedef struct runway_VisRange {
char runway_designator[6];
MDSP_BOOL vrbl_visRange;
MDSP_BOOL below_min_RVR;
MDSP_BOOL above_max_RVR;
int visRange;
int Max_visRange;
int Min_visRange;
} Runway_VisRange;
/***********************************************/
/* */
/* DISPATCH VISUAL RANGE STRUCTURE DECLARATION */
/* AND VARIABLE TYPE DEFINITION */
/* */
/***********************************************/
typedef struct dispatch_VisRange {
MDSP_BOOL vrbl_visRange;
MDSP_BOOL below_min_DVR;
MDSP_BOOL above_max_DVR;
int visRange;
int Max_visRange;
int Min_visRange;
} Dispatch_VisRange;
/*****************************************/
/* */
/* CLOUD CONDITION STRUCTURE DECLARATION */
/* AND VARIABLE TYPE DEFINITION */
/* */
/*****************************************/
typedef struct cloud_Conditions {
char cloud_type[5];
char cloud_hgt_char[4];
char other_cld_phenom[4];
int cloud_hgt_meters;
} Cloud_Conditions;
/*****************************************/
/* */
/* WIND GROUP DATA STRUCTURE DECLARATION */
/* AND VARIABLE TYPE DEFINITION */
/* */
/*****************************************/
typedef struct windstruct {
char windUnits[ 4 ];
MDSP_BOOL windVRB;
int windDir;
int windSpeed;
int windGust;
} WindStruct;
/*****************************************/
/* */
/* RECENT WX GROUP STRUCTURE DECLARATION */
/* AND VARIABLE TYPE DEFINITION */
/* */
/*****************************************/
typedef struct recent_wx {
char Recent_weather[ 5 ];
int Bhh;
int Bmm;
int Ehh;
int Emm;
} Recent_Wx;
/***************************************/
/* */
/* DECODED METAR STRUCTURE DECLARATION */
/* AND VARIABLE TYPE DEFINITION */
/* */
/***************************************/
typedef struct decoded_METAR {
char synoptic_cloud_type[ 6 ];
char snow_depth_group[ 6 ];
char codeName[ 6 ];
char stnid[5];
char horiz_vsby[5];
char dir_min_horiz_vsby[3];
char vsby_Dir[ 3 ];
char WxObstruct[10][8];
char autoIndicator[5];
char VSBY_2ndSite_LOC[10];
char SKY_2ndSite_LOC[10];
char SKY_2ndSite[10];
char SectorVsby_Dir[ 3 ];
char ObscurAloft[ 12 ];
char ObscurAloftSkyCond[ 12 ];
char VrbSkyBelow[ 4 ];
char VrbSkyAbove[ 4 ];
char LTG_DIR[ 3 ];
char CloudLow;
char CloudMedium;
char CloudHigh;
char CIG_2ndSite_LOC[10];
char VIRGA_DIR[3];
char TornadicType[15];
char TornadicLOC[10];
char TornadicDIR[4];
char TornadicMovDir[3];
char CHINO_LOC[6];
char VISNO_LOC[6];
char PartialObscurationAmt[2][7];
char PartialObscurationPhenom[2][12];
char SfcObscuration[6][10];
char charPrevailVsby[12];
char charVertVsby[10];
char TS_LOC[3];
char TS_MOVMNT[3];
MDSP_BOOL Indeterminant3_6HrPrecip;
MDSP_BOOL Indeterminant_24HrPrecip;
MDSP_BOOL CIGNO;
MDSP_BOOL SLPNO;
MDSP_BOOL ACFTMSHP;
MDSP_BOOL NOSPECI;
MDSP_BOOL FIRST;
MDSP_BOOL LAST;
MDSP_BOOL SunSensorOut;
MDSP_BOOL AUTO;
MDSP_BOOL COR;
MDSP_BOOL NIL_rpt;
MDSP_BOOL CAVOK;
MDSP_BOOL RVRNO;
MDSP_BOOL A_altstng;
MDSP_BOOL Q_altstng;
MDSP_BOOL VIRGA;
MDSP_BOOL VOLCASH;
MDSP_BOOL GR;
MDSP_BOOL CHINO;
MDSP_BOOL VISNO;
MDSP_BOOL PNO;
MDSP_BOOL PWINO;
MDSP_BOOL FZRANO;
MDSP_BOOL TSNO;
MDSP_BOOL DollarSign;
MDSP_BOOL PRESRR;
MDSP_BOOL PRESFR;
MDSP_BOOL Wshft_FROPA;
MDSP_BOOL OCNL_LTG;
MDSP_BOOL FRQ_LTG;
MDSP_BOOL CNS_LTG;
MDSP_BOOL CG_LTG;
MDSP_BOOL IC_LTG;
MDSP_BOOL CC_LTG;
MDSP_BOOL CA_LTG;
MDSP_BOOL DSNT_LTG;
MDSP_BOOL AP_LTG;
MDSP_BOOL VcyStn_LTG;
MDSP_BOOL OVHD_LTG;
MDSP_BOOL LightningVCTS;
MDSP_BOOL LightningTS;
int TornadicDistance;
int ob_hour;
int ob_minute;
int ob_date;
int minWnDir;
int maxWnDir;
int VertVsby;
int temp;
int dew_pt_temp;
int QFE;
int hectoPasc_altstng;
int char_prestndcy;
int minCeiling;
int maxCeiling;
int WshfTime_hour;
int WshfTime_minute;
int min_vrbl_wind_dir;
int max_vrbl_wind_dir;
int PKWND_dir;
int PKWND_speed;
int PKWND_hour;
int PKWND_minute;
int SKY_2ndSite_Meters;
int Ceiling;
int Estimated_Ceiling;
int SNINCR;
int SNINCR_TotalDepth;
int SunshineDur;
int ObscurAloftHgt;
int VrbSkyLayerHgt;
int Num8thsSkyObscured;
int CIG_2ndSite_Meters;
int snow_depth;
int BTornadicHour;
int BTornadicMinute;
int ETornadicHour;
int ETornadicMinute;
float SectorVsby;
float WaterEquivSnow;
float VSBY_2ndSite;
float prevail_vsbySM;
float prevail_vsbyM;
float prevail_vsbyKM;
float prestndcy;
float precip_amt;
float precip_24_amt;
float maxtemp;
float mintemp;
float max24temp;
float min24temp;
float minVsby;
float maxVsby;
float hourlyPrecip;
float TWR_VSBY;
float SFC_VSBY;
float Temp_2_tenths;
float DP_Temp_2_tenths;
float SLP;
float GR_Size;
double inches_altstng;
Runway_VisRange RRVR[12];
Dispatch_VisRange DVR;
Recent_Wx ReWx[3];
WindStruct winData;
Cloud_Conditions cldTypHgt[6];
} Decoded_METAR;
#define MAXWXSYMBOLS 10 /*-- NOT TO EXCEED 10 PRES. WX GRPS --*/
#define MAXTOKENS 500 /*-- RPT NOT TO EXCEED 500 GRPS --*/
#endif

Wyświetl plik

@ -0,0 +1,963 @@
/*
METAR Decoder Software Package Library: Parses Aviation Routine Weather Reports
Copyright (C) 2003 Eric McCarthy
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "metar_structs.h"
void say_text(char *speech, char *text) {
int i;
char tmp[2];
for (i = 0; i < strlen(text); i++) {
switch(text[i]) {
case '-':
strcat(speech, "minus");
break;
case '0':
strcat(speech, "zero");
break;
case '1':
strcat(speech, "one");
break;
case '2':
strcat(speech, "two");
break;
case '3':
strcat(speech, "three");
break;
case '4':
strcat(speech, "four");
break;
case '5':
strcat(speech, "five");
break;
case '6':
strcat(speech, "six");
break;
case '7':
strcat(speech, "seven");
break;
case '8':
strcat(speech, "eight");
break;
case '9':
strcat(speech, "niner");
break;
case '@':
strcat(speech, "at");
break;
default:
sprintf(tmp, "%c", text[i]);
strcat(speech, tmp);
break;
}
strcat(speech, " ");
}
}
void sprint_metar (char * string, Decoded_METAR *Mptr)
{
/***************************/
/* DECLARE LOCAL VARIABLES */
/***************************/
int i;
char temp[100];
/*************************/
/* START BODY OF ROUTINE */
/*************************/
strcat(string, "ME TAR. ");
if ( Mptr->stnid[ 0 ] == '\0' ) {
strcat(string, "Error");
return;
}
for (i = 0; i < strlen(Mptr->stnid); i++) {
sprintf(temp, "%c ", Mptr->stnid[i]);
strcat(string, temp);
}
strcat(string, ". ");
if (Mptr->ob_hour != MAXINT && Mptr->ob_minute != MAXINT) {
if (Mptr->AUTO) {
strcat(string, "Automated ");
}
if (Mptr->COR) {
strcat(string, "Corrected ");
}
strcat(string, "Observation ");
sprintf(temp, "%d%d", Mptr->ob_hour, Mptr->ob_minute);
say_text(string, temp);
strcat(string, "zulu. ");
}
strcat(string, "Wind ");
if (Mptr->winData.windDir != MAXINT) {
sprintf(temp, "%03d", Mptr->winData.windDir);
say_text(string, temp);
}
if ( Mptr->winData.windVRB ) {
strcat(string, "variable ");
}
//FIXME.
if ( Mptr->minWnDir != MAXINT ) {
sprintf(temp, "%03d", Mptr->minWnDir);
say_text(string, temp);
}
//FIXME.
if ( Mptr->maxWnDir != MAXINT ) {
sprintf(temp, "%03d", Mptr->maxWnDir);
say_text(string, temp);
}
if ( Mptr->winData.windSpeed != MAXINT ) {
sprintf(temp, "@%d", Mptr->winData.windSpeed);
say_text(string, temp);
} else {
strcat(string, "calm ");
}
if ( Mptr->winData.windGust != MAXINT ) {
strcat(string, "gusting ");
sprintf(temp, "%d", Mptr->winData.windGust);
say_text(string, temp);
}
strcat(string, ". ");
if ( Mptr->prevail_vsbyM != (float) MAXINT ) {
strcat(string, "Visibility ");
sprintf(temp, "%d", (int)Mptr->prevail_vsbyM);
say_text(string, temp);
strcat(string, "miles. ");
}
if ( Mptr->prevail_vsbySM != (float) MAXINT ) {
strcat(string, "Visibility ");
sprintf(temp, "%d", (int)Mptr->prevail_vsbySM);
say_text(string, temp);
strcat(string, "miles. ");
}
/* for ( i = 0; i < 12; i++ )
{
if( Mptr->RRVR[i].runway_designator[0] != '\0' ) {
sprintf(temp, "RUNWAY DESIGNATOR : %s\n",
Mptr->RRVR[i].runway_designator);
strcat(string, temp);
}
if( Mptr->RRVR[i].visRange != MAXINT ) {
sprintf(temp, "R_WAY VIS RANGE (FT): %d\n",
Mptr->RRVR[i].visRange);
strcat(string, temp);
}
if ( Mptr->RRVR[i].vrbl_visRange ) {
sprintf(temp, "VRBL VISUAL RANGE : TRUE\n");
strcat(string, temp);
}
if ( Mptr->RRVR[i].below_min_RVR ) {
sprintf(temp, "BELOW MIN RVR : TRUE\n");
strcat(string, temp);
}
if ( Mptr->RRVR[i].above_max_RVR ) {
sprintf(temp, "ABOVE MAX RVR : TRUE\n");
strcat(string, temp);
}
if( Mptr->RRVR[i].Max_visRange != MAXINT ) {
sprintf(temp, "MX R_WAY VISRNG (FT): %d\n",
Mptr->RRVR[i].Max_visRange);
strcat(string, temp);
}
if( Mptr->RRVR[i].Min_visRange != MAXINT ) {
sprintf(temp, "MN R_WAY VISRNG (FT): %d\n",
Mptr->RRVR[i].Min_visRange);
strcat(string, temp);
}
}
if( Mptr->DVR.visRange != MAXINT ) {
sprintf(temp, "DISPATCH VIS RANGE : %d\n",
Mptr->DVR.visRange);
strcat(string, temp);
}
if ( Mptr->DVR.vrbl_visRange ) {
sprintf(temp, "VRBL DISPATCH VISRNG: TRUE\n");
strcat(string, temp);
}
if ( Mptr->DVR.below_min_DVR ) {
sprintf(temp, "BELOW MIN DVR : TRUE\n");
strcat(string, temp);
}
if ( Mptr->DVR.above_max_DVR ) {
sprintf(temp, "ABOVE MAX DVR : TRUE\n");
strcat(string, temp);
}
if( Mptr->DVR.Max_visRange != MAXINT ) {
sprintf(temp, "MX DSPAT VISRNG (FT): %d\n",
Mptr->DVR.Max_visRange);
strcat(string, temp);
}
if( Mptr->DVR.Min_visRange != MAXINT ) {
sprintf(temp, "MN DSPAT VISRNG (FT): %d\n",
Mptr->DVR.Min_visRange);
strcat(string, temp);
}
i = 0;
while ( Mptr->WxObstruct[i][0] != '\0' && i < MAXWXSYMBOLS )
{
sprintf(temp, "WX/OBSTRUCT VISION : %s\n",
Mptr->WxObstruct[i] );
strcat(string, temp);
i++;
}
if ( Mptr->PartialObscurationAmt[0][0] != '\0' ) {
sprintf(temp, "OBSCURATION AMOUNT : %s\n",
&(Mptr->PartialObscurationAmt[0][0]));
strcat(string, temp);
}
if ( Mptr->PartialObscurationPhenom[0][0] != '\0' ) {
sprintf(temp, "OBSCURATION PHENOM : %s\n",
&(Mptr->PartialObscurationPhenom[0][0]));
strcat(string, temp);
}
if ( Mptr->PartialObscurationAmt[1][0] != '\0' ) {
sprintf(temp, "OBSCURATION AMOUNT : %s\n",
&(Mptr->PartialObscurationAmt[1][0]));
strcat(string, temp);
}
if ( Mptr->PartialObscurationPhenom[1][0] != '\0' ) {
sprintf(temp, "OBSCURATION PHENOM : %s\n",
&(Mptr->PartialObscurationPhenom[1][0]));
strcat(string, temp);
}
*/
strcat(string, "Sky condition ");
i = 0;
while ( Mptr->cldTypHgt[ i ].cloud_type[0] != '\0' &&
i < 6 )
{
if ( Mptr->cldTypHgt[ i ].cloud_type[0] != '\0' ) {
if (strcmp(Mptr->cldTypHgt[ i ].cloud_type, "CLR") == 0) {
strcat(string, "clear. ");
} else {
if (strcmp(Mptr->cldTypHgt[ i ].cloud_type, "FEW") == 0) {
strcat(string, "scattered ");
}
if (strcmp(Mptr->cldTypHgt[ i ].cloud_type, "SCT") == 0) {
strcat(string, "scattered ");
}
if (strcmp(Mptr->cldTypHgt[ i ].cloud_type, "BKN") == 0) {
strcat(string, "broken ");
}
if (strcmp(Mptr->cldTypHgt[ i ].cloud_type, "OVC") == 0) {
strcat(string, "overcast ");
}
//TODO: Others?
}
}
if ( Mptr->cldTypHgt[ i ].cloud_hgt_char[0] != '\0' ) {
char thousands[4];
char hundreds[4];
int height = atoi(Mptr->cldTypHgt[i].cloud_hgt_char);
if ((height - (height%10)) > 0) {
sprintf(thousands, "%d", height/10);
say_text(string, thousands);
strcat(string, "thousand ");
}
if (height%10) {
sprintf(hundreds, "%d", height%10);
say_text(string, hundreds);
strcat(string, "hundred ");
}
}
strcat(string, ". ");
/*
//TODO: TCU, Towering Cumulus, etc.
if ( Mptr->cldTypHgt[ i ].other_cld_phenom[0] != '\0' ) {
sprintf(temp, "OTHER CLOUD PHENOM : %s\n",
Mptr->cldTypHgt[ i ].other_cld_phenom);
strcat(string, temp);
}
*/
i++;
}
if ( Mptr->temp != MAXINT ) {
strcat(string, "Temperature ");
sprintf(temp, "%d", Mptr->temp);
say_text(string, temp);
strcat(string, "celsius. ");
}
if ( Mptr->dew_pt_temp != MAXINT ) {
strcat(string, "Dew point ");
sprintf(temp, "%d", Mptr->dew_pt_temp);
say_text(string, temp);
strcat(string, "celsius. ");
}
if ( Mptr->A_altstng ) {
strcat(string, "Altimeter ");
sprintf(temp, "%d", (int)Mptr->inches_altstng);
say_text(string, temp);
strcat(string, ", ");
sprintf(temp, "%02d", (int)(100*Mptr->inches_altstng)%100);
say_text(string, temp);
strcat(string, ". ");
}
/*
if ( Mptr->TornadicType[0] != '\0' ) {
sprintf(temp, "TORNADIC ACTVTY TYPE: %s\n",
Mptr->TornadicType );
strcat(string, temp);
}
if ( Mptr->BTornadicHour != MAXINT ) {
sprintf(temp, "TORN. ACTVTY BEGHOUR: %d\n",
Mptr->BTornadicHour );
strcat(string, temp);
}
if ( Mptr->BTornadicMinute != MAXINT ) {
sprintf(temp, "TORN. ACTVTY BEGMIN : %d\n",
Mptr->BTornadicMinute );
strcat(string, temp);
}
if ( Mptr->ETornadicHour != MAXINT ) {
sprintf(temp, "TORN. ACTVTY ENDHOUR: %d\n",
Mptr->ETornadicHour );
strcat(string, temp);
}
if ( Mptr->ETornadicMinute != MAXINT ) {
sprintf(temp, "TORN. ACTVTY ENDMIN : %d\n",
Mptr->ETornadicMinute );
strcat(string, temp);
}
if ( Mptr->TornadicDistance != MAXINT ) {
sprintf(temp, "TORN. DIST. FROM STN: %d\n",
Mptr->TornadicDistance );
strcat(string, temp);
}
if ( Mptr->TornadicLOC[0] != '\0' ) {
sprintf(temp, "TORNADIC LOCATION : %s\n",
Mptr->TornadicLOC );
strcat(string, temp);
}
if ( Mptr->TornadicDIR[0] != '\0' ) {
sprintf(temp, "TORNAD. DIR FROM STN: %s\n",
Mptr->TornadicDIR );
strcat(string, temp);
}
if ( Mptr->TornadicMovDir[0] != '\0' ) {
sprintf(temp, "TORNADO DIR OF MOVM.: %s\n",
Mptr->TornadicMovDir );
strcat(string, temp);
}
if ( Mptr->autoIndicator[0] != '\0' ) {
sprintf(temp, "AUTO INDICATOR : %s\n",
Mptr->autoIndicator);
strcat(string, temp);
}
if ( Mptr->PKWND_dir != MAXINT ) {
sprintf(temp, "PEAK WIND DIRECTION : %d\n",Mptr->PKWND_dir);
strcat(string, temp);
}
if ( Mptr->PKWND_speed != MAXINT ) {
sprintf(temp, "PEAK WIND SPEED : %d\n",Mptr->PKWND_speed);
strcat(string, temp);
}
if ( Mptr->PKWND_hour != MAXINT ) {
sprintf(temp, "PEAK WIND HOUR : %d\n",Mptr->PKWND_hour);
strcat(string, temp);
}
if ( Mptr->PKWND_minute != MAXINT ) {
sprintf(temp, "PEAK WIND MINUTE : %d\n",Mptr->PKWND_minute);
strcat(string, temp);
}
if ( Mptr->WshfTime_hour != MAXINT ) {
sprintf(temp, "HOUR OF WIND SHIFT : %d\n",Mptr->WshfTime_hour);
strcat(string, temp);
}
if ( Mptr->WshfTime_minute != MAXINT ) {
sprintf(temp, "MINUTE OF WIND SHIFT: %d\n",Mptr->WshfTime_minute);
strcat(string, temp);
}
if ( Mptr->Wshft_FROPA != FALSE ) {
sprintf(temp, "FROPA ASSOC. W/WSHFT: TRUE\n");
strcat(string, temp);
}
if ( Mptr->TWR_VSBY != (float) MAXINT ) {
sprintf(temp, "TOWER VISIBILITY : %.2f\n",Mptr->TWR_VSBY);
strcat(string, temp);
}
if ( Mptr->SFC_VSBY != (float) MAXINT ) {
sprintf(temp, "SURFACE VISIBILITY : %.2f\n",Mptr->SFC_VSBY);
strcat(string, temp);
}
if ( Mptr->minVsby != (float) MAXINT ) {
sprintf(temp, "MIN VRBL_VIS (SM) : %.4f\n",Mptr->minVsby);
strcat(string, temp);
}
if ( Mptr->maxVsby != (float) MAXINT ) {
sprintf(temp, "MAX VRBL_VIS (SM) : %.4f\n",Mptr->maxVsby);
strcat(string, temp);
}
if( Mptr->VSBY_2ndSite != (float) MAXINT ) {
sprintf(temp, "VSBY_2ndSite (SM) : %.4f\n",Mptr->VSBY_2ndSite);
strcat(string, temp);
}
if( Mptr->VSBY_2ndSite_LOC[0] != '\0' ) {
sprintf(temp, "VSBY_2ndSite LOC. : %s\n",
Mptr->VSBY_2ndSite_LOC);
strcat(string, temp);
}
if ( Mptr->OCNL_LTG ) {
sprintf(temp, "OCCASSIONAL LTG : TRUE\n");
strcat(string, temp);
}
if ( Mptr->FRQ_LTG ) {
sprintf(temp, "FREQUENT LIGHTNING : TRUE\n");
strcat(string, temp);
}
if ( Mptr->CNS_LTG ) {
sprintf(temp, "CONTINUOUS LTG : TRUE\n");
strcat(string, temp);
}
if ( Mptr->CG_LTG ) {
sprintf(temp, "CLOUD-GROUND LTG : TRUE\n");
strcat(string, temp);
}
if ( Mptr->IC_LTG ) {
sprintf(temp, "IN-CLOUD LIGHTNING : TRUE\n");
strcat(string, temp);
}
if ( Mptr->CC_LTG ) {
sprintf(temp, "CLD-CLD LIGHTNING : TRUE\n");
strcat(string, temp);
}
if ( Mptr->CA_LTG ) {
sprintf(temp, "CLOUD-AIR LIGHTNING : TRUE\n");
strcat(string, temp);
}
if ( Mptr->AP_LTG ) {
sprintf(temp, "LIGHTNING AT AIRPORT: TRUE\n");
strcat(string, temp);
}
if ( Mptr->OVHD_LTG ) {
sprintf(temp, "LIGHTNING OVERHEAD : TRUE\n");
strcat(string, temp);
}
if ( Mptr->DSNT_LTG ) {
sprintf(temp, "DISTANT LIGHTNING : TRUE\n");
strcat(string, temp);
}
if ( Mptr->LightningVCTS ) {
sprintf(temp, "L'NING W/I 5-10(ALP): TRUE\n");
strcat(string, temp);
}
if ( Mptr->LightningTS ) {
sprintf(temp, "L'NING W/I 5 (ALP) : TRUE\n");
strcat(string, temp);
}
if ( Mptr->VcyStn_LTG ) {
sprintf(temp, "VCY STN LIGHTNING : TRUE\n");
strcat(string, temp);
}
if ( Mptr->LTG_DIR[0] != '\0' ) {
sprintf(temp, "DIREC. OF LIGHTNING : %s\n", Mptr->LTG_DIR);
strcat(string, temp);
}
i = 0;
while( i < 3 && Mptr->ReWx[ i ].Recent_weather[0] != '\0' )
{
sprintf(temp, "RECENT WEATHER : %s",
Mptr->ReWx[i].Recent_weather);
strcat(string, temp);
if ( Mptr->ReWx[i].Bhh != MAXINT ) {
sprintf(temp, " BEG_hh = %d",Mptr->ReWx[i].Bhh);
strcat(string, temp);
}
if ( Mptr->ReWx[i].Bmm != MAXINT ) {
sprintf(temp, " BEG_mm = %d",Mptr->ReWx[i].Bmm);
strcat(string, temp);
}
if ( Mptr->ReWx[i].Ehh != MAXINT ) {
sprintf(temp, " END_hh = %d",Mptr->ReWx[i].Ehh);
strcat(string, temp);
}
if ( Mptr->ReWx[i].Emm != MAXINT ) {
sprintf(temp, " END_mm = %d",Mptr->ReWx[i].Emm);
strcat(string, temp);
}
strcat(string, "\n");
i++;
}
if ( Mptr->minCeiling != MAXINT ) {
sprintf(temp, "MIN VRBL_CIG (FT) : %d\n",Mptr->minCeiling);
strcat(string, temp);
}
if ( Mptr->maxCeiling != MAXINT ) {
sprintf(temp, "MAX VRBL_CIG (FT)) : %d\n",Mptr->maxCeiling);
strcat(string, temp);
}
if ( Mptr->CIG_2ndSite_Meters != MAXINT ) {
sprintf(temp, "CIG2ndSite (FT) : %d\n",Mptr->CIG_2ndSite_Meters);
strcat(string, temp);
}
if ( Mptr->CIG_2ndSite_LOC[0] != '\0' ) {
sprintf(temp, "CIG @ 2nd Site LOC. : %s\n",Mptr->CIG_2ndSite_LOC);
strcat(string, temp);
}
if ( Mptr->PRESFR ) {
sprintf(temp, "PRESFR : TRUE\n");
strcat(string, temp);
}
if ( Mptr->PRESRR ) {
sprintf(temp, "PRESRR : TRUE\n");
strcat(string, temp);
}
if ( Mptr->SLPNO ) {
sprintf(temp, "SLPNO : TRUE\n");
strcat(string, temp);
}
if ( Mptr->SLP != (float) MAXINT ) {
sprintf(temp, "SLP (hPa) : %.1f\n", Mptr->SLP);
strcat(string, temp);
}
if ( Mptr->SectorVsby != (float) MAXINT ) {
sprintf(temp, "SECTOR VSBY (MILES) : %.2f\n", Mptr->SectorVsby );
strcat(string, temp);
}
if ( Mptr->SectorVsby_Dir[ 0 ] != '\0' ) {
sprintf(temp, "SECTOR VSBY OCTANT : %s\n", Mptr->SectorVsby_Dir );
strcat(string, temp);
}
if ( Mptr->TS_LOC[ 0 ] != '\0' ) {
sprintf(temp, "THUNDERSTORM LOCAT. : %s\n", Mptr->TS_LOC );
strcat(string, temp);
}
if ( Mptr->TS_MOVMNT[ 0 ] != '\0' ) {
sprintf(temp, "THUNDERSTORM MOVMNT.: %s\n", Mptr->TS_MOVMNT);
strcat(string, temp);
}
if ( Mptr->GR ) {
sprintf(temp, "GR (HAILSTONES) : TRUE\n");
strcat(string, temp);
}
if ( Mptr->GR_Size != (float) MAXINT ) {
sprintf(temp, "HLSTO SIZE (INCHES) : %.3f\n",Mptr->GR_Size);
strcat(string, temp);
}
if ( Mptr->VIRGA ) {
sprintf(temp, "VIRGA : TRUE\n");
strcat(string, temp);
}
if ( Mptr->VIRGA_DIR[0] != '\0' ) {
sprintf(temp, "DIR OF VIRGA FRM STN: %s\n", Mptr->VIRGA_DIR);
strcat(string, temp);
}
for( i = 0; i < 6; i++ ) {
if( Mptr->SfcObscuration[i][0] != '\0' ) {
sprintf(temp, "SfcObscuration : %s\n",
&(Mptr->SfcObscuration[i][0]) );
strcat(string, temp);
}
}
if ( Mptr->Num8thsSkyObscured != MAXINT ) {
sprintf(temp, "8ths of SkyObscured : %d\n",Mptr->Num8thsSkyObscured);
strcat(string, temp);
}
if ( Mptr->CIGNO ) {
sprintf(temp, "CIGNO : TRUE\n");
strcat(string, temp);
}
if ( Mptr->Ceiling != MAXINT ) {
sprintf(temp, "Ceiling (ft) : %d\n",Mptr->Ceiling);
strcat(string, temp);
}
if ( Mptr->Estimated_Ceiling != MAXINT ) {
sprintf(temp, "Estimated CIG (ft) : %d\n",Mptr->Estimated_Ceiling);
strcat(string, temp);
}
if ( Mptr->VrbSkyBelow[0] != '\0' ) {
sprintf(temp, "VRB SKY COND BELOW : %s\n",Mptr->VrbSkyBelow);
strcat(string, temp);
}
if ( Mptr->VrbSkyAbove[0] != '\0' ) {
sprintf(temp, "VRB SKY COND ABOVE : %s\n",Mptr->VrbSkyAbove);
strcat(string, temp);
}
if ( Mptr->VrbSkyLayerHgt != MAXINT ) {
sprintf(temp, "VRBSKY COND HGT (FT): %d\n",Mptr->VrbSkyLayerHgt);
strcat(string, temp);
}
if ( Mptr->ObscurAloftHgt != MAXINT ) {
sprintf(temp, "Hgt Obscur Aloft(ft): %d\n",Mptr->ObscurAloftHgt);
strcat(string, temp);
}
if ( Mptr->ObscurAloft[0] != '\0' ) {
sprintf(temp, "Obscur Phenom Aloft : %s\n",Mptr->ObscurAloft);
strcat(string, temp);
}
if ( Mptr->ObscurAloftSkyCond[0] != '\0' ) {
sprintf(temp, "Obscur ALOFT SKYCOND: %s\n",Mptr->ObscurAloftSkyCond);
strcat(string, temp);
}
if ( Mptr->NOSPECI ) {
sprintf(temp, "NOSPECI : TRUE\n");
strcat(string, temp);
}
if ( Mptr->LAST ) {
sprintf(temp, "LAST : TRUE\n");
strcat(string, temp);
}
if ( Mptr->synoptic_cloud_type[ 0 ] != '\0' ) {
sprintf(temp, "SYNOPTIC CLOUD GROUP: %s\n",Mptr->synoptic_cloud_type);
strcat(string, temp);
}
if ( Mptr->CloudLow != '\0' ) {
sprintf(temp, "LOW CLOUD CODE : %c\n",Mptr->CloudLow);
strcat(string, temp);
}
if ( Mptr->CloudMedium != '\0' ) {
sprintf(temp, "MEDIUM CLOUD CODE : %c\n",Mptr->CloudMedium);
strcat(string, temp);
}
if ( Mptr->CloudHigh != '\0' ) {
sprintf(temp, "HIGH CLOUD CODE : %c\n",Mptr->CloudHigh);
strcat(string, temp);
}
if ( Mptr->SNINCR != MAXINT ) {
sprintf(temp, "SNINCR (INCHES) : %d\n",Mptr->SNINCR);
strcat(string, temp);
}
if ( Mptr->SNINCR_TotalDepth != MAXINT ) {
sprintf(temp, "SNINCR(TOT. INCHES) : %d\n",Mptr->SNINCR_TotalDepth);
strcat(string, temp);
}
if ( Mptr->snow_depth_group[ 0 ] != '\0' ) {
sprintf(temp, "SNOW DEPTH GROUP : %s\n",Mptr->snow_depth_group);
strcat(string, temp);
}
if ( Mptr->snow_depth != MAXINT ) {
sprintf(temp, "SNOW DEPTH (INCHES) : %d\n",Mptr->snow_depth);
strcat(string, temp);
}
if ( Mptr->WaterEquivSnow != (float) MAXINT ) {
sprintf(temp, "H2O EquivSno(inches): %.2f\n",Mptr->WaterEquivSnow);
strcat(string, temp);
}
if ( Mptr->SunshineDur != MAXINT ) {
sprintf(temp, "SUNSHINE (MINUTES) : %d\n",Mptr->SunshineDur);
strcat(string, temp);
}
if ( Mptr->SunSensorOut ) {
sprintf(temp, "SUN SENSOR OUT : TRUE\n");
strcat(string, temp);
}
if ( Mptr->hourlyPrecip != (float) MAXINT ) {
sprintf(temp, "HRLY PRECIP (INCHES): %.2f\n",Mptr->hourlyPrecip);
strcat(string, temp);
}
if( Mptr->precip_amt != (float) MAXINT) {
sprintf(temp, "3/6HR PRCIP (INCHES): %.2f\n",
Mptr->precip_amt);
strcat(string, temp);
}
if( Mptr->Indeterminant3_6HrPrecip ) {
sprintf(temp, "INDTRMN 3/6HR PRECIP: TRUE\n");
strcat(string, temp);
}
if( Mptr->precip_24_amt != (float) MAXINT) {
sprintf(temp, "24HR PRECIP (INCHES): %.2f\n",
Mptr->precip_24_amt);
strcat(string, temp);
}
if ( Mptr->Indeterminant_24HrPrecip ) {
sprintf(temp, "INDTRMN 24 HR PRECIP: TRUE\n");
strcat(string, temp);
}
if ( Mptr->Temp_2_tenths != (float) MAXINT ) {
sprintf(temp, "TMP2TENTHS (CELSIUS): %.1f\n",Mptr->Temp_2_tenths);
strcat(string, temp);
}
if ( Mptr->DP_Temp_2_tenths != (float) MAXINT ) {
sprintf(temp, "DPT2TENTHS (CELSIUS): %.1f\n",Mptr->DP_Temp_2_tenths);
strcat(string, temp);
}
if ( Mptr->maxtemp != (float) MAXINT) {
sprintf(temp, "MAX TEMP (CELSIUS) : %.1f\n",
Mptr->maxtemp);
strcat(string, temp);
}
if ( Mptr->mintemp != (float) MAXINT) {
sprintf(temp, "MIN TEMP (CELSIUS) : %.1f\n",
Mptr->mintemp);
strcat(string, temp);
}
if ( Mptr->max24temp != (float) MAXINT) {
sprintf(temp, "24HrMAXTMP (CELSIUS): %.1f\n",
Mptr->max24temp);
strcat(string, temp);
}
if ( Mptr->min24temp != (float) MAXINT) {
sprintf(temp, "24HrMINTMP (CELSIUS): %.1f\n",
Mptr->min24temp);
strcat(string, temp);
}
if ( Mptr->char_prestndcy != MAXINT) {
sprintf(temp, "CHAR PRESS TENDENCY : %d\n",
Mptr->char_prestndcy );
strcat(string, temp);
}
if ( Mptr->prestndcy != (float) MAXINT) {
sprintf(temp, "PRES. TENDENCY (hPa): %.1f\n",
Mptr->prestndcy );
strcat(string, temp);
}
if ( Mptr->PWINO ) {
sprintf(temp, "PWINO : TRUE\n");
strcat(string, temp);
}
if ( Mptr->PNO ) {
sprintf(temp, "PNO : TRUE\n");
strcat(string, temp);
}
if ( Mptr->CHINO ) {
sprintf(temp, "CHINO : TRUE\n");
strcat(string, temp);
}
if ( Mptr->CHINO_LOC[0] != '\0' ) {
sprintf(temp, "CHINO_LOC : %s\n",Mptr->CHINO_LOC);
strcat(string, temp);
}
if ( Mptr->VISNO ) {
sprintf(temp, "VISNO : TRUE\n");
strcat(string, temp);
}
if ( Mptr->VISNO_LOC[0] != '\0' ) {
sprintf(temp, "VISNO_LOC : %s\n",Mptr->VISNO_LOC);
strcat(string, temp);
}
if ( Mptr->FZRANO ) {
sprintf(temp, "FZRANO : TRUE\n");
strcat(string, temp);
}
if ( Mptr->TSNO ) {
sprintf(temp, "TSNO : TRUE\n");
strcat(string, temp);
}
if ( Mptr->DollarSign) {
sprintf(temp, "DOLLAR $IGN INDCATR : TRUE\n");
strcat(string, temp);
}
if ( Mptr->horiz_vsby[ 0 ] != '\0' ) {
sprintf(temp, "HORIZ VISIBILITY : %s\n",Mptr->horiz_vsby);
strcat(string, temp);
}
if ( Mptr->dir_min_horiz_vsby[ 0 ] != '\0' ) {
sprintf(temp, "DIR MIN HORIZ VSBY : %s\n",Mptr->dir_min_horiz_vsby);
strcat(string, temp);
}
if ( Mptr->CAVOK ) {
sprintf(temp, "CAVOK : TRUE\n");
strcat(string, temp);
}
if( Mptr->VertVsby != MAXINT ) {
sprintf(temp, "Vert. Vsby (meters) : %d\n",
Mptr->VertVsby );
strcat(string, temp);
}
*/
/*
if( Mptr->charVertVsby[0] != '\0' )
sprintf(temp, "Vert. Vsby (CHAR) : %s\n",
Mptr->charVertVsby );
*/
/*
if ( Mptr->QFE != MAXINT ) {
sprintf(temp, "QFE : %d\n", Mptr->QFE);
strcat(string, temp);
}
if ( Mptr->VOLCASH ) {
sprintf(temp, "VOLCANIC ASH : TRUE\n");
strcat(string, temp);
}
if ( Mptr->min_vrbl_wind_dir != MAXINT ) {
sprintf(temp, "MIN VRBL WIND DIR : %d\n",Mptr->min_vrbl_wind_dir);
strcat(string, temp);
}
if ( Mptr->max_vrbl_wind_dir != MAXINT ) {
sprintf(temp, "MAX VRBL WIND DIR : %d\n",Mptr->max_vrbl_wind_dir);
strcat(string, temp);
}
*/
strcat(string, "\n\n\n");
}
void prtDMETR (Decoded_METAR *Mptr)
{
char string[5000];
sprint_metar(string, Mptr);
printf(string);
}

Wyświetl plik

@ -0,0 +1,230 @@
/*
METAR Decoder Software Package Library: Parses Aviation Routine Weather Reports
Copyright (C) 2003 Eric McCarthy
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#pragma comment (compiler)
#pragma comment (date)
#pragma comment (timestamp)
#pragma pagesize(80)
#include "local.h" /* standard header file */
#pragma page(1)
#pragma subtitle(" ")
#pragma subtitle("stspack2 - Local string test functions ")
/********************************************************************/
/* */
/* Title: stspack2 */
/* Organization: W/OSO242 - GRAPHICS AND DISPLAY SECTION */
/* Date: 05 Oct 1992 */
/* Programmer: ALLAN DARLING */
/* Language: C/2 */
/* */
/* Abstract: The stspack2 package contains functions to */
/* perform the isalnum through isxdigit functions */
/* on strings. The functions come in four forms: */
/* those that test NULL delimited strings and are */
/* named in the form sxxxxxxx, those that test at */
/* most n characters and are named in the form */
/* nxxxxxxx, those that search forward in a string */
/* and are named in the form nxtyyyyy, and those */
/* that search backward in a string and are named */
/* in the form lstyyyyy. */
/* */
/* The xxxxxxx is the name of the test applied to */
/* each character in the string, such as isalpha, */
/* thus a function to test a NULL delimited string */
/* an return a nonzero value if all characters in */
/* the string are digits is named sisdigit. */
/* */
/* The yyyyy is the name of the test applied to */
/* characters in a string, minus the 'is' prefix. */
/* Thus a function to find the next digit in a NULL */
/* delimited string and return a pointer to it is */
/* named nxtdigit. */
/* */
/* The only exception to the naming rule is for the */
/* functions that test for hexadecimal digits. */
/* These are named sisxdigi, nisxdigi, nxtxdigi, */
/* and lstxdigi because of the eight character */
/* function name limitation. */
/* */
/* The nxxxxxxx class of functions will test up to */
/* n characters or the first NULL character */
/* encountered, whichever comes first. For all */
/* classes of functions, the string sentinal is */
/* not included in the test. */
/* */
/* External Functions Called: */
/* isalnum, isalpha, iscntrl, isdigit, isgraph, */
/* islower, isprint, ispunct, isspace, isupper, */
/* isxdigit. */
/* */
/* Input: For sxxxxxxx class functions, a pointer to a */
/* NULL delimited character string. */
/* */
/* For nxtyyyyy class functions, a pointer to a */
/* NULL delimited character string. */
/* */
/* for nxxxxxxx class functions, a pointer to a */
/* character array, and a positive, nonzero integer.*/
/* */
/* for lstyyyyy class functions, a pointer to a */
/* character array, and a positive, nonzero integer.*/
/* */
/* Output: A nonzero value if the test is true for all */
/* characters in the string, a zero value otherwise.*/
/* */
/* Modification History: */
/* None. */
/* */
/********************************************************************/
#pragma page(1)
int nisalnum(char *s, int n) {
for (; *s && n; s++, n--)
if (!isalnum(*s))
return (0);
return (1);
} /* end nisalnum */
int nisalpha(char *s, int n) {
for (; *s && n; s++, n--)
if (!isalpha(*s))
return (0);
return (1);
} /* end nisalpha */
int niscntrl(char *s, int n) {
for (; *s && n; s++, n--)
if (!iscntrl(*s))
return (0);
return (1);
} /* end niscntrl */
int nisdigit(char *s, int n) {
for (; *s && n; s++, n--)
if (!isdigit(*s))
return (0);
return (1);
} /* end nisdigit */
int nisgraph(char *s, int n) {
for (; *s && n; s++, n--)
if (!isgraph(*s))
return (0);
return (1);
} /* end nisgraph */
int nislower(char *s, int n) {
for (; *s && n; s++, n--)
if (!islower(*s))
return (0);
return (1);
} /* end nislower */
int nisprint(char *s, int n) {
for (; *s && n; s++, n--)
if (!isprint(*s))
return (0);
return (1);
} /* end nisprint */
int nispunct(char *s, int n) {
for (; *s && n; s++, n--)
if (!ispunct(*s))
return (0);
return (1);
} /* end nispunct */
int nisspace(char *s, int n) {
for (; *s && n; s++, n--)
if (!isspace(*s))
return (0);
return (1);
} /* end nisspace */
int nisupper(char *s, int n) {
for (; *s && n; s++, n--)
if (!isupper(*s))
return (0);
return (1);
} /* end nisupper */
int nisxdigi(char *s, int n) {
for (; *s && n; s++, n--)
if (!isxdigit(*s))
return (0);
return (1);
} /* end nisxdigi */
#pragma page(1)

Wyświetl plik

@ -0,0 +1,230 @@
/*
METAR Decoder Software Package Library: Parses Aviation Routine Weather Reports
Copyright (C) 2003 Eric McCarthy
This library is free software; you can redistribute it and/or
modify it under the terms of the GNU Lesser General Public
License as published by the Free Software Foundation; either
version 2.1 of the License, or (at your option) any later version.
This library is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
Lesser General Public License for more details.
You should have received a copy of the GNU Lesser General Public
License along with this library; if not, write to the Free Software
Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#pragma comment (compiler)
#pragma comment (date)
#pragma comment (timestamp)
#pragma pagesize(80)
#include "local.h" /* standard header file */
#pragma page(1)
#pragma subtitle(" ")
#pragma subtitle("stspack3 - Local string test functions ")
/********************************************************************/
/* */
/* Title: stspack3 */
/* Organization: W/OSO242 - GRAPHICS AND DISPLAY SECTION */
/* Date: 05 Oct 1992 */
/* Programmer: ALLAN DARLING */
/* Language: C/2 */
/* */
/* Abstract: The stspack3 package contains functions to */
/* perform the isalnum through isxdigit functions */
/* on strings. The functions come in four forms: */
/* those that test NULL delimited strings and are */
/* named in the form sxxxxxxx, those that test at */
/* most n characters and are named in the form */
/* nxxxxxxx, those that search forward in a string */
/* and are named in the form nxtyyyyy, and those */
/* that search backward in a string and are named */
/* in the form lstyyyyy. */
/* */
/* The xxxxxxx is the name of the test applied to */
/* each character in the string, such as isalpha, */
/* thus a function to test a NULL delimited string */
/* an return a nonzero value if all characters in */
/* the string are digits is named sisdigit. */
/* */
/* The yyyyy is the name of the test applied to */
/* characters in a string, minus the 'is' prefix. */
/* Thus a function to find the next digit in a NULL */
/* delimited string and return a pointer to it is */
/* named nxtdigit. */
/* */
/* The only exception to the naming rule is for the */
/* functions that test for hexadecimal digits. */
/* These are named sisxdigi, nisxdigi, nxtxdigi, */
/* and lstxdigi because of the eight character */
/* function name limitation. */
/* */
/* The nxxxxxxx class of functions will test up to */
/* n characters or the first NULL character */
/* encountered, whichever comes first. For all */
/* classes of functions, the string sentinal is */
/* not included in the test. */
/* */
/* External Functions Called: */
/* isalnum, isalpha, iscntrl, isdigit, isgraph, */
/* islower, isprint, ispunct, isspace, isupper, */
/* isxdigit. */
/* */
/* Input: For sxxxxxxx class functions, a pointer to a */
/* NULL delimited character string. */
/* */
/* For nxtyyyyy class functions, a pointer to a */
/* NULL delimited character string. */
/* */
/* for nxxxxxxx class functions, a pointer to a */
/* character array, and a positive, nonzero integer.*/
/* */
/* for lstyyyyy class functions, a pointer to a */
/* character array, and a positive, nonzero integer.*/
/* */
/* Output: A nonzero value if the test is true for all */
/* characters in the string, a zero value otherwise.*/
/* */
/* Modification History: */
/* None. */
/* */
/********************************************************************/
#pragma page(1)
char *nxtalnum(char *s) {
for (; !isalnum(*s) && *s; s++) ;
if (*s)
return (s);
else
return (NULL);
} /* end nxtalnum */
char *nxtalpha(char *s) {
for (; !isalpha(*s) && *s; s++) ;
if (*s)
return (s);
else
return (NULL);
} /* end nxtalpha */
char *nxtcntrl(char *s) {
for (; !iscntrl(*s) && *s; s++) ;
if (*s)
return (s);
else
return (NULL);
} /* end nxtcntrl */
char *nxtdigit(char *s) {
for (; !isdigit(*s) && *s; s++) ;
if (*s)
return (s);
else
return (NULL);
} /* end nxtdigit */
char *nxtgraph(char *s) {
for (; !isgraph(*s) && *s; s++) ;
if (*s)
return (s);
else
return (NULL);
} /* end nxtgraph */
char *nxtlower(char *s) {
for (; !islower(*s) && *s; s++) ;
if (*s)
return (s);
else
return (NULL);
} /* end nxtlower */
char *nxtprint(char *s) {
for (; !isprint(*s) && *s; s++) ;
if (*s)
return (s);
else
return (NULL);
} /* end nxtprint */
char *nxtpunct(char *s) {
for (; !ispunct(*s) && *s; s++) ;
if (*s)
return (s);
else
return (NULL);
} /* end nxtpunct */
char *nxtspace(char *s) {
for (; !isspace(*s) && *s; s++) ;
if (*s)
return (s);
else
return (NULL);
} /* end nxtspace */
char *nxtupper(char *s) {
for (; !isupper(*s) && *s; s++) ;
if (*s)
return (s);
else
return (NULL);
} /* end nxtupper */
char *nxtxdigi(char *s) {
for (; !isxdigit(*s) && *s; s++) ;
if (*s)
return (s);
else
return (NULL);
} /* end nxtxdigi */
#pragma page(1)

73
test/mtk_config.sh 100755
Wyświetl plik

@ -0,0 +1,73 @@
#!/bin/bash
#
# mtk_config.sh: Script to set up MTK3339 receiver for Stratux.
# Resets receiver to 9600 and 1 Hz GPRMC messaging, then enables
# WAAS, 5 Hz position reporting, the NMEA messages needed by
# Stratux, and 38400 bps serial output.
printf "About to configure MTK3339 receiver on /dev/ttyAMA0.\n"
printf "Press ctrl-C to abort or any other key to continue.\n"
read
# Iterate through common bitrates and send commands to reduce output to 1 Hz / 9600 bps.
printf "Setting MTK and RPi baud rate of /dev/ttyAMA0 to 9600. Iterating through common rates.\n"
printf "Current /dev/ttyAMA0 baudrate.\n"
printf "\$PMTK220,1000*1F\r\n" > /dev/ttyAMA0
printf "\$PMTK251,9600*17\r\n" > /dev/ttyAMA0
sleep 0.2
printf "38400 bps.\n"
stty -F /dev/ttyAMA0 38400
printf "\$PMTK220,1000*1F\r\n" > /dev/ttyAMA0
printf "\$PMTK251,9600*17\r\n" > /dev/ttyAMA0
sleep 0.2
printf "115200 bps.\n"
printf "\$PMTK220,1000*1F\r\n" > /dev/ttyAMA0
stty -F /dev/ttyAMA0 115200
printf "\$PMTK220,1000*1F\r\n" > /dev/ttyAMA0
printf "\$PMTK251,9600*17\r\n" > /dev/ttyAMA0
sleep 0.2
printf "57600 bps.\n"
stty -F /dev/ttyAMA0 57600
printf "\$PMTK220,1000*1F\r\n" > /dev/ttyAMA0
printf "\$PMTK251,9600*17\r\n" > /dev/ttyAMA0
sleep 0.2
printf "19200 bps.\n"
stty -F /dev/ttyAMA0 19200
printf "\$PMTK220,1000*1F\r\n" > /dev/ttyAMA0
printf "\$PMTK251,9600*17\r\n" > /dev/ttyAMA0
sleep 0.2
printf "4800 bps.\n"
stty -F /dev/ttyAMA0 4800
printf "\$PMTK220,1000*1F\r\n" > /dev/ttyAMA0
printf "\$PMTK251,9600*17\r\n" > /dev/ttyAMA0
sleep 0.2
stty -F /dev/ttyAMA0 9600
printf "\$PMTK314,0,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0*29\r\n" > /dev/ttyAMA0
printf "MTK has been set to 9600 baud with RMC messages at 1 Hz.\n"
printf "Press ctrl-C to abort, or any other key enter to continue with setup.\n"
read
# Now start the Stratux setup.
printf "Sending MTK command to set GPS baud rate to 38400\n"
printf "\$PMTK251,38400*27\r\n" > /dev/ttyAMA0
printf "Setting RPi baud rate of /dev/ttyAMA0 to 38400\n"
stty -F /dev/ttyAMA0 38400
sleep 0.2
printf "Sending MTK command to configure NMEA message output\n"
printf "\$PMTK314,0,1,1,1,5,5,0,0,0,0,0,0,0,0,0,0,0,0,0*29\r\n" > /dev/ttyAMA0
sleep 0.2
printf "Sending MTK commands to enable WAAS\n"
printf "\$PMTK301,2*2E\r\n" > /dev/ttyAMA0
sleep 0.2
printf "\$PMTK513,1*28\r\n" > /dev/ttyAMA0
sleep 0.2
printf "Sending MTK commands to enable 5 Hz position reporting\n"
printf "\$PMTK220,200*2C\r\n" > /dev/ttyAMA0
# Finally, test the connection.
printf "Opening /dev/ttyAMA0 to listen to GPS. Press ctrl-C to cancel.\n"
cat /dev/ttyAMA0

BIN
test/packetrate 100755

Plik binarny nie jest wyświetlany.

112
test/sirf_config.sh 100755
Wyświetl plik

@ -0,0 +1,112 @@
#!/bin/bash
#
# sirf_config.sh: Script to set up BU-353-S4 receiver for Stratux.
# Resets receiver to 4800 baud and 1 Hz GPRMC messaging, then enables
# WAAS, 5 Hz position reporting, all NMEA messages needed by
# Stratux, and 38400 bps serial output.
printf "About to configure SIRF receiver on /dev/ttyUSB0.\n"
printf "Press ctrl-C to abort or any other key to continue.\n"
read
# Iterate through common bitrates and send commands to reduce output to 1 Hz / 4800 bps.
printf "Setting SIRF and RPi baud rate of /dev/ttyUSB0 to 4800. Iterating through common rates.\n"
printf "Current /dev/ttyUSB0 baudrate.\n"
printf "\$PSRF103,00,7,00,0*22\r\n" > /dev/ttyUSB0
printf "\$PSRF100,1,4800,8,1,0*0E\r\n" > /dev/ttyUSB0
sleep 0.2
printf "38400 bps.\n"
stty -F /dev/ttyUSB0 38400
printf "\$PSRF103,00,7,00,0*22\r\n" > /dev/ttyUSB0
printf "\$PSRF100,1,4800,8,1,0*0E\r\n" > /dev/ttyUSB0
sleep 0.2
printf "115200 bps.\n"
printf "\$PSRF103,00,7,00,0*22\r\n" > /dev/ttyUSB0
stty -F /dev/ttyUSB0 115200
printf "\$PSRF103,00,7,00,0*22\r\n" > /dev/ttyUSB0
printf "\$PSRF100,1,4800,8,1,0*0E\r\n" > /dev/ttyUSB0
sleep 0.2
printf "57600 bps.\n"
stty -F /dev/ttyUSB0 57600
printf "\$PSRF103,00,7,00,0*22\r\n" > /dev/ttyUSB0
printf "\$PSRF100,1,4800,8,1,0*0E\r\n" > /dev/ttyUSB0
sleep 0.2
printf "19200 bps.\n"
stty -F /dev/ttyUSB0 19200
printf "\$PSRF103,00,7,00,0*22\r\n" > /dev/ttyUSB0
printf "\$PSRF100,1,4800,8,1,0*0E\r\n" > /dev/ttyUSB0
sleep 0.2
printf "9600 bps.\n"
stty -F /dev/ttyUSB0 9600
printf "\$PSRF103,00,7,00,0*22\r\n" > /dev/ttyUSB0
printf "\$PMTK251,4800*17\r\n" > /dev/ttyUSB0
sleep 0.2
stty -F /dev/ttyUSB0 4800
# GGA off:
printf "\$PSRF103,00,00,00,01*24\r\n" > /dev/ttyUSB0
# GLL off:
printf "\$PSRF103,01,00,00,01*27\r\n" > /dev/ttyUSB0
# GSA off:
printf "\$PSRF103,02,00,00,01*26\r\n" > /dev/ttyUSB0
# GSV off:
printf "\$PSRF103,03,00,00,01*27\r\n" > /dev/ttyUSB0
# RMC on:
printf "\$PSRF103,04,00,01,01*21\r\n" > /dev/ttyUSB0
# VTG off:
printf "\$PSRF103,05,00,00,01*21\r\n" > /dev/ttyUSB0
printf "SIRF device has been set to 4800 baud with RMC messages at 1 Hz.\n"
printf "Press ctrl-C to abort, or any other key enter to continue with setup.\n"
read
# Now start the Stratux setup.
printf "Sending Sirf PSRF100 command to set GPS baud rate to 38400\n"
printf "\$PSRF100,1,38400,8,1,0*3D\r\n" > /dev/ttyUSB0
printf "Resetting RPi baud rate of /dev/ttyUSB0 to 38400\n"
stty -F /dev/ttyUSB0 38400
sleep 0.2
printf "Sending SIRF PSRF103 commands to configure NMEA message output\n"
#GGA:
printf "\$PSRF103,00,00,01,01*25\r\n" > /dev/ttyUSB0
# Uncomment next two commands set GSA/GSV on each position message.
# Stratux doesn't need this much info - but keep for developer debug
# GSA (every position message):
#printf "\$PSRF103,02,00,01,01*27\r\n" > /dev/ttyUSB0
# GSV (every position message):
#printf "\$PSRF103,03,00,01,01*26\r\n" > /dev/ttyUSB0
# Next two commands set GSA/GSV on every 5th position message.
# Comment out (and uncomment above two commands) to report on
# every position.
# GSA (every 5 position messages):
printf "\$PSRF103,02,00,05,01*23\r\n" > /dev/ttyUSB0
# GSV (every 5 position messages):
printf "\$PSRF103,03,00,05,01*22\r\n" > /dev/ttyUSB0
# RMC:
printf "\$PSRF103,04,00,01,01*21\r\n" > /dev/ttyUSB0
# VTG:
printf "\$PSRF103,05,00,01,01*20\r\n" > /dev/ttyUSB0
sleep 0.2
printf "Sending SIRF PSRF151 command to enable WAAS\n"
printf "\$PSRF151,01*3F\r\n" > /dev/ttyUSB0
sleep 0.2
printf "Sending SIRF PSRF103 command to enable 5 Hz position reporting\n"
printf "\$PSRF103,00,6,00,0*23\r\n" > /dev/ttyUSB0
# Finally, test the connection.
printf "Opening /dev/ttyUSB0 to listen to GPS. Press ctrl-C to cancel.\n"
cat /dev/ttyUSB0

Wyświetl plik

@ -404,55 +404,63 @@ func (f *UATFrame) decodeAirmet() {
f.Points = points
}
case 9: // Extended Range 3D Point (AGL). p.47.
lng_raw := (int32(record_data[0]) << 11) | (int32(record_data[1]) << 3) | (int32(record_data[2]) & 0xE0 >> 5)
lat_raw := ((int32(record_data[2]) & 0x1F) << 14) | (int32(record_data[3]) << 6) | ((int32(record_data[4]) & 0xFC) >> 2)
alt_raw := ((int32(record_data[4]) & 0x03) << 8) | int32(record_data[5])
fmt.Fprintf(ioutil.Discard, "lat_raw=%d, lng_raw=%d, alt_raw=%d\n", lat_raw, lng_raw, alt_raw)
lat, lng := airmetLatLng(lat_raw, lng_raw, false)
alt := alt_raw * 100
fmt.Fprintf(ioutil.Discard, "lat=%f,lng=%f,alt=%d\n", lat, lng, alt)
fmt.Fprintf(ioutil.Discard, "coord:%f,%f\n", lat, lng)
var point GeoPoint
point.Lat = lat
point.Lon = lng
point.Alt = alt
f.Points = []GeoPoint{point}
case 7, 8: // Extended Range Circular Prism (MSL). (8 = AGL)
lng_bot_raw := (int32(record_data[0]) << 10) | (int32(record_data[1]) << 2) | (int32(record_data[2]) & 0xC0 >> 6)
lat_bot_raw := ((int32(record_data[2]) & 0x3F) << 12) | (int32(record_data[3]) << 4) | ((int32(record_data[4]) & 0xF0) >> 4)
lng_top_raw := ((int32(record_data[4]) & 0x0F) << 14) | (int32(record_data[5]) << 6) | ((int32(record_data[6]) & 0xFC) >> 2)
lat_top_raw := ((int32(record_data[6]) & 0x03) << 16) | (int32(record_data[7]) << 8) | int32(record_data[8])
alt_bot_raw := (int32(record_data[9]) & 0xFE) >> 1
alt_top_raw := ((int32(record_data[9]) & 0x01) << 6) | ((int32(record_data[10]) & 0xFC) >> 2)
r_lng_raw := ((int32(record_data[10]) & 0x03) << 7) | ((int32(record_data[11]) & 0xFE) >> 1)
r_lat_raw := ((int32(record_data[11]) & 0x01) << 8) | int32(record_data[12])
alpha := int32(record_data[13])
lat_bot, lng_bot := airmetLatLng(lat_bot_raw, lng_bot_raw, true)
lat_top, lng_top := airmetLatLng(lat_top_raw, lng_top_raw, true)
alt_bot := alt_bot_raw * 5
alt_top := alt_top_raw * 500
r_lng := float64(r_lng_raw) * float64(0.2)
r_lat := float64(r_lat_raw) * float64(0.2)
fmt.Fprintf(ioutil.Discard, "lat_bot, lng_bot = %f, %f\n", lat_bot, lng_bot)
fmt.Fprintf(ioutil.Discard, "lat_top, lng_top = %f, %f\n", lat_top, lng_top)
if geometry_overlay_options == 8 {
fmt.Fprintf(ioutil.Discard, "alt_bot, alt_top = %d AGL, %d AGL\n", alt_bot, alt_top)
if len(record_data) < 6 {
fmt.Fprintf(ioutil.Discard, "invalid data: Extended Range 3D Point. Should be 6 bytes; % seen.\n", len(record_data))
} else {
fmt.Fprintf(ioutil.Discard, "alt_bot, alt_top = %d MSL, %d MSL\n", alt_bot, alt_top)
lng_raw := (int32(record_data[0]) << 11) | (int32(record_data[1]) << 3) | (int32(record_data[2]) & 0xE0 >> 5)
lat_raw := ((int32(record_data[2]) & 0x1F) << 14) | (int32(record_data[3]) << 6) | ((int32(record_data[4]) & 0xFC) >> 2)
alt_raw := ((int32(record_data[4]) & 0x03) << 8) | int32(record_data[5])
fmt.Fprintf(ioutil.Discard, "lat_raw=%d, lng_raw=%d, alt_raw=%d\n", lat_raw, lng_raw, alt_raw)
lat, lng := airmetLatLng(lat_raw, lng_raw, false)
alt := alt_raw * 100
fmt.Fprintf(ioutil.Discard, "lat=%f,lng=%f,alt=%d\n", lat, lng, alt)
fmt.Fprintf(ioutil.Discard, "coord:%f,%f\n", lat, lng)
var point GeoPoint
point.Lat = lat
point.Lon = lng
point.Alt = alt
f.Points = []GeoPoint{point}
}
fmt.Fprintf(ioutil.Discard, "r_lng, r_lat = %f, %f\n", r_lng, r_lat)
case 7, 8: // Extended Range Circular Prism (7 = MSL, 8 = AGL)
if len(record_data) < 14 {
fmt.Fprintf(ioutil.Discard, "invalid data: Extended Range Circular Prism. Should be 14 bytes; % seen.\n", len(record_data))
} else {
fmt.Fprintf(ioutil.Discard, "alpha=%d\n", alpha)
lng_bot_raw := (int32(record_data[0]) << 10) | (int32(record_data[1]) << 2) | (int32(record_data[2]) & 0xC0 >> 6)
lat_bot_raw := ((int32(record_data[2]) & 0x3F) << 12) | (int32(record_data[3]) << 4) | ((int32(record_data[4]) & 0xF0) >> 4)
lng_top_raw := ((int32(record_data[4]) & 0x0F) << 14) | (int32(record_data[5]) << 6) | ((int32(record_data[6]) & 0xFC) >> 2)
lat_top_raw := ((int32(record_data[6]) & 0x03) << 16) | (int32(record_data[7]) << 8) | int32(record_data[8])
alt_bot_raw := (int32(record_data[9]) & 0xFE) >> 1
alt_top_raw := ((int32(record_data[9]) & 0x01) << 6) | ((int32(record_data[10]) & 0xFC) >> 2)
r_lng_raw := ((int32(record_data[10]) & 0x03) << 7) | ((int32(record_data[11]) & 0xFE) >> 1)
r_lat_raw := ((int32(record_data[11]) & 0x01) << 8) | int32(record_data[12])
alpha := int32(record_data[13])
lat_bot, lng_bot := airmetLatLng(lat_bot_raw, lng_bot_raw, true)
lat_top, lng_top := airmetLatLng(lat_top_raw, lng_top_raw, true)
alt_bot := alt_bot_raw * 5
alt_top := alt_top_raw * 500
r_lng := float64(r_lng_raw) * float64(0.2)
r_lat := float64(r_lat_raw) * float64(0.2)
fmt.Fprintf(ioutil.Discard, "lat_bot, lng_bot = %f, %f\n", lat_bot, lng_bot)
fmt.Fprintf(ioutil.Discard, "lat_top, lng_top = %f, %f\n", lat_top, lng_top)
if geometry_overlay_options == 8 {
fmt.Fprintf(ioutil.Discard, "alt_bot, alt_top = %d AGL, %d AGL\n", alt_bot, alt_top)
} else {
fmt.Fprintf(ioutil.Discard, "alt_bot, alt_top = %d MSL, %d MSL\n", alt_bot, alt_top)
}
fmt.Fprintf(ioutil.Discard, "r_lng, r_lat = %f, %f\n", r_lng, r_lat)
fmt.Fprintf(ioutil.Discard, "alpha=%d\n", alpha)
}
default:
fmt.Fprintf(ioutil.Discard, "unknown geometry: %d\n", geometry_overlay_options)
}
@ -476,8 +484,10 @@ func (f *UATFrame) decodeInfoFrame() {
switch f.Product_id {
case 413:
f.decodeTextFrame()
case 8, 11, 13:
f.decodeAirmet()
/*
case 8, 11, 13:
f.decodeAirmet()
*/
default:
fmt.Fprintf(ioutil.Discard, "don't know what to do with product id: %d\n", f.Product_id)
}
@ -489,6 +499,10 @@ func (u *UATMsg) DecodeUplink() error {
// position_valid := (uint32(frame[5]) & 0x01) != 0
frame := u.msg
if len(frame) < UPLINK_FRAME_DATA_BYTES {
return errors.New(fmt.Sprintf("DecodeUplink: short read (%d).", len(frame)))
}
raw_lat := (uint32(frame[0]) << 15) | (uint32(frame[1]) << 7) | (uint32(frame[2]) >> 1)
raw_lon := ((uint32(frame[2]) & 0x01) << 23) | (uint32(frame[3]) << 15) | (uint32(frame[4]) << 7) | (uint32(frame[5]) >> 1)

Wyświetl plik

@ -5,10 +5,13 @@ var URL_SETTINGS_SET = "http://" + URL_HOST_BASE + "/setSettings";
var URL_GPS_GET = "http://" + URL_HOST_BASE + "/getSituation";
var URL_TOWERS_GET = "http://" + URL_HOST_BASE + "/getTowers"
var URL_STATUS_GET = "http://" + URL_HOST_BASE + "/getStatus"
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_UPDATE_UPLOAD = "http://" + URL_HOST_BASE + "/updateUpload";
var URL_REBOOT = "http://" + URL_HOST_BASE + "/reboot";
var URL_SHUTDOWN = "http://" + URL_HOST_BASE + "/shutdown";
// define the module with dependency on mobile-angular-ui
//var app = angular.module('stratux', ['ngRoute', 'mobile-angular-ui', 'mobile-angular-ui.gestures', 'appControllers']);

Wyświetl plik

@ -1,7 +1,8 @@
<div class="section text-left help-page">
<p>The <strong>GPS / AHRS</strong> page provides a view on the current status of GPS data and AHRS orientation. The Satellite count is located on the <strong>Status</strong> page.</p>
<p>The <strong>GPS</strong> reports position with estimated accuracy, ground track, ground speed, and GPS derived altitude are displayed along with the location depicted on a world map.</p>
<p>The <strong>AHRS</strong> reports magnetic heading, pressure altitude, pitch and roll are displayed along with a graphical representation of movement.</p>
<p>The AHR graphical depiction is a 3-dimentional paper airplane which rotates about a heading with 000&deg; being off in the distance and 180&deg; being down in front. The airplane will pitch up/down and left/right based on the data from the AHRS. To aid with recognizing orientation, the <span class="paperairplane_left">left wing is blue</span> and the <span class="paperairplane_right">right wing is tan</span>.</p>
<p><strong>GPS</strong> shows position with estimated accuracy, ground track, ground speed, and geometric altitude. Location is displayed on a world map.</p>
<p><strong>Satellites</strong> shows the status of GNSS constellations, and lists all satellites that your receiver is tracking. Stratux uses Satellite Based Augmentation System (SBAS) and multi-GNSS solutions on supported receivers. GPS satellites are prefixed with "G", SBAS satellites such as WAAS or EGNOS are prefixed with "S", and Russian GLONASS satellites are prefixed with "R". A checkmark shows if each satellite is used in the current position solution. For each satellite, the elevation, azimuth, and signal strength are provided. A summary of total satellites is presented at the bottom of the table.</p>
<p><strong>AHRS</strong> reports heading, pressure altitude, pitch and roll, along with a graphical representation of movement. As of version v0.8, heading is derived from GPS track, and is provided in degrees true.</p>
<p>The AHRS graphical depiction is a 3-dimensional paper airplane. Heading of 000&deg; is depicted with the nose of the airplane into the page; 180&deg; is depicted with the nose pointing out of the page.The airplane will pitch up/down and left/right based on the data from the AHRS. To aid with recognizing orientation, the <span class="paperairplane_left">left wing is blue</span> and the <span class="paperairplane_right">right wing is tan</span>.</p>
<p class="text-warning">NOTE: This page is for reference only and must not be used for flight operations.</p>
</div>

Wyświetl plik

@ -18,7 +18,7 @@
<div class="row">
<strong class="col-xs-6 text-center">Location:</strong>
<strong class="col-xs-6 text-center">Track:</strong>
</div>
</div>
<div class="row">
<span class="col-xs-6 text-center">{{gps_lat}}, {{gps_lon}} &plusmn; {{gps_accuracy}} m <br> {{gps_alt}} &plusmn; {{gps_vert_accuracy}} ft @ {{gps_vert_speed}} ft/min</span>
<span class="col-xs-6 text-center">{{gps_track}}&deg; @ {{gps_speed}} KTS</span>
@ -54,6 +54,46 @@
</div>
</div>
</div>
<div class="col-sm-12">
<div class="col-sm-6">
<div class="panel panel-default">
<div class="panel-heading">
<span class="panel_label">Satellites</span>
</div>
<div class="panel-body towers-page">
<div class="row">
<span class="col-xs-3"><strong>Satellite</strong></span>
<!--<span class="col-xs-2 text-right"><strong>NMEA Code</strong></span>-->
<span class="col-xs-3 text-right"><strong>Elevation</strong></span>
<span class="col-xs-3 text-right"><strong>Azimuth</strong></span>
<span class="col-xs-3 text-right"><strong>Signal</strong></span>
</div>
<div class="row" ng-repeat="satellite in data_list | orderBy: 'SatelliteNMEA'">
<div class="separator"></div>
<span class="col-xs-3">{{satellite.SatelliteID}}<span ng-show="satellite.InSolution">&nbsp;&#x2705;</span></span>
<!--<span class="col-xs-2 text-right">{{satellite.SatelliteNMEA}}</span>-->
<span class="col-xs-3 text-right">{{satellite.Elevation < -5 ? "---" : satellite.Elevation}}&deg;</span>
<span class="col-xs-3 text-right">{{satellite.Azimuth < 0 ? "---" : satellite.Azimuth}}&deg;</span>
<span class="col-xs-3 text-right">{{satellite.Signal < 1 ? "---" : satellite.Signal}}<span style="font-size:50%">&nbsp;dB-Hz</span></span>
</div>
</div>
<div class="separator"></div>
<div class="panel-footer">
<div class="row">
<label class="col-xs-6">GPS solution:</label>
<span class="col-xs-6">{{SolutionText}}</span>
</div>
<div class="row">
<label class="col-xs-6">Summary:</label>
<span class="col-xs-6">{{Satellites}} in solution; {{GPS_satellites_seen}} seen; {{GPS_satellites_tracked}} tracked</span>
</div>
</div>
</div>
</div>
</div>
<!--
<div class="col-sm-12">
<div class="panel panel-default">

Wyświetl plik

@ -4,7 +4,8 @@ GPSCtrl.$inject = ['$rootScope', '$scope', '$state', '$http', '$interval']; // I
// create our controller function with all necessary logic
function GPSCtrl($rootScope, $scope, $state, $http, $interval) {
$scope.$parent.helppage = 'plates/gps-help.html';
$scope.data_list = [];
var status = {};
var display_area_size = -1;
@ -52,14 +53,25 @@ function GPSCtrl($rootScope, $scope, $state, $http, $interval) {
};
function loadStatus(data) {
function loadStatus(data) { // mySituation
status = angular.fromJson(data);
// consider using angular.extend()
$scope.raw_data = angular.toJson(data, true); // makes it pretty
/* not currently used
$scope.gps_satellites = status.Satellites;
*/
$scope.Satellites = status.Satellites;
$scope.GPS_satellites_tracked = status.SatellitesTracked;
$scope.GPS_satellites_seen = status.SatellitesSeen;
$scope.Quality = status.Quality;
var solutionText = "No Fix";
if (status.Quality == 2) {
solutionText = "GPS + SBAS (WAAS / EGNOS)";
} else if (status.Quality == 1) {
solutionText = "3D GPS"
}
$scope.SolutionText = solutionText;
$scope.gps_accuracy = status.Accuracy.toFixed(1);
$scope.gps_vert_accuracy = (status.AccuracyVert*3.2808).toFixed(1); // accuracy is in meters, need to display in ft
@ -106,9 +118,48 @@ function GPSCtrl($rootScope, $scope, $state, $http, $interval) {
});
};
function getSatellites() {
// Simple GET request example (note: response is asynchronous)
$http.get(URL_SATELLITES_GET).
then(function (response) {
loadSatellites(response.data);
}, function (response) {
$scope.raw_data = "error getting satellite data";
});
};
function setSatellite(obj, new_satellite) {
new_satellite.SatelliteNMEA = obj.SatelliteNMEA;
new_satellite.SatelliteID = obj.SatelliteID; // Formatted code indicating source and PRN code. e.g. S138==WAAS satellite 138, G2==GPS satellites 2
new_satellite.Elevation = obj.Elevation; // Angle above local horizon, -xx to +90
new_satellite.Azimuth = obj.Azimuth; // Bearing (degrees true), 0-359
new_satellite.Signal = obj.Signal; // Signal strength, 0 - 99; -99 indicates no reception
new_satellite.InSolution = obj.InSolution; // is this satellite in the position solution
}
function loadSatellites(data) {
if (($scope === undefined) || ($scope === null))
return; // we are getting called once after clicking away from the status page
var satellites = data; // it seems the json was already converted to an object list by the http request
$scope.raw_data = angular.toJson(data, true);
$scope.data_list.length = 0; // clear array
// we need to use an array so AngularJS can perform sorting; it also means we need to loop to find a tower in the towers set
for (var key in satellites) {
//if (satellites[key].Messages_last_minute > 0) {
var new_satellite = {};
setSatellite(satellites[key], new_satellite);
$scope.data_list.push(new_satellite); // add to start of array
//}
}
// $scope.$apply();
}
var updateStatus = $interval(function () {
// refresh GPS/AHRS status once each half second (aka polling)
getStatus();
getSatellites();
}, (1 * 500), 0, false);
$state.get('gps').onEnter = function () {

Wyświetl plik

@ -1,12 +1,12 @@
angular.module('appControllers').controller('SettingsCtrl', SettingsCtrl); // get the main module contollers set
SettingsCtrl.$inject = ['$rootScope', '$scope', '$state', '$http']; // Inject my dependencies
SettingsCtrl.$inject = ['$rootScope', '$scope', '$state', '$location', '$window', '$http']; // Inject my dependencies
// create our controller function with all necessary logic
function SettingsCtrl($rootScope, $scope, $state, $http) {
function SettingsCtrl($rootScope, $scope, $state, $location, $window, $http) {
$scope.$parent.helppage = 'plates/settings-help.html';
var toggles = ['UAT_Enabled', 'ES_Enabled', 'GPS_Enabled', 'AHRS_Enabled', 'DEBUG', 'ReplayLog']; // DEBUG is 'DspTrafficSrc'
var toggles = ['UAT_Enabled', 'ES_Enabled', 'GPS_Enabled', 'AHRS_Enabled', 'DisplayTrafficSource', 'DEBUG', 'ReplayLog'];
var settings = {};
for (i = 0; i < toggles.length; i++) {
settings[toggles[i]] = undefined;
@ -21,7 +21,7 @@ function SettingsCtrl($rootScope, $scope, $state, $http) {
$scope.ES_Enabled = settings.ES_Enabled;
$scope.GPS_Enabled = settings.GPS_Enabled;
$scope.AHRS_Enabled = settings.AHRS_Enabled;
$scope.PowerSave = settings.PowerSave
$scope.DisplayTrafficSource = settings.DisplayTrafficSource;
$scope.DEBUG = settings.DEBUG;
$scope.ReplayLog = settings.ReplayLog;
$scope.PPM = settings.PPM;
@ -79,10 +79,11 @@ function SettingsCtrl($rootScope, $scope, $state, $http) {
});
$scope.updateppm = function () {
settings["PPM"] = 0
if (($scope.PPM !== undefined) && ($scope.PPM !== null) && ($scope.PPM !== settings["PPM"])) {
settings["PPM"] = parseInt($scope.PPM);
newsettings = {
"PPM": parseInt($scope.PPM)
"PPM": settings["PPM"]
};
// console.log(angular.toJson(newsettings));
setSettings(angular.toJson(newsettings));
@ -91,9 +92,12 @@ function SettingsCtrl($rootScope, $scope, $state, $http) {
$scope.updatewatchlist = function () {
if ($scope.WatchList !== settings["WatchList"]) {
settings["WatchList"] = $scope.WatchList.toUpperCase();
settings["WatchList"] = "";
if ($scope.WatchList !== undefined) {
settings["WatchList"] = $scope.WatchList.toUpperCase();
}
newsettings = {
"WatchList": $scope.WatchList.toUpperCase()
"WatchList": settings["WatchList"]
};
// console.log(angular.toJson(newsettings));
setSettings(angular.toJson(newsettings));
@ -111,11 +115,27 @@ function SettingsCtrl($rootScope, $scope, $state, $http) {
};
$scope.postShutdown = function () {
$http.post('/shutdown');
$window.location.href = "/";
$location.path('/home');
$http.post(URL_SHUTDOWN).
then(function (response) {
// do nothing
// $scope.$apply();
}, function (response) {
// do nothing
});
};
$scope.postReboot = function () {
$http.post('/reboot');
$window.location.href = "/";
$location.path('/home');
$http.post(URL_REBOOT).
then(function (response) {
// do nothing
// $scope.$apply();
}, function (response) {
// do nothing
});
};
$scope.setUploadFile = function (files) {

Wyświetl plik

@ -46,7 +46,6 @@ function StatusCtrl($rootScope, $scope, $state, $http, $interval) {
$scope.Devices = status.Devices;
$scope.Connected_Users = status.Connected_Users;
$scope.UAT_messages_last_minute = status.UAT_messages_last_minute;
// $scope.UAT_products_last_minute = JSON.stringify(status.UAT_products_last_minute);
$scope.UAT_messages_max = status.UAT_messages_max;
$scope.ES_messages_last_minute = status.ES_messages_last_minute;
$scope.ES_messages_max = status.ES_messages_max;

Wyświetl plik

@ -6,9 +6,10 @@ function TrafficCtrl($rootScope, $scope, $state, $http, $interval) {
$scope.$parent.helppage = 'plates/traffic-help.html';
$scope.data_list = [];
$scope.data_list_invalid = [];
function utcTimeString(epoc) {
var time = "";
@ -23,6 +24,7 @@ function TrafficCtrl($rootScope, $scope, $state, $http, $interval) {
time += "Z";
return time;
}
/*
function dmsString(val) {
return [0 | val,
@ -32,17 +34,37 @@ function TrafficCtrl($rootScope, $scope, $state, $http, $interval) {
0 | val * 60 % 1 * 60,
'"'].join('');
}
*/
// chop off seconds for space
function dmsString(val) {
var deg;
var min;
deg = 0 | val;
min = 0 | (val < 0 ? val = -val : val) % 1 * 60;
return [deg*deg < 100 ? "0" + deg : deg,
'° ',
min < 10 ? "0" + min : min,
"' "].join('');
}
function setAircraft(obj, new_traffic) {
new_traffic.icao_int = obj.Icao_addr;
new_traffic.targettype = obj.TargetType;
new_traffic.signal = obj.SignalLevel.toFixed(2);
new_traffic.signal = obj.SignalLevel;
new_traffic.addr_symb ='\u2708';
if (new_traffic.targettype > 3) {
new_traffic.addr_symb ='\ud83d\udce1';
}
new_traffic.icao = obj.Icao_addr.toString(16).toUpperCase();
new_traffic.tail = obj.Tail;
if (obj.Squawk == 0) {
new_traffic.squawk = "----";
} else {
new_traffic.squawk = obj.Squawk;
}
new_traffic.addr_type = obj.Addr_type;
new_traffic.lat = dmsString(obj.Lat);
new_traffic.lon = dmsString(obj.Lng);
var n = Math.round(obj.Alt / 25) * 25;
@ -58,8 +80,11 @@ function TrafficCtrl($rootScope, $scope, $state, $http, $interval) {
new_traffic.vspeed = Math.round(obj.Vvel / 100) * 100
var timestamp = Date.parse(obj.Timestamp);
new_traffic.time = utcTimeString(timestamp);
new_traffic.age = (Math.round(obj.Age * 10)/10).toFixed(1);
new_traffic.age = obj.Age;
new_traffic.ageLastAlt = obj.AgeLastAlt;
new_traffic.src = obj.Last_source; // 1=ES, 2=UAT
new_traffic.bearing = Math.round(obj.Bearing); // degrees true
new_traffic.dist = (obj.Distance/1852); // nautical miles
// return new_aircraft;
}
@ -101,9 +126,11 @@ function TrafficCtrl($rootScope, $scope, $state, $http, $interval) {
var message = JSON.parse(msg.data);
$scope.raw_data = angular.toJson(msg.data, true);
if (message.Position_valid) {
// we need to use an array so AngularJS can perform sorting; it also means we need to loop to find an aircraft in the traffic set
var found = false;
var foundInvalid = false;
for (var i = 0, len = $scope.data_list.length; i < len; i++) {
if ($scope.data_list[i].icao_int === message.Icao_addr) {
setAircraft(message, $scope.data_list[i]);
@ -111,13 +138,39 @@ function TrafficCtrl($rootScope, $scope, $state, $http, $interval) {
break;
}
}
if (!found) {
for (var i = 0, len = $scope.data_list_invalid.length; i < len; i++) {
if ($scope.data_list_invalid[i].icao_int === message.Icao_addr) {
setAircraft(message, $scope.data_list_invalid[i]);
foundInvalid = true;
break;
}
}
if ((!found) && (message.Position_valid)) {
var new_traffic = {};
setAircraft(message, new_traffic);
$scope.data_list.unshift(new_traffic); // add to start of array
$scope.data_list.unshift(new_traffic); // add to start of main array if position is valid and removed from the invalid array
for (var i = 0, len = $scope.data_list_invalid.length; i < len; i++) {
if ($scope.data_list_invalid[i].icao_int === message.Icao_addr) {
$scope.data_list_invalid.splice(i, 1);
}
}
} else if ((!foundInvalid) && (!message.Position_valid)) {
var new_traffic = {};
setAircraft(message, new_traffic);
$scope.data_list_invalid.unshift(new_traffic); // otherwise add to start of invalid array
}
$scope.$apply();
}
};
}
@ -137,20 +190,23 @@ function TrafficCtrl($rootScope, $scope, $state, $http, $interval) {
var tempLocalClock = new Date;
$scope.LocalClock = tempLocalClock.toUTCString();
$scope.SecondsFast = (tempClock-tempLocalClock)/1000;
$scope.GPS_connected = globalStatus.GPS_connected;
}, function (response) {
// nop
});
}, 500, 0, false);
// perform cleanup every 10 seconds
var clearStaleTraffic = $interval(function () {
// remove stale aircraft = anything more than 59 seconds without an update
// remove stale aircraft = anything more than 59 seconds without a position update
var dirty = false;
var dirtyInvalid = false;
var cutoff =59;
for (var i = len = $scope.data_list.length; i > 0; i--) {
@ -163,6 +219,17 @@ function TrafficCtrl($rootScope, $scope, $state, $http, $interval) {
$scope.raw_data = "";
$scope.$apply();
}
for (var i = len = $scope.data_list_invalid.length; i > 0; i--) {
if (($scope.data_list_invalid[i - 1].age >= cutoff) || ($scope.data_list_invalid[i - 1].ageLastAlt >= cutoff)) {
$scope.data_list_invalid.splice(i - 1, 1);
dirtyInvalid = true;
}
}
if (dirtyInvalid) {
$scope.raw_data = "";
$scope.$apply();
}
}, (1000 * 10), 0, false);

Wyświetl plik

@ -37,13 +37,19 @@
<div class="panel-heading">Diagnostics</div>
<div class="panel-body">
<div class="form-group">
<label class="control-label col-xs-7">Traffic Markings</label>
<label class="control-label col-xs-7">Show Traffic Source in Callsign</label>
<div class="col-xs-5">
<ui-switch ng-model='DisplayTrafficSource' settings-change></ui-switch>
</div>
</div>
<div class="form-group">
<label class="control-label col-xs-7">Verbose Message Log</label>
<div class="col-xs-5">
<ui-switch ng-model='DEBUG' settings-change></ui-switch>
</div>
</div>
<div class="form-group">
<label class="control-label col-xs-7">Record Logs</label>
<label class="control-label col-xs-7">Record Replay Logs</label>
<div class="col-xs-5">
<ui-switch ng-model='ReplayLog' settings-change></ui-switch>
</div>

Wyświetl plik

@ -1,18 +1,25 @@
<div class="section text-left help-page">
<p>The <strong>Traffic</strong> page provides a list of all aircraft position reports received within the last 60 seconds. Each time a new aircraft is reported, it is added to the list. Each time a new report is received for an existing aircraft, the list is updated. If a report for an aircraft has not been received within the last 60 seconds, the aircraft is removed from the list.</p>
<p>The <strong>Traffic</strong> page provides a list of all aircraft position reports received within the last 60 seconds. Each time a new aircraft is detected, it is added to the list. Each time a new report is received for an existing aircraft, the list is updated. If a valid position for an aircraft has not been received within the last 60 seconds, the aircraft is removed from the list.</p>
<p>For each aircraft, the list includes the following details:</p>
<ul class="list-simple">
<li><strong>Flight</strong> is aircraft tail number / call sign (when available) or the ICAO 24-bit code. When the ICAO code is used, it is displayed in gray.
<ul class="list-simple">
<li><span class="label traffic-style1">1090 ES</span> traffic is displayed with a light blue background.</li>
<li><span class="label traffic-style2">978 UAT</span> traffic is displayed with a light tan background.</li>
</ul>
</li>
<li><strong>Speed</strong> - Reported ground speed, rounded to the nearest 5 knots. Invalid or missing values are shown as '---'.</li>
<ul>
<li><strong>Callsign</strong> is the aircraft callsign or tail number. Unknown callsigns will be shown as <span class="label traffic-style11">[--N/A--]</span>. Color and symbol indicates traffic source:</li>
<ul class="list-simple">
<li><span class="label traffic-style11">&#x2708; ADSB1090</span> 1090 MHz air-to-air ADS-B traffic is displayed with a medium blue background and airplane symbol.</li>
<li><span class="label traffic-style12">&#x2708; ADSR1090</span> 1090 MHz ground-to-air ADS-R rebroadcasts are displayed with a light cyan background and airplane symbol.</li>
<li><span class="label traffic-style14">&#x1f4e1; TISB1090</span> 1090 MHZ TIS-B traffic is displayed with a light cyan background and antenna symbol.</li>
<li><span class="label traffic-style21">&#x2708; ADSB978</span> 978 MHz air-to-air ADS-B traffic is displayed with a light tan background and airplane symbol.</li>
<li><span class="label traffic-style22">&#x2708; ADSR978</span> 978 MHz ground-to-air ADS-R rebroadcasts are displayed with a gold background and airplane symbol.</li>
<li><span class="label traffic-style24">&#x1f4e1; TISB978</span> 978 MHz TIS-B traffic is displayed with a gold background and antenna symbol.</li>
</ul>
<li><strong>Code</strong> is the ICAO 24-bit code (ADS-B/ADS-R targets), 24-bit FAA-assigned track file ID (TIS-B), or Mode C squawk code, if <strong>Show Squawk</strong> is enabled, and if a squawk code has been received for that target.</li>
<li><strong>Location</strong> - Reported latitude and longitude, DD° mm'.</li>
<li><strong>Dist</strong> - Calculated distance to target in nautical miles. Requires GPS position and <strong>Show Distance</strong> slider to be enabled.</li>
<li><strong>Bearing</strong> - Calculated bearing to target in degrees true. Requires GPS position and <strong>Show Distance</strong> slider to be enabled.</li>
<li><strong>Altitude</strong> - Reported pressure altitude, feet MSL. Climb or descent rate is also shown if not in level flight.</li>
<li><strong>Speed</strong> - Reported ground speed, rounded to the nearest 5 knots. Invalid or missing values are shown as '---'.</li>
<li><strong>Course</strong> - Reported true course, rounded to the nearest 5°. Invalid or missing values are shown as '---'</li>
<li><strong>Location</strong> - Reported latitude and longitude, DD° mm' ss''.</li>
<li><strong>Age</strong> - Age of the last traffic report, seconds.</li>
<li><strong>Power</strong> - Signal strength in dB. The maximum signal is about +1.4 dB. For typical unamplified SDRs, the minimum detection threshold is about -35 dB for altitude reports, and -30 dB for position reports.</li>
<li><strong>Age</strong> - Age of the last position report, seconds.</li>
</ul>
<p><strong>Stratux Clock</strong> and <strong>Device Clock</strong> are the UTC timestamps reported by the Stratux and by the web browser on your mobile device, respectively.</p>
<p>Additionally, if <strong>1090 MHz</strong> is enabled on the <strong>Settings</strong> page, most users will see reports from aircraft in the <strong>Basic Mode S and No-Position Messages</strong> table. These are targets that do not transmitting ADS-B position. Instead, Stratux is picking up altitude, squawk code, and occasionally velocity reports from non-ADS-B Mode S reports. These include air-to-air TCAS messages and radar interrogations, and typically make up the majority of all 1090 messages received.</p>
</div>

Wyświetl plik

@ -1,66 +1,133 @@
<div class="col-sm-12">
<div class="panel panel-default">
<div class="panel-heading">
<span class="panel_label">Traffic</span>
<span class="panel_label">ADS-B and TIS-B Traffic</span>
<span ng-show="ConnectState == 'Connected'" class="label label-success">{{ConnectState}}</span>
<span ng-hide="ConnectState == 'Connected'" class="label label-danger">{{ConnectState}}</span>
</div>
<div class="panel-body traffic-page">
<div class="row">
<div class="col-sm-5">
<span class="col-xs-3"><strong>Flight</strong></span>
<span class="col-xs-3 text-right">Speed</span>
<span class="col-xs-3 text-right">Altitude</span><span class="col-xs-1 col-padding-shift-right">&nbsp;</span>
<span class="col-xs-2 text-right">Course</span>
<div class="col-sm-6">
<span class="col-xs-3"><strong>Callsign</strong></span>
<span class="col-xs-2" ng-hide="showSquawk"><strong>Code</strong></span>
<span class="col-xs-2" ng-show="showSquawk"><strong>Squawk</strong></span>
<span class="col-xs-5 text-right" ng-hide="GPS_connected && RelDist"><strong>Location</strong></span>
<span class="col-xs-3 text-right" ng-show="GPS_connected && RelDist"><strong>Dist</strong></span>
<span class="col-xs-2 text-right" ng-show="GPS_connected && RelDist"><strong>Bearing</strong></span>
</div>
<div class="col-sm-7">
<span class="col-xs-2">&nbsp;</span>
<span class="col-xs-5">Location</span>
<span class="col-xs-2">Power (dB)</span>
<span class="col-xs-2 text-right">Age</span>
<div class="col-sm-6">
<span class="col-xs-3 text-right"><strong>Altitude</strong></span><span class="col-xs-1">&nbsp;</span>
<span class="col-xs-2 text-right"><strong>Speed</strong></span>
<span class="col-xs-2 text-right"><strong>Course</strong></span>
<span class="col-xs-2 text-right"><strong>Power</strong></span>
<span class="col-xs-2 text-right"><strong>Age</strong></span>
</div>
</div>
<div class="row" ng-repeat="aircraft in data_list | orderBy: -age">
<div class="row" ng-repeat="aircraft in data_list | orderBy: 'dist'">
<div class="separator"></div>
<div class="col-sm-5">
<div class="col-sm-6">
<span class="col-xs-3">
<span ng-show="aircraft.tail" ng-class="'label traffic-style'+aircraft.src+aircraft.targettype"><strong>{{aircraft.addr_symb}}&nbsp;{{aircraft.tail}}</strong></span>
<span ng-hide="aircraft.tail" ng-class="'label traffic-style'+aircraft.src+aircraft.targettype"><strong class="text-muted">{{aircraft.addr_symb}}&nbsp;{{aircraft.icao}}</strong></span>
<span ng-show="aircraft.tail" ng-class="'label traffic-style'+aircraft.src+aircraft.targettype">{{aircraft.addr_symb}}<strong>&nbsp;{{aircraft.tail}}</strong></span>
<span ng-hide="aircraft.tail" ng-class="'label traffic-style'+aircraft.src+aircraft.targettype">{{aircraft.addr_symb}}<strong>&nbsp;[--N/A--]</strong></span>
</span>
<span class="col-xs-2">
<span style="font-size:80%" ng-hide="showSquawk">{{aircraft.icao}}<span style="font-size:50%">{{aircraft.addr_type == 3 ? "&nbsp;(TFID)" : ""}}</span></span>
<span ng-show="showSquawk"><span ng-show="aircraft.squawk < 1000">0</span><span ng-show="aircraft.squawk < 100">0</span><span ng-show="aircraft.squawk < 10">0</span>{{aircraft.squawk}}</span>
</span>
<span class="col-xs-5 text-right" ng-hide="GPS_connected && RelDist">{{aircraft.lat}} {{aircraft.lon}}</span>
<span class="col-xs-3 text-right" ng-show="GPS_connected && RelDist">{{aircraft.dist.toFixed(1)}}<span style="font-size:50%">NM</span></span>
<span class="col-xs-2 text-right" ng-show="GPS_connected && RelDist">{{aircraft.bearing}}&deg;</span>
<span class="col-xs-3 text-right">{{aircraft.speed}} KTS</span>
</div>
<div class="col-sm-6">
<span class="col-xs-3 text-right">{{aircraft.alt}}</span>
<span class="col-xs-1 small col-padding-shift-right text-muted">
<span ng-show="aircraft.vspeed > 0"><span class="fa fa-ascent"></span>{{aircraft.vspeed}}</span>
<span ng-show="aircraft.vspeed < 0"><span class="fa fa-descent"></span>{{0-aircraft.vspeed}}</span>
</span>
<span class="col-xs-2 text-right"><span ng-show="aircraft.heading < 10">0</span><span ng-show="aircraft.heading < 100">0</span>{{aircraft.heading}}&deg;</span>
</div>
<div class="col-sm-7">
<span class="col-xs-2">&nbsp;</span>
<span class="col-xs-5">{{aircraft.lat}} {{aircraft.lon}}</span>
<span class="col-xs-2">{{aircraft.signal}}</span>
<!--<span class="col-xs-3 text-right">{{aircraft.time}}</span>-->
<span class="col-xs-2 text-right">{{aircraft.age}}s</span>
<span class="col-xs-2 text-right">{{aircraft.speed}}<span style="font-size:50%">KTS</span></span>
<span class="col-xs-2 text-right"><span ng-show="aircraft.heading < 10">0</span><span ng-show="aircraft.heading < 100">0</span>{{aircraft.heading}}&deg;</span>
<span class="col-xs-2 text-right">{{aircraft.signal.toFixed(2)}}<span style="font-size:50%">dB</span></span>
<span class="col-xs-2 text-right">{{aircraft.age.toFixed(1)}}<span style="font-size:50%">s</span></span>
</div>
</div>
</div>
<!--
<div class="panel-body traffic-footer">
<div class="separator"></div>
<div class="row">
<div class="col-sm-6 label_adj">
<span class="col-xs-4"><strong>Stratux Clock:</strong></span>
<span class="col-xs-8">{{Clock}}</span>
<div class="col-sm-4">
<label class="control-label col-xs-6">Show Squawk</label>
<span class="col-xs-3"><ui-switch ng-model='showSquawk' settings-change></ui-switch></span>
</div>
<div class="col-sm-6 label_adj">
<span class="col-xs-4"><strong>Device Clock:</strong></span>
<span class="col-xs-8">{{LocalClock}}</span>
<div class="col-sm-4">
<label class="control-label col-xs-6">Show Distance</label>
<span class="col-xs-3"><ui-switch ng-model='RelDist' settings-change></ui-switch></span>
</div>
<div class="col-sm-4">
<label class="control-label col-xs-6">GPS Status</label>
<span ng-show="GPS_connected" class="label label-success col-xs-3" style="font-size:100%; display:block; height: 34px; line-height: 34px">Valid</span>
<span ng-hide="GPS_connected" class="label label-danger col-xs-3" style="font-size:100%; display:block; height: 34px; line-height: 34px">No Fix</span>
</div>
</div>
</div>
-->
</div>
<div class="panel panel-default">
<div class="panel-heading">
<span class="panel_label">Basic Mode S and No-Position Messages</span>
</div>
<div class="panel-body traffic-page">
<div class="row">
<div class="col-sm-6">
<span class="col-xs-4"><strong>Callsign</strong></span>
<span class="col-xs-3"><strong>Code</strong></span>
<span class="col-xs-3"><strong>Squawk</strong></span>
</div>
<div class="col-sm-6">
<span class="col-xs-3 text-right"><strong>Altitude</strong></span><span class="col-xs-1">&nbsp;</span>
<span class="col-xs-2 text-right"><strong>Speed</strong></span>
<span class="col-xs-2 text-right"><strong>Course</strong></span>
<span class="col-xs-2 text-right"><strong>Power</strong></span>
<span class="col-xs-2 text-right"><strong>Age</strong></span>
</div>
</div>
<div class="row" ng-repeat="aircraft in data_list_invalid | orderBy: 'icao'">
<div class="separator"></div>
<div class="col-sm-6">
<span class="col-xs-4">
<span ng-show="aircraft.tail" ng-class="'label traffic-style'+aircraft.src+aircraft.targettype">{{aircraft.addr_symb}}<strong>&nbsp;{{aircraft.tail}}</strong></span>
<span ng-hide="aircraft.tail" ng-class="'label traffic-style'+aircraft.src+aircraft.targettype">{{aircraft.addr_symb}}<strong>&nbsp;[--N/A--]</strong></span>
</span>
<span class="col-xs-3" style="font-size:80%">{{aircraft.icao}}<span style="font-size:50%">{{aircraft.addr_type == 3 ? "&nbsp;(TFID)" : ""}}</span></span>
<span class="col-xs-3"><span ng-show="aircraft.squawk < 1000">0</span><span ng-show="aircraft.squawk < 100">0</span><span ng-show="aircraft.squawk < 10">0</span>{{aircraft.squawk}}</span>
</div>
<div class="col-sm-6">
<span class="col-xs-3 text-right">{{aircraft.alt}}</span>
<span class="col-xs-1 small col-padding-shift-right text-muted">
<span ng-show="aircraft.vspeed > 0"><span class="fa fa-ascent"></span>{{aircraft.vspeed}}</span>
<span ng-show="aircraft.vspeed < 0"><span class="fa fa-descent"></span>{{0-aircraft.vspeed}}</span>
</span>
<span class="col-xs-2 text-right">{{aircraft.speed}}<span style="font-size:50%">KTS</span></span>
<span class="col-xs-2 text-right"><span ng-show="aircraft.heading < 10">0</span><span ng-show="aircraft.heading < 100">0</span>{{aircraft.heading}}&deg;</span>
<span class="col-xs-2 text-right">{{aircraft.signal.toFixed(2)}}<span style="font-size:50%">dB</span></span>
<span class="col-xs-2 text-right">{{aircraft.ageLastAlt.toFixed(1)}}<span style="font-size:50%">s</span></span>
</div>
</div>
</div>
<div class="panel-body traffic-footer">
<div class="separator"></div>
<span class ="col-sm-12 small">Stratux has not received valid ADS-B position transmissions from the aircraft in this section. They will not appear on your EFB map. See help page for details.</span>
</div>
</div>
</div>