Merge pull request #2 from cyoung/master

Merge upstream changes
pull/25/head
Brant K. Kyser 2015-08-23 17:23:01 -05:00
commit 104ad005d5
14 zmienionych plików z 995 dodań i 269 usunięć

Wyświetl plik

@ -1,8 +1,12 @@
GOOS ?= linux
GOARCH ?= arm
GOARM ?= 6
GOARM ?= 7
all:
GOOS=$(GOOS) GOARCH=$(GOARCH) GOARM=$(GOARM) go build gen_gdl90.go traffic.go ry835ai.go network.go
install:
cp -f gen_gdl90 /usr/bin/gen_gdl90
chmod 755 /usr/bin/gen_gdl90
clean:
rm -f gen_gdl90

50
dump978.go 100644
Wyświetl plik

@ -0,0 +1,50 @@
// Copyright (c) 2015 Joseph D Poirier
// Distributable under the terms of The New BSD License
// that can be found in the LICENSE file.
// Package dump978 wraps libdump978, a 978MHz UAT demodulator.
package dump978
/*
#cgo linux LDFLAGS: -L. -ldump978
#cgo darwin LDFLAGS: -L. -ldump978
#cgo windows CFLAGS: -IC:/WINDOWS/system32
#cgo windows LDFLAGS: -L. -lrtlsdr -LC:/WINDOWS/system32
#include <stdlib.h>
#include <stdint.h>
#include "dump978/dump978.h"
extern void dump978Cb(char updown, uint8_t *data, int len);
static inline CallBack GetGoCb() {
return (CallBack)dump978Cb;
}
*/
import "C"
import "unsafe"
// Current version.
var PackageVersion = "v0.1"
// InChan is a buffered input channel for raw data.
var InChan = make(chan []byte, 100)
type UserCbT func(C.char, *C.uint8_t, C.int)
// Dump978Init must be the first function called in this package.
func Dump978Init() {
C.Dump978Init((C.CallBack)(C.GetGoCb()))
}
// ProcessData passes buf (modulated data) to dump978 for demodulation.
func ProcessData(buf []byte) {
C.process_data((*C.char)(unsafe.Pointer(&buf[0])), C.int(len(buf)))
}
func ProcessDataFromChannel() {
for {
inData := <-InChan
ProcessData(inData)
}
}

Wyświetl plik

@ -8,6 +8,10 @@ all: dump978 uat2json uat2text uat2esnt extract_nexrad
%.o: %.c *.h
$(CC) $(CPPFLAGS) $(CFLAGS) -c $< -o $@
lib:
$(CC) -c -O2 -g -Wall -Werror -Ifec -fpic -DBUILD_LIB=1 dump978.c fec.c fec/decode_rs_char.c fec/init_rs_char.c
$(CC) -shared -lm -o ../libdump978.so dump978.o fec.o decode_rs_char.o init_rs_char.o
dump978: dump978.o fec.o fec/decode_rs_char.o fec/init_rs_char.o
$(CC) -g -o $@ $^ $(LDFLAGS) $(LIBS)

Wyświetl plik

@ -2,17 +2,17 @@
// Copyright 2015, Oliver Jowett <oliver@mutability.co.uk>
//
// This file is free software: you may copy, redistribute and/or modify it
// This file is free software: you may copy, redistribute and/or modify it
// under the terms of the GNU General Public License as published by the
// Free Software Foundation, either version 2 of the License, or (at your
// option) any later version.
// Free Software Foundation, either version 2 of the License, or (at your
// option) any later version.
//
// This file 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
// This file 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
// General Public License for more details.
//
// You should have received a copy of the GNU General Public License
// You should have received a copy of the GNU General Public License
// along with this program. If not, see <http://www.gnu.org/licenses/>.
#include <stdio.h>
@ -25,8 +25,14 @@
#include "uat.h"
#include "fec.h"
static void make_atan2_table();
static void read_from_stdin();
#ifdef BUILD_LIB
#include "dump978.h"
#endif
static void make_atan2_table(void);
#ifndef BUILD_LIB
static void read_from_stdin(void);
#endif
static int process_buffer(uint16_t *phi, int len, uint64_t offset);
static int demod_adsb_frame(uint16_t *phi, uint8_t *to, int *rs_errors);
static int demod_uplink_frame(uint16_t *phi, uint8_t *to, int *rs_errors);
@ -55,6 +61,7 @@ inline int16_t phi_difference(uint16_t from, uint16_t to)
}
#endif
#ifndef BUILD_LIB
int main(int argc, char **argv)
{
make_atan2_table();
@ -62,9 +69,19 @@ int main(int argc, char **argv)
read_from_stdin();
return 0;
}
#else
static CallBack userCB = NULL;
void Dump978Init(CallBack cb)
{
make_atan2_table();
init_fec();
userCB = cb;
}
#endif
static void dump_raw_message(char updown, uint8_t *data, int len, int rs_errors)
{
#ifndef BUILD_LIB
int i;
fprintf(stdout, "%c", updown);
@ -75,6 +92,9 @@ static void dump_raw_message(char updown, uint8_t *data, int len, int rs_errors)
if (rs_errors)
fprintf(stdout, ";rs=%d", rs_errors);
fprintf(stdout, ";\n");
#else
userCB(updown, data, len);
#endif
}
static void handle_adsb_frame(uint64_t timestamp, uint8_t *frame, int rs)
@ -91,7 +111,7 @@ static void handle_uplink_frame(uint64_t timestamp, uint8_t *frame, int rs)
uint16_t iqphase[65536]; // contains value [0..65536) -> [0, 2*pi)
void make_atan2_table()
void make_atan2_table(void)
{
unsigned i,q;
union {
@ -121,13 +141,14 @@ static void convert_to_phi(uint16_t *buffer, int n)
buffer[i] = iqphase[buffer[i]];
}
void read_from_stdin()
#ifndef BUILD_LIB
void read_from_stdin(void)
{
char buffer[65536*2];
int n;
int used = 0;
uint64_t offset = 0;
while ( (n = read(0, buffer+used, sizeof(buffer)-used)) > 0 ) {
int processed;
@ -142,6 +163,38 @@ void read_from_stdin()
}
}
}
#else
// #define DEFAULT_SAMPLE_RATE 2048000
// #define DEFAULT_BUF_LENGTH (262144) 16*16384
static char buffer[65536*2]; // 131072, max received should be 113120
int process_data(char *data, int dlen)
{
int n;
int processed;
int doffset = 0;
static int used = 0;
static uint64_t offset = 0;
while (dlen > 0) {
n = (sizeof(buffer)-used) >= dlen ? dlen : (sizeof(buffer)-used);
memcpy(buffer+used, data+doffset, n);
convert_to_phi((uint16_t*) (buffer+(used&~1)), ((used&1)+n)/2);
used += n;
processed = process_buffer((uint16_t*)buffer, used/2, offset);
used -= processed * 2;
offset += processed;
if (used > 0) {
memmove(buffer, buffer+processed*2, used);
}
doffset += n;
dlen -= n;
}
return dlen;
}
#endif
// Return 1 if word is "equal enough" to expected
@ -166,19 +219,19 @@ static inline int sync_word_fuzzy_compare(uint64_t word, uint64_t expected)
//
// 010101010101010000
// ^
// Subtracting one, will flip the
// Subtracting one, will flip the
// bits starting at the last set bit:
//
// 010101010101001111
// ^
// then we can use that as a bitwise-and
// then we can use that as a bitwise-and
// mask to clear the lowest set bit:
//
// 010101010101000000
// ^
// And repeat until the value is zero
// or we have seen too many set bits.
// >= 1 bit
diff &= (diff-1); // clear lowest set bit
if (!diff)
@ -259,7 +312,7 @@ int check_sync_word(uint16_t *phi, uint64_t pattern, int16_t *center)
#define SYNC_MASK ((((uint64_t)1)<<SYNC_BITS)-1)
int process_buffer(uint16_t *phi, int len, uint64_t offset)
int process_buffer(uint16_t *phi, int len, uint64_t offset)
{
uint64_t sync0 = 0, sync1 = 0;
int lenbits;
@ -298,7 +351,7 @@ int process_buffer(uint16_t *phi, int len, uint64_t offset)
continue; // haven't fully populated sync0/1 yet
// see if we have (the start of) a valid sync word
// It would be nice to look at popcount(expected ^ sync)
// It would be nice to look at popcount(expected ^ sync)
// so we can tolerate some errors, but that turns out
// to be very expensive to do on every sample
@ -393,7 +446,7 @@ static int demod_adsb_frame(uint16_t *phi, uint8_t *to, int *rs_errors)
return 0;
}
demod_frame(phi + SYNC_BITS*2, to, LONG_FRAME_BYTES, center_dphi);
demod_frame(phi + SYNC_BITS*2, to, LONG_FRAME_BYTES, center_dphi);
frametype = correct_adsb_frame(to, rs_errors);
if (frametype == 1)
return (SYNC_BITS + SHORT_FRAME_BITS);

12
dump978/dump978.h 100644
Wyświetl plik

@ -0,0 +1,12 @@
#ifndef DUMP978_H
#define DUMP978_H
// $ gcc -c -O2 -g -Wall -Werror -Ifec -fpic -DBUILD_LIB=1 dump978.c fec.c fec/decode_rs_char.c fec/init_rs_char.c
// $ gcc -shared -lm -o ../libdump978.so dump978.o fec.o decode_rs_char.o init_rs_char.o
typedef void (*CallBack)(char updown, uint8_t *data, int len);
extern void Dump978Init(CallBack cb);
extern int process_data(char *data, int dlen);
#endif /* DUMP978_H */

41
exports.go 100644
Wyświetl plik

@ -0,0 +1,41 @@
// Copyright (c) 2015 Joseph D Poirier
// Distributable under the terms of The New BSD License
// that can be found in the LICENSE file.
// Package dump978 wraps libdump978, a 978MHz UAT demodulator.
package dump978
import (
"fmt"
"reflect"
"unsafe"
)
/*
#include <stdint.h>
#include "dump978/dump978.h"
*/
import "C"
// OutChan is a buffered output channel for demodulated data.
var OutChan = make(chan string, 100)
//export dump978Cb
func dump978Cb(updown C.char, data *C.uint8_t, length C.int) {
// c buffer to go slice without copying
var buf []byte
b := (*reflect.SliceHeader)((unsafe.Pointer(&buf)))
b.Cap = int(length)
b.Len = int(length)
b.Data = uintptr(unsafe.Pointer(data))
// copy incoming to outgoing
outData := string(updown)
for i := 0; i < int(length); i++ {
outData += fmt.Sprintf("%02x", buf[i])
}
OutChan <- outData
}

Wyświetl plik

@ -47,7 +47,7 @@ const (
var Crc16Table [256]uint16
var myGPS GPSData
var mySituation SituationData
type msg struct {
MessageClass uint
@ -121,14 +121,6 @@ func makeLatLng(v float32) []byte {
return ret
}
func isGPSValid() bool {
return time.Since(myGPS.lastFixLocalTime).Seconds() < 15
}
func isGPSGroundTrackValid() bool {
return time.Since(myGPS.lastGroundTrackTime).Seconds() < 15
}
//TODO
func makeOwnshipReport() bool {
if !isGPSValid() {
@ -144,20 +136,22 @@ func makeOwnshipReport() bool {
msg[3] = 1 // Address.
msg[4] = 1 // Address.
tmp := makeLatLng(myGPS.lat)
tmp := makeLatLng(mySituation.lat)
msg[5] = tmp[0] // Latitude.
msg[6] = tmp[1] // Latitude.
msg[7] = tmp[2] // Latitude.
tmp = makeLatLng(myGPS.lng)
tmp = makeLatLng(mySituation.lng)
msg[8] = tmp[0] // Longitude.
msg[9] = tmp[1] // Longitude.
msg[10] = tmp[2] // Longitude.
//TODO: 0xFFF "invalid altitude."
//FIXME: This is **PRESSURE ALTITUDE**
// This is **PRESSURE ALTITUDE**
alt := uint16(0xFFF) // 0xFFF "invalid altitude."
alt := uint16(myGPS.alt)
if isTempPressValid() {
alt = uint16(mySituation.pressure_alt)
}
alt = (alt + 1000) / 25
alt = alt & 0xFFF // Should fit in 12 bits.
@ -173,7 +167,7 @@ func makeOwnshipReport() bool {
gdSpeed := uint16(0) // 1kt resolution.
if isGPSGroundTrackValid() {
gdSpeed = myGPS.groundSpeed
gdSpeed = mySituation.groundSpeed
}
gdSpeed = gdSpeed & 0x0FFF // Should fit in 12 bits.
@ -189,7 +183,7 @@ func makeOwnshipReport() bool {
// Showing magnetic (corrected) on ForeFlight. Needs to be True Heading.
groundTrack := uint16(0)
if isGPSGroundTrackValid() {
groundTrack = myGPS.trueCourse
groundTrack = mySituation.trueCourse
}
trk := uint8(float32(groundTrack) / TRACK_RESOLUTION) // Resolution is ~1.4 degrees.
@ -197,7 +191,7 @@ func makeOwnshipReport() bool {
msg[18] = 0x01 // "Light (ICAO) < 15,500 lbs"
sendMsg(prepareMessage(msg))
sendGDL90(prepareMessage(msg))
return true
}
@ -208,8 +202,8 @@ func makeOwnshipGeometricAltitudeReport() bool {
}
msg := make([]byte, 5)
// See p.28.
msg[0] = 0x0B // Message type "Ownship Geo Alt".
alt := int16(myGPS.alt)
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.
@ -218,7 +212,7 @@ func makeOwnshipGeometricAltitudeReport() bool {
msg[3] = 0x00
msg[4] = 0x0A
sendMsg(prepareMessage(msg))
sendGDL90(prepareMessage(msg))
return true
}
@ -235,8 +229,12 @@ func makeHeartbeat() []byte {
msg := make([]byte, 7)
// See p.10.
msg[0] = 0x00 // Message type "Heartbeat".
msg[1] = 0x01 // "UAT Initialized". //FIXME
msg[1] = 0x91 //FIXME: GPS valid. Addr talkback.
msg[1] = 0x01 // "UAT Initialized".
if isGPSValid() {
msg[1] = msg[1] | 0x80
}
msg[1] = msg[1] | 0x10 //FIXME: Addr talkback.
nowUTC := time.Now().UTC()
// Seconds since 0000Z.
midnightUTC := time.Date(nowUTC.Year(), nowUTC.Month(), nowUTC.Day(), 0, 0, 0, 0, time.UTC)
@ -265,18 +263,18 @@ func relayMessage(msgtype uint16, msg []byte) {
ret[i+4] = msg[i]
}
sendMsg(prepareMessage(ret))
sendGDL90(prepareMessage(ret))
}
func heartBeatSender() {
timer := time.Tick(1 * time.Second)
timer := time.NewTicker(1 * time.Second)
for {
<-timer
sendMsg(makeHeartbeat())
// sendMsg(makeTrafficReport())
<-timer.C
sendGDL90(makeHeartbeat())
// sendGDL90(makeTrafficReport())
makeOwnshipReport()
makeOwnshipGeometricAltitudeReport()
sendMsg(makeInitializationMessage())
sendGDL90(makeInitializationMessage())
sendTrafficUpdates()
updateStatus()
}
@ -302,7 +300,7 @@ func updateStatus() {
globalStatus.ES_messages_last_minute = ES_messages_last_minute
if isGPSValid() {
globalStatus.GPS_satellites_locked = myGPS.satellites
globalStatus.GPS_satellites_locked = mySituation.satellites
}
}
@ -359,17 +357,21 @@ type settings struct {
UAT_Enabled bool
ES_Enabled bool
GPS_Enabled bool
GDLOutputPorts []uint16
NetworkOutputs []networkConnection
AHRS_Enabled bool
}
type status struct {
Version string
Devices uint
Connected_Users uint
UAT_messages_last_minute uint
UAT_messages_max uint
ES_messages_last_minute uint
ES_messages_max uint
GPS_satellites_locked uint16
GPS_connected bool
RY835AI_connected bool
}
var globalSettings settings
@ -401,9 +403,6 @@ func handleManagementConnection(conn net.Conn) {
log.Printf("%s - error: %s\n", s, err.Error())
} else {
log.Printf("new settings: %s\n", s)
if !globalSettings.GPS_Enabled && newSettings.GPS_Enabled { // GPS was enabled, restart the reader thread.
go gpsReader()
}
globalSettings = newSettings
saveSettings()
}
@ -428,10 +427,11 @@ func managementInterface() {
}
func defaultSettings() {
globalSettings.UAT_Enabled = true //TODO
globalSettings.ES_Enabled = false //TODO
globalSettings.GPS_Enabled = false //TODO
globalSettings.GDLOutputPorts = []uint16{4000, 43211}
globalSettings.UAT_Enabled = true //TODO
globalSettings.ES_Enabled = true //TODO
globalSettings.GPS_Enabled = true //TODO
globalSettings.NetworkOutputs = []networkConnection{{nil, "", 4000, NETWORK_GDL90}, {nil, "", 43211, NETWORK_GDL90}, {nil, "", 49002, NETWORK_AHRS}}
globalSettings.AHRS_Enabled = true
}
func readSettings() {
@ -486,9 +486,7 @@ func main() {
readSettings()
if globalSettings.GPS_Enabled {
go gpsReader()
}
initRY835AI()
//TODO: network stuff

Wyświetl plik

@ -124,8 +124,6 @@ chmod 755 /etc/init.d/stratux
ln -s /etc/init.d/stratux /etc/rc2.d/S01stratux
ln -s /etc/init.d/stratux /etc/rc6.d/K01stratux
echo -n '{"UAT_Enabled":false,"ES_Enabled":true,"GPS_Enabled":true}' >/etc/stratux.conf
update-rc.d stratux enable
#usb hub power

Wyświetl plik

@ -1,33 +1,36 @@
// Package bmp180 allows interfacing with Bosch BMP180 barometric pressure sensor. This sensor
// Package mpu6050 allows interfacing with InvenSense mpu6050 barometric pressure sensor. This sensor
// has the ability to provided compensated temperature and pressure readings.
package mpu6050
import (
"time"
"math"
// "github.com/golang/glog"
"time"
// "github.com/golang/glog"
"github.com/kidoman/embd"
"fmt"
"log"
)
//https://www.olimex.com/Products/Modules/Sensors/MOD-MPU6050/resources/RM-MPU-60xxA_rev_4.pdf
const (
address = 0x68
GYRO_XOUT_H = 0x43
GYRO_YOUT_H = 0x45
GYRO_ZOUT_H = 0x47
GYRO_XOUT_H = 0x43
GYRO_YOUT_H = 0x45
GYRO_ZOUT_H = 0x47
ACCEL_XOUT_H = 0x3B
ACCEL_YOUT_H = 0x3D
ACCEL_ZOUT_H = 0x3F
ACCEL_XOUT_H = 0x3B
ACCEL_YOUT_H = 0x3D
ACCEL_ZOUT_H = 0x3F
PWR_MGMT_1 = 0x6B
PWR_MGMT_1 = 0x6B
ACCEL_SCALE = 16384.0 // Assume AFS_SEL = 0.
GYRO_SCALE = 131.0 // Assume FS_SEL = 0.
GYRO_CONFIG = 0x1B
ACCEL_CONFIG = 0x1C
pollDelay = 500 * time.Microsecond // 2000Hz
ACCEL_SCALE = 16384.0 // Assume AFS_SEL = 0.
GYRO_SCALE = 131.0 // Assume FS_SEL = 0.
pollDelay = 500 * time.Microsecond // 2000Hz
)
type XYZ struct {
@ -41,24 +44,25 @@ type MPU6050 struct {
Bus embd.I2CBus
Poll time.Duration
started bool
//TODO
gyro_reading XYZ // "Integrated".
accel_reading XYZ // Directly from sensor.
started bool
pitch_history []float64
roll_history []float64
//TODO
gyro_reading XYZ // "Integrated".
accel_reading XYZ // Directly from sensor.
pitch_resting float64
roll_resting float64
pitch_history []float64
roll_history []float64
pitch float64
roll float64
// gyro chan XYZ
// accel chan XYZ
pitch_resting float64
roll_resting float64
quit chan struct{}
pitch float64
roll float64
heading float64
// gyro chan XYZ
// accel chan XYZ
quit chan struct{}
}
// New returns a handle to a MPU6050 sensor.
@ -72,6 +76,9 @@ func New(bus embd.I2CBus) *MPU6050 {
func (d *MPU6050) StartUp() error {
d.Bus.WriteByteToReg(address, PWR_MGMT_1, 0) // Wake device up.
d.Bus.WriteByteToReg(address, GYRO_CONFIG, 0) // FS_SEL = 0
d.Bus.WriteByteToReg(address, ACCEL_CONFIG, 0) // AFS_SEL = 0
d.pitch_history = make([]float64, 0)
d.roll_history = make([]float64, 0)
@ -81,7 +88,6 @@ func (d *MPU6050) StartUp() error {
return nil
}
func (d *MPU6050) calibrate() {
//TODO: Error checking to make sure that the histories are extensive enough to be significant.
//TODO: Error checking to do continuous calibrations.
@ -98,7 +104,7 @@ func (d *MPU6050) calibrate() {
}
roll_adjust = roll_adjust / float64(len(d.roll_history))
d.roll_resting = roll_adjust
fmt.Printf("calibrate: pitch %f, roll %f\n", pitch_adjust, roll_adjust)
log.Printf("calibrate: pitch %f, roll %f\n", pitch_adjust, roll_adjust)
}
func (d *MPU6050) readGyro() (XYZ, error) {
@ -149,17 +155,15 @@ func (d *MPU6050) readAccel() (XYZ, error) {
func (d *MPU6050) calculatePitchAndRoll() {
accel := d.accel_reading
// fmt.Printf("accel: %f, %f, %f\n", accel.x, accel.y, accel.z)
// log.Printf("accel: %f, %f, %f\n", accel.x, accel.y, accel.z)
// Accel.
p1 := math.Atan2(float64(accel.y), dist(accel.x, accel.z))
p1_deg := p1 * (180 / math.Pi)
p1_deg := p1 * (180.0 / math.Pi)
r1 := math.Atan2(float64(accel.x), dist(accel.y, accel.z))
r1_deg := -r1 * (180 / math.Pi)
r1_deg := -r1 * (180.0 / math.Pi)
// Gyro.
@ -168,38 +172,60 @@ func (d *MPU6050) calculatePitchAndRoll() {
// "Noise filter".
ft := float64(0.98)
sample_period := float64(1/2000.0)
d.pitch = float64( ft*( sample_period*p2 + d.pitch) + (1-ft)*p1_deg)
d.roll = float64( (ft*( sample_period*r2 + d.roll) + (1-ft)*r1_deg))
sample_period := float64(1 / 2000.0)
d.pitch = float64(ft*(sample_period*p2+d.pitch) + (1-ft)*p1_deg)
d.roll = float64((ft*(sample_period*r2+d.roll) + (1-ft)*r1_deg))
d.pitch_history = append(d.pitch_history, d.pitch)
d.roll_history = append(d.roll_history, d.roll)
//FIXME: Experimental (heading).
f := math.Atan2(float64(d.gyro_reading.z), dist(float32(d.pitch), float32(d.roll)))
h1_deg := -float64(3.42857142857)*f * (180.0 / math.Pi)
// d.heading = float64((float64(3.42857142857)*sample_period * float64(-d.gyro_reading.z)) + d.heading)
d.heading = float64((sample_period * h1_deg) + d.heading)
if d.heading > 360.0 {
d.heading = d.heading - float64(360.0)
} else if d.heading < 0.0 {
d.heading = d.heading + float64(360.0)
}
}
func (d *MPU6050) measure() error {
func (d *MPU6050) measureGyro() error {
XYZ_gyro, err := d.readGyro()
if err != nil {
return err
}
d.gyro_reading = XYZ_gyro
return nil
}
func (d *MPU6050) measureAccel() error {
XYZ_accel, err := d.readAccel()
if err != nil {
return err
}
// glog.V(1).Infof("mpu6050: scaled gyro: (%f, %f, %f)", XYZ_gyro.x, XYZ_gyro.y, XYZ_gyro.z)
// glog.V(1).Infof("mpu6050: scaled accel: (%f, %f, %f)", XYZ_accel.x, XYZ_accel.y, XYZ_accel.z)
d.accel_reading = XYZ_accel
d.gyro_reading = XYZ_gyro
return nil
}
func (d *MPU6050) measure() error {
if err := d.measureGyro(); err != nil {
return err
}
if err := d.measureAccel(); err != nil {
return err
}
return nil
}
func dist(a, b float32) float64 {
a64 := float64(a)
b64 := float64(b)
return math.Sqrt((a64*a64) + (b64*b64))
return math.Sqrt((a64 * a64) + (b64 * b64))
}
// Temperature returns the current temperature reading.
@ -207,6 +233,10 @@ func (d *MPU6050) PitchAndRoll() (float64, float64) {
return (d.pitch - d.pitch_resting), (d.roll - d.roll_resting)
}
func (d *MPU6050) Heading() float64 {
return d.heading
}
func (d *MPU6050) Run() {
go func() {
d.quit = make(chan struct{})
@ -215,8 +245,8 @@ func (d *MPU6050) Run() {
for {
select {
case <-timer.C:
// read values.
d.measure()
d.measureGyro()
d.measureAccel()
d.calculatePitchAndRoll()
case <-calibrateTimer.C:
d.calibrate()
@ -229,9 +259,15 @@ func (d *MPU6050) Run() {
return
}
// Set heading from a known value (usually GPS true heading).
func (d *MPU6050) ResetHeading(heading float64) {
log.Printf("reset true heading: %f\n", heading)
d.heading = heading
}
// Close.
func (d *MPU6050) Close() {
if d.quit != nil {
d.quit <- struct{}{}
}
}
}

Wyświetl plik

@ -1,6 +1,7 @@
package main
import (
"golang.org/x/exp/inotify"
"io/ioutil"
"log"
"net"
@ -10,14 +11,32 @@ import (
"time"
)
var messageQueue chan []byte
var outSockets map[string]*net.UDPConn
type networkMessage struct {
msg []byte
msgType uint8
}
type networkConnection struct {
Conn *net.UDPConn
Ip string
Port uint32
Capability uint8
}
var messageQueue chan networkMessage
var outSockets map[string]networkConnection
var dhcpLeases map[string]string
var netMutex *sync.Mutex
const (
NETWORK_GDL90 = 1
NETWORK_AHRS = 2
dhcp_lease_file = "/var/lib/dhcp/dhcpd.leases"
)
// Read the "dhcpd.leases" file and parse out IP/hostname.
func getDHCPLeases() (map[string]string, error) {
dat, err := ioutil.ReadFile("/var/lib/dhcp/dhcpd.leases")
dat, err := ioutil.ReadFile(dhcp_lease_file)
ret := make(map[string]string)
if err != nil {
return ret, err
@ -39,17 +58,21 @@ func getDHCPLeases() (map[string]string, error) {
return ret, nil
}
func sendToAllConnectedClients(msg []byte) {
func sendToAllConnectedClients(msg networkMessage) {
netMutex.Lock()
defer netMutex.Unlock()
for _, sock := range outSockets {
sock.Write(msg)
for _, netconn := range outSockets {
if (netconn.Capability & msg.msgType) != 0 { // Check if this port is able to accept the type of message we're sending.
netconn.Conn.Write(msg.msg)
}
}
}
// Just returns the number of DHCP leases for now.
func getNetworkStats() int {
return len(dhcpLeases)
func getNetworkStats() uint {
ret := uint(len(dhcpLeases))
globalStatus.Connected_Users = ret
return ret
}
// See who has a DHCP lease and make a UDP connection to each of them.
@ -65,10 +88,10 @@ func refreshConnectedClients() {
dhcpLeases = t
// Client connected that wasn't before.
for ip, hostname := range dhcpLeases {
for _, port := range globalSettings.GDLOutputPorts {
ipAndPort := ip + ":" + strconv.Itoa(int(port))
for _, networkOutput := range globalSettings.NetworkOutputs {
ipAndPort := ip + ":" + strconv.Itoa(int(networkOutput.Port))
if _, ok := outSockets[ipAndPort]; !ok {
log.Printf("client connected: %s:%d (%s).\n", ip, port, hostname)
log.Printf("client connected: %s:%d (%s).\n", ip, networkOutput.Port, hostname)
addr, err := net.ResolveUDPAddr("udp", ipAndPort)
if err != nil {
log.Printf("ResolveUDPAddr(%s): %s\n", ipAndPort, err.Error())
@ -79,7 +102,7 @@ func refreshConnectedClients() {
log.Printf("DialUDP(%s): %s\n", ipAndPort, err.Error())
continue
}
outSockets[ipAndPort] = outConn
outSockets[ipAndPort] = networkConnection{outConn, ip, networkOutput.Port, networkOutput.Capability}
}
validConnections[ipAndPort] = true
}
@ -88,36 +111,57 @@ func refreshConnectedClients() {
for ipAndPort, conn := range outSockets {
if _, ok := validConnections[ipAndPort]; !ok {
log.Printf("removed connection %s.\n", ipAndPort)
conn.Close()
conn.Conn.Close()
delete(outSockets, ipAndPort)
}
}
}
func messageQueueSender() {
secondTimer := time.NewTicker(1 * time.Second)
dhcpRefresh := time.NewTicker(30 * time.Second)
secondTimer := time.NewTicker(5 * time.Second)
for {
select {
case msg := <-messageQueue:
sendToAllConnectedClients(msg)
case <-secondTimer.C:
getNetworkStats()
case <-dhcpRefresh.C:
refreshConnectedClients()
}
}
}
func sendMsg(msg []byte) {
messageQueue <- msg
func sendMsg(msg []byte, msgType uint8) {
messageQueue <- networkMessage{msg, msgType}
}
func sendGDL90(msg []byte) {
sendMsg(msg, NETWORK_GDL90)
}
func monitorDHCPLeases() {
watcher, err := inotify.NewWatcher()
if err != nil {
log.Fatal(err)
}
err = watcher.AddWatch(dhcp_lease_file, inotify.IN_CLOSE_WRITE)
if err != nil {
log.Fatal(err)
}
for {
select {
case <-watcher.Event:
log.Println("file modified, attempting to refresh DHCP")
refreshConnectedClients()
case err := <-watcher.Error:
log.Println("error with DHCP file system watcher:", err)
}
}
}
func initNetwork() {
messageQueue = make(chan []byte, 1024) // Buffered channel, 1024 messages.
outSockets = make(map[string]*net.UDPConn)
messageQueue = make(chan networkMessage, 1024) // Buffered channel, 1024 messages.
outSockets = make(map[string]networkConnection)
netMutex = &sync.Mutex{}
refreshConnectedClients()
go monitorDHCPLeases()
go messageQueueSender()
}

Wyświetl plik

@ -1,18 +1,25 @@
package main
import (
"fmt"
"log"
"strconv"
"strings"
"sync"
"time"
"github.com/kidoman/embd"
_ "github.com/kidoman/embd/host/all"
"github.com/kidoman/embd/sensor/bmp180"
"github.com/tarm/serial"
"./mpu6050"
)
type GPSData struct {
type SituationData struct {
mu_GPS *sync.Mutex
// From GPS.
lastFixSinceMidnightUTC uint32
lat float32
lng float32
@ -25,12 +32,25 @@ type GPSData struct {
trueCourse uint16
groundSpeed uint16
lastGroundTrackTime time.Time
mu_Attitude *sync.Mutex
// From BMP180 pressure sensor.
temp float64
pressure_alt float64
lastTempPressTime time.Time
// From MPU6050 accel/gyro.
pitch float64
roll float64
gyro_heading float64
lastAttitudeTime time.Time
}
var serialConfig *serial.Config
var serialPort *serial.Port
func initGPSSerialReader() bool {
func initGPSSerial() bool {
serialConfig = &serial.Config{Name: "/dev/ttyACM0", Baud: 9600}
p, err := serial.OpenPort(serialConfig)
if err != nil {
@ -44,6 +64,8 @@ func initGPSSerialReader() bool {
func processNMEALine(l string) bool {
x := strings.Split(l, ",")
if x[0] == "$GNVTG" { // Ground track information.
mySituation.mu_GPS.Lock()
defer mySituation.mu_GPS.Unlock()
if len(x) < 10 {
return false
}
@ -54,11 +76,15 @@ func processNMEALine(l string) bool {
return false
}
trueCourse = uint16(tc)
//FIXME: Experimental. Set heading to true heading on the MPU6050 reader.
if myMPU6050 != nil && globalStatus.RY835AI_connected && globalSettings.AHRS_Enabled {
myMPU6050.ResetHeading(float64(tc))
}
} else {
// No movement.
myGPS.trueCourse = 0
myGPS.groundSpeed = 0
myGPS.lastGroundTrackTime = time.Time{}
mySituation.trueCourse = 0
mySituation.groundSpeed = 0
mySituation.lastGroundTrackTime = time.Time{}
return true
}
groundSpeed, err := strconv.ParseFloat(x[5], 32) // Knots.
@ -66,17 +92,16 @@ func processNMEALine(l string) bool {
return false
}
myGPS.trueCourse = uint16(trueCourse)
myGPS.groundSpeed = uint16(groundSpeed)
myGPS.lastGroundTrackTime = time.Now()
mySituation.trueCourse = uint16(trueCourse)
mySituation.groundSpeed = uint16(groundSpeed)
mySituation.lastGroundTrackTime = time.Now()
} else if x[0] == "$GNGGA" { // GPS fix.
if len(x) < 15 {
return false
}
var fix GPSData
fix = myGPS
mySituation.mu_GPS.Lock()
defer mySituation.mu_GPS.Unlock()
// Timestamp.
if len(x[1]) < 9 {
return false
@ -88,7 +113,7 @@ func processNMEALine(l string) bool {
return false
}
fix.lastFixSinceMidnightUTC = uint32((hr * 60 * 60) + (min * 60) + sec)
mySituation.lastFixSinceMidnightUTC = uint32((hr * 60 * 60) + (min * 60) + sec)
// Latitude.
if len(x[2]) < 10 {
@ -100,9 +125,9 @@ func processNMEALine(l string) bool {
return false
}
fix.lat = float32(hr) + float32(minf/60.0)
mySituation.lat = float32(hr) + float32(minf/60.0)
if x[3] == "S" { // South = negative.
fix.lat = -fix.lat
mySituation.lat = -mySituation.lat
}
// Longitude.
@ -115,9 +140,9 @@ func processNMEALine(l string) bool {
return false
}
fix.lng = float32(hr) + float32(minf/60.0)
mySituation.lng = float32(hr) + float32(minf/60.0)
if x[5] == "W" { // West = negative.
fix.lng = -fix.lng
mySituation.lng = -mySituation.lng
}
// Quality indicator.
@ -125,36 +150,34 @@ func processNMEALine(l string) bool {
if err1 != nil {
return false
}
fix.quality = uint8(q)
mySituation.quality = uint8(q)
// Satellites.
sat, err1 := strconv.Atoi(x[7])
if err1 != nil {
return false
}
fix.satellites = uint16(sat)
mySituation.satellites = uint16(sat)
// Accuracy.
hdop, err1 := strconv.ParseFloat(x[8], 32)
if err1 != nil {
return false
}
fix.accuracy = float32(hdop * 5.0) //FIXME: 5 meters ~ 1.0 HDOP?
mySituation.accuracy = float32(hdop * 5.0) //FIXME: 5 meters ~ 1.0 HDOP?
// Altitude.
alt, err1 := strconv.ParseFloat(x[9], 32)
if err1 != nil {
return false
}
fix.alt = float32(alt * 3.28084) // Covnert to feet.
mySituation.alt = float32(alt * 3.28084) // Covnert to feet.
//TODO: Altitude accuracy.
fix.alt_accuracy = 0
mySituation.alt_accuracy = 0
// Timestamp.
fix.lastFixLocalTime = time.Now()
myGPS = fix
mySituation.lastFixLocalTime = time.Now()
}
return true
@ -162,15 +185,13 @@ func processNMEALine(l string) bool {
func gpsSerialReader() {
defer serialPort.Close()
buf := make([]byte, 1024)
for {
if !globalSettings.GPS_Enabled { // GPS was turned off. Shut down.
break
}
for globalSettings.GPS_Enabled && globalStatus.GPS_connected {
buf := make([]byte, 1024)
n, err := serialPort.Read(buf)
if err != nil {
log.Printf("gps unit read error: %s\n", err.Error())
return
log.Printf("gps serial read error: %s\n", err.Error())
globalStatus.GPS_connected = false
break
}
s := string(buf[:n])
x := strings.Split(s, "\n")
@ -178,32 +199,158 @@ func gpsSerialReader() {
processNMEALine(l)
}
}
globalStatus.GPS_connected = false
}
func gpsReader() {
if initGPSSerialReader() {
gpsSerialReader()
} else {
globalSettings.GPS_Enabled = false
}
}
var bus embd.I2CBus
var i2csensor *bmp180.BMP180
var i2cbus embd.I2CBus
var myBMP180 *bmp180.BMP180
var myMPU6050 *mpu6050.MPU6050
func readBMP180() (float64, float64, error) { // ºCelsius, Meters
temp, err := i2csensor.Temperature()
temp, err := myBMP180.Temperature()
if err != nil {
return temp, 0.0, err
}
altitude, err := i2csensor.Altitude()
altitude, err := myBMP180.Altitude()
altitude = float64(1/0.3048) * altitude // Convert meters to feet.
if err != nil {
return temp, altitude, err
}
return temp, altitude, nil
}
func initBMP180() {
bus = embd.NewI2CBus(1)
i2csensor = bmp180.New(bus)
func readMPU6050() (float64, float64, error) { //TODO: error checking.
pitch, roll := myMPU6050.PitchAndRoll()
return pitch, roll, nil
}
func initBMP180() error {
myBMP180 = bmp180.New(i2cbus) //TODO: error checking.
return nil
}
func initMPU6050() error {
myMPU6050 = mpu6050.New(i2cbus) //TODO: error checking.
return nil
}
func initI2C() error {
i2cbus = embd.NewI2CBus(1) //TODO: error checking.
return nil
}
// Unused at the moment. 5 second update, since read functions in bmp180 are slow.
func tempAndPressureReader() {
timer := time.NewTicker(5 * time.Second)
for globalStatus.RY835AI_connected && globalSettings.AHRS_Enabled {
<-timer.C
// Read temperature and pressure altitude.
temp, alt, err_bmp180 := readBMP180()
// Process.
if err_bmp180 != nil {
log.Printf("readBMP180(): %s\n", err_bmp180.Error())
globalStatus.RY835AI_connected = false
} else {
mySituation.temp = temp
mySituation.pressure_alt = alt
mySituation.lastTempPressTime = time.Now()
}
}
globalStatus.RY835AI_connected = false
}
func attitudeReaderSender() {
timer := time.NewTicker(100 * time.Millisecond) // ~10Hz update.
for globalStatus.RY835AI_connected && globalSettings.AHRS_Enabled {
<-timer.C
// Read pitch and roll.
pitch, roll, err_mpu6050 := readMPU6050()
mySituation.mu_Attitude.Lock()
if err_mpu6050 != nil {
log.Printf("readMPU6050(): %s\n", err_mpu6050.Error())
globalStatus.RY835AI_connected = false
break
} else {
mySituation.pitch = pitch
mySituation.roll = roll
mySituation.gyro_heading = myMPU6050.Heading() //FIXME. Experimental.
mySituation.lastAttitudeTime = time.Now()
}
// Send, if valid.
// if isGPSGroundTrackValid(), etc.
s := fmt.Sprintf("XATTStratux,%f,%f,%f", mySituation.gyro_heading, mySituation.pitch, mySituation.roll)
sendMsg([]byte(s), NETWORK_AHRS)
mySituation.mu_Attitude.Unlock()
}
globalStatus.RY835AI_connected = false
}
func isGPSValid() bool {
return time.Since(mySituation.lastFixLocalTime).Seconds() < 15
}
func isGPSGroundTrackValid() bool {
return time.Since(mySituation.lastGroundTrackTime).Seconds() < 15
}
func isAHRSValid() bool {
return time.Since(mySituation.lastAttitudeTime).Seconds() < 1 // If attitude information gets to be over 1 second old, declare invalid.
}
func isTempPressValid() bool {
return time.Since(mySituation.lastTempPressTime).Seconds() < 15
}
func initAHRS() error {
if err := initI2C(); err != nil { // I2C bus.
return err
}
if err := initBMP180(); err != nil { // I2C temperature and pressure altitude.
i2cbus.Close()
return err
}
if err := initMPU6050(); err != nil { // I2C accel/gyro.
i2cbus.Close()
myBMP180.Close()
return err
}
globalStatus.RY835AI_connected = true
go attitudeReaderSender()
go tempAndPressureReader()
return nil
}
func pollRY835AI() {
timer := time.NewTicker(10 * time.Second)
for {
<-timer.C
// GPS enabled, was not connected previously?
if globalSettings.GPS_Enabled && !globalStatus.GPS_connected {
globalStatus.GPS_connected = initGPSSerial() // via USB for now.
if globalStatus.GPS_connected {
go gpsSerialReader()
}
}
// RY835AI I2C enabled, was not connected previously?
if globalSettings.AHRS_Enabled && !globalStatus.RY835AI_connected {
err := initAHRS()
if err != nil {
log.Printf("initAHRS(): %s\ndisabling AHRS sensors.\n", err.Error())
globalStatus.RY835AI_connected = false
}
}
}
}
func initRY835AI() {
mySituation.mu_GPS = &sync.Mutex{}
mySituation.mu_Attitude = &sync.Mutex{}
go pollRY835AI()
}

Wyświetl plik

@ -1,12 +1,12 @@
package main
import (
"./mpu6050"
"fmt"
"github.com/kidoman/embd"
_ "github.com/kidoman/embd/host/all"
"./mpu6050"
"time"
"net"
"time"
)
var bus embd.I2CBus
@ -32,9 +32,9 @@ func main() {
outConn, err := net.DialUDP("udp", nil, addr)
for {
pitch, roll := readMPU6050()
s := fmt.Sprintf("XATTMy Sim,180.0,%f,%f", pitch, roll)
s := fmt.Sprintf("XATTMy Sim,%f,%f,%f", attSensor.Heading(), pitch, roll)
fmt.Printf("%f, %f\n", pitch, roll)
outConn.Write([]byte(s))
time.Sleep(50 * time.Millisecond)
}
}
}

Wyświetl plik

@ -1,8 +1,13 @@
package main
import (
"bufio"
"encoding/hex"
"log"
"math"
"net"
"strconv"
"strings"
"sync"
"time"
)
@ -45,8 +50,9 @@ AUXSV:
*/
type TrafficInfo struct {
icao_addr uint32
addr_type uint8
icao_addr uint32
addr_type uint8
emitter_category uint8
lat float32
lng float32
@ -70,10 +76,8 @@ var traffic map[uint32]TrafficInfo
var trafficMutex *sync.Mutex
func cleanupOldEntries() {
trafficMutex.Lock()
defer trafficMutex.Unlock()
for icao_addr, ti := range traffic {
if time.Since(ti.last_seen).Seconds() > float64(60) { //FIXME: 60 seconds with no update on this address - stop displaying.
if time.Since(ti.last_seen).Seconds() > float64(60.0) { //FIXME: 60 seconds with no update on this address - stop displaying.
delete(traffic, icao_addr)
}
}
@ -84,15 +88,12 @@ func sendTrafficUpdates() {
defer trafficMutex.Unlock()
cleanupOldEntries()
for _, ti := range traffic {
makeTrafficReport(ti)
if ti.position_valid {
makeTrafficReport(ti)
}
}
}
func initTraffic() {
traffic = make(map[uint32]TrafficInfo)
trafficMutex = &sync.Mutex{}
}
func makeTrafficReport(ti TrafficInfo) {
msg := make([]byte, 28)
// See p.16.
@ -146,9 +147,20 @@ func makeTrafficReport(ti TrafficInfo) {
trk := uint8(float32(ti.track) / TRACK_RESOLUTION) // Resolution is ~1.4 degrees.
msg[17] = byte(trk)
msg[18] = 0x01 // "light"
msg[18] = ti.emitter_category
sendMsg(prepareMessage(msg))
// 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.
c = byte(20)
}
msg[19+i] = c
}
//TODO: text identifier (tail).
sendGDL90(prepareMessage(msg))
}
func parseDownlinkReport(s string) {
@ -158,9 +170,24 @@ func parseDownlinkReport(s string) {
hex.Decode(frame, []byte(s))
// Header.
// msg_type := (uint8(frame[0]) >> 3) & 0x1f
msg_type := (uint8(frame[0]) >> 3) & 0x1f
// Extract emitter category.
if msg_type == 1 || msg_type == 3 {
v := (uint16(frame[17]) << 8) | (uint16(frame[18]))
ti.emitter_category = uint8((v / 1600) % 40)
}
icao_addr := (uint32(frame[1]) << 16) | (uint32(frame[2]) << 8) | uint32(frame[3])
trafficMutex.Lock()
defer trafficMutex.Unlock()
if curTi, ok := traffic[icao_addr]; ok { // Retrieve the current entry, as it may contain some useful information like "tail" from 1090ES.
ti = curTi
}
ti.icao_addr = icao_addr
ti.addr_type = uint8(frame[0]) & 0x07
ti.icao_addr = (uint32(frame[1]) << 16) | (uint32(frame[2]) << 8) | uint32(frame[3])
// OK.
// fmt.Printf("%d, %d, %06X\n", msg_type, ti.addr_type, ti.icao_addr)
@ -235,14 +262,14 @@ func parseDownlinkReport(s string) {
if (raw_ew & 0x400) != 0 {
ew_vel = 0 - ew_vel
}
if airground_state == 1 { // Supersonic
if airground_state == 1 { // Supersonic.
ew_vel = ew_vel * 4
}
}
if ns_vel_valid && ew_vel_valid {
if ns_vel != 0 && ew_vel != 0 {
//TODO: Track type
track = (360 + 90 - uint16(math.Atan2(float64(ns_vel), float64(ew_vel))*180/math.Pi)) % 360
track = (360 + 90 - (uint16(math.Atan2(float64(ns_vel), float64(ew_vel)) * 180 / math.Pi))) % 360
}
speed_valid = true
speed = uint16(math.Sqrt(float64((ns_vel * ns_vel) + (ew_vel * ew_vel))))
@ -258,8 +285,18 @@ func parseDownlinkReport(s string) {
}
}
} else if airground_state == 2 { // Ground vehicle.
//TODO.
return
raw_gs := ((uint16(frame[12]) & 0x1f) << 6) | ((uint16(frame[13]) & 0xfc) >> 2)
if raw_gs != 0 {
speed_valid = true
speed = ((raw_gs & 0x3ff) - 1)
}
raw_track := ((uint16(frame[13]) & 0x03) << 9) | (uint16(frame[14]) << 1) | ((uint16(frame[15]) & 0x80) >> 7)
//tt := ((raw_track & 0x0600) >> 9)
//FIXME: tt == 1 TT_TRACK. tt == 2 TT_MAG_HEADING. tt == 3 TT_TRUE_HEADING.
track = uint16((raw_track & 0x1ff) * 360 / 512)
// Dimensions of vehicle - skip.
}
ti.track = track
@ -286,75 +323,159 @@ func parseDownlinkReport(s string) {
ti.last_seen = time.Now()
trafficMutex.Lock()
// 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
}
traffic[ti.icao_addr] = ti
trafficMutex.Unlock()
}
//TODO
/*
// dump1090Addr = "127.0.0.1:30003"
inConn, err := net.Dial("tcp", dump1090Addr)
if err != nil {
time.Sleep(1 * time.Second)
continue
func esListen() {
for {
if !globalSettings.ES_Enabled {
time.Sleep(1 * time.Second) // Don't do much unless ES is actually enabled.
continue
}
dump1090Addr := "127.0.0.1:30003"
inConn, err := net.Dial("tcp", dump1090Addr)
if err != nil { // Local connection failed.
time.Sleep(1 * time.Second)
continue
}
rdr := bufio.NewReader(inConn)
for {
buf, err := rdr.ReadString('\n')
if err != nil { // Must have disconnected?
break
}
buf = strings.Trim(buf, "\r\n")
//log.Printf("%s\n", buf)
x := strings.Split(buf, ",")
if len(x) < 22 {
continue
}
icao := x[4]
icaoDecf, err := strconv.ParseInt(icao, 16, 32)
if err != nil {
continue
}
icaoDec := uint32(icaoDecf)
trafficMutex.Lock()
// Retrieve previous information on this ICAO code.
var ti TrafficInfo
if val, ok := traffic[icaoDec]; ok {
ti = val
}
ti.icao_addr = icaoDec
//FIXME: Some stale information will be renewed.
valid_change := true
if x[1] == "3" {
//MSG,3,111,11111,AC2BB7,111111,2015/07/28,03:59:12.363,2015/07/28,03:59:12.353,,5550,,,42.35847,-83.42212,,,,,,0
//MSG,3,111,11111,A5D007,111111, , , , ,,35000,,,42.47454,-82.57433,,,0,0,0,0
alt := x[11]
lat := x[14]
lng := x[15]
if len(alt) == 0 || len(lat) == 0 || len(lng) == 0 { //FIXME.
valid_change = false
}
altFloat, err := strconv.ParseFloat(alt, 32)
if err != nil {
log.Printf("err parsing alt (%s): %s\n", alt, err.Error())
valid_change = false
}
latFloat, err := strconv.ParseFloat(lat, 32)
if err != nil {
log.Printf("err parsing lat (%s): %s\n", lat, err.Error())
valid_change = false
}
lngFloat, err := strconv.ParseFloat(lng, 32)
if err != nil {
log.Printf("err parsing lng (%s): %s\n", lng, err.Error())
valid_change = false
}
//log.Printf("icao=%s, icaoDec=%d, alt=%s, lat=%s, lng=%s\n", icao, icaoDec, alt, lat, lng)
if valid_change {
ti.alt = uint32(altFloat)
ti.lat = float32(latFloat)
ti.lng = float32(lngFloat)
ti.position_valid = true
}
}
if x[1] == "4" {
// MSG,4,111,11111,A3B557,111111,2015/07/28,06:13:36.417,2015/07/28,06:13:36.398,,,414,278,,,-64,,,,,0
speed := x[12]
track := x[13]
vvel := x[16]
if len(speed) == 0 || len(track) == 0 || len(vvel) == 0 {
valid_change = false
}
speedFloat, err := strconv.ParseFloat(speed, 32)
if err != nil {
log.Printf("err parsing speed (%s): %s\n", speed, err.Error())
valid_change = false
}
trackFloat, err := strconv.ParseFloat(track, 32)
if err != nil {
log.Printf("err parsing track (%s): %s\n", track, err.Error())
valid_change = false
}
vvelFloat, err := strconv.ParseFloat(vvel, 32)
if err != nil {
log.Printf("err parsing vvel (%s): %s\n", vvel, err.Error())
valid_change = false
}
//log.Printf("icao=%s, icaoDec=%d, vel=%s, hdg=%s, vr=%s\n", icao, icaoDec, vel, hdg, vr)
if valid_change {
ti.speed = uint16(speedFloat)
ti.track = uint16(trackFloat)
ti.vvel = int16(vvelFloat)
ti.speed_valid = true
}
}
if x[1] == "1" {
// MSG,1,,,%02X%02X%02X,,,,,,%s,,,,,,,,0,0,0,0
tail := x[10]
if len(tail) == 0 {
valid_change = false
}
if valid_change {
ti.tail = tail
}
}
// Update "last seen" (any type of message, as long as the ICAO addr can be parsed).
ti.last_seen = time.Now()
ti.addr_type = 0 //FIXME: ADS-B with ICAO address. Not recognized by ForeFlight.
ti.emitter_category = 0x01 //FIXME. "Light"
// This is a hack to show the source of the traffic in ForeFlight.
ti.tail = strings.Trim(ti.tail, " ")
if len(ti.tail) == 0 || (len(ti.tail) != 0 && len(ti.tail) < 8 && ti.tail[0] != 'E') {
ti.tail = "e" + ti.tail
}
traffic[icaoDec] = ti // Update information on this ICAO code.
trafficMutex.Unlock()
}
}
}
rdr := bufio.NewReader(inConn)
for {
buf, err := rdr.ReadString('\n')
if err != nil { // Must have disconnected?
break
}
buf = strings.Trim(buf, "\r\n")
//log.Printf("%s\n", buf)
x := strings.Split(buf, ",")
//TODO: Add more sophisticated stuff that combines heading/speed updates with the location.
if len(x) < 22 {
continue
}
icao := x[4]
icaoDec, err := strconv.ParseInt(icao, 16, 32)
if err != nil {
continue
}
mutex.Lock()
// Retrieve previous information on this ICAO code.
var pi PositionInfo
if _, ok := blips[icaoDec]; ok {
pi = blips[icaoDec]
}
if x[1] == "3" {
//MSG,3,111,11111,AC2BB7,111111,2015/07/28,03:59:12.363,2015/07/28,03:59:12.353,,5550,,,42.35847,-83.42212,,,,,,0
alt := x[11]
lat := x[14]
lng := x[15]
//log.Printf("icao=%s, icaoDec=%d, alt=%s, lat=%s, lng=%s\n", icao, icaoDec, alt, lat, lng)
pi.alt = alt
pi.lat = lat
pi.lng = lng
}
if x[1] == "4" {
// MSG,4,111,11111,A3B557,111111,2015/07/28,06:13:36.417,2015/07/28,06:13:36.398,,,414,278,,,-64,,,,,0
vel := x[12]
hdg := x[13]
vr := x[16]
//log.Printf("icao=%s, icaoDec=%d, vel=%s, hdg=%s, vr=%s\n", icao, icaoDec, vel, hdg, vr)
pi.vel = vel
pi.hdg = hdg
pi.vr = vr
}
if x[1] == "1" {
// MSG,1,,,%02X%02X%02X,,,,,,%s,,,,,,,,0,0,0,0
tail := x[10]
pi.tail = tail
}
// Update "last seen" (any type of message).
pi.last_seen = time.Now()
blips[icaoDec] = pi // Update information on this ICAO code.
mutex.Unlock()
*/
func initTraffic() {
traffic = make(map[uint32]TrafficInfo)
trafficMutex = &sync.Mutex{}
go esListen()
}

218
uat_read.go 100644
Wyświetl plik

@ -0,0 +1,218 @@
// +build ignore
package main
import (
"errors"
// "fmt"
"./godump978"
"log"
"os"
"os/signal"
"syscall"
rtl "github.com/jpoirier/gortlsdr"
// "unsafe"
"fmt"
)
func sigAbort(dev *rtl.Context) {
ch := make(chan os.Signal)
signal.Notify(ch, syscall.SIGINT)
<-ch
_ = dev.CancelAsync()
dev.Close()
os.Exit(0)
}
func printUAT() {
for {
uat := <-dump978.OutChan
log.Printf("dump978: %s\n", string(uat))
fmt.Printf("%s;\n", uat)
}
}
func main() {
var err error
var dev *rtl.Context
//---------- Device Check ----------
if c := rtl.GetDeviceCount(); c == 0 {
log.Fatal("No devices found, exiting.\n")
} else {
for i := 0; i < c; i++ {
m, p, s, err := rtl.GetDeviceUsbStrings(i)
if err == nil {
err = errors.New("")
}
log.Printf("GetDeviceUsbStrings %s - %s %s %s\n",
err, m, p, s)
}
}
log.Printf("===== Device name: %s =====\n", rtl.GetDeviceName(0))
log.Printf("===== Running tests using device indx: 0 =====\n")
//---------- Open Device ----------
if dev, err = rtl.Open(0); err != nil {
log.Fatal("\tOpen Failed, exiting\n")
}
defer dev.Close()
go sigAbort(dev)
//---------- Device Strings ----------
m, p, s, err := dev.GetUsbStrings()
if err != nil {
log.Printf("\tGetUsbStrings Failed - error: %s\n", err)
} else {
log.Printf("\tGetUsbStrings - %s %s %s\n", m, p, s)
}
log.Printf("\tGetTunerType: %s\n", dev.GetTunerType())
//---------- Set Tuner Gain ----------
tgain := 480
err = dev.SetTunerGainMode(true)
if err != nil {
log.Printf("\tSetTunerGainMode Failed - error: %s\n", err)
} else {
log.Printf("\tSetTunerGainMode Successful\n")
}
err = dev.SetTunerGain(tgain)
if err != nil {
log.Printf("\tSetTunerGain Failed - error: %s\n", err)
} else {
log.Printf("\tSetTunerGain Successful\n")
}
//---------- Get/Set Sample Rate ----------
samplerate := 2083334
err = dev.SetSampleRate(samplerate)
if err != nil {
log.Printf("\tSetSampleRate Failed - error: %s\n", err)
} else {
log.Printf("\tSetSampleRate - rate: %d\n", samplerate)
}
log.Printf("\tGetSampleRate: %d\n", dev.GetSampleRate())
//---------- Get/Set Xtal Freq ----------
rtlFreq, tunerFreq, err := dev.GetXtalFreq()
if err != nil {
log.Printf("\tGetXtalFreq Failed - error: %s\n", err)
} else {
log.Printf("\tGetXtalFreq - Rtl: %d, Tuner: %d\n", rtlFreq, tunerFreq)
}
newRTLFreq := 28800000
newTunerFreq := 28800000
err = dev.SetXtalFreq(newRTLFreq, newTunerFreq)
if err != nil {
log.Printf("\tSetXtalFreq Failed - error: %s\n", err)
} else {
log.Printf("\tSetXtalFreq - Center freq: %d, Tuner freq: %d\n",
newRTLFreq, newTunerFreq)
}
//---------- Get/Set Center Freq ----------
err = dev.SetCenterFreq(978000000)
if err != nil {
log.Printf("\tSetCenterFreq 978MHz Failed, error: %s\n", err)
} else {
log.Printf("\tSetCenterFreq 978MHz Successful\n")
}
log.Printf("\tGetCenterFreq: %d\n", dev.GetCenterFreq())
//---------- Set Bandwidth ----------
bw := 1000000
log.Printf("\tSetting Bandwidth: %d\n", bw)
if err = dev.SetTunerBw(bw); err != nil {
log.Printf("\tSetTunerBw %d Failed, error: %s\n", bw, err)
} else {
log.Printf("\tSetTunerBw %d Successful\n", bw)
}
/*
//---------- Get/Set Freq Correction ----------
freqCorr := dev.GetFreqCorrection()
log.Printf("\tGetFreqCorrection: %d\n", freqCorr)
err = dev.SetFreqCorrection(0) // 10ppm
if err != nil {
log.Printf("\tSetFreqCorrection %d Failed, error: %s\n", 0, err)
} else {
log.Printf("\tSetFreqCorrection %d Successful\n", 0)
}
//---------- Get/Set AGC Mode ----------
if err = dev.SetAgcMode(false); err == nil {
log.Printf("\tSetAgcMode off Successful\n")
} else {
log.Printf("\tSetAgcMode Failed, error: %s\n", err)
}
//---------- Get/Set Direct Sampling ----------
if mode, err := dev.GetDirectSampling(); err == nil {
log.Printf("\tGetDirectSampling Successful, mode: %s\n",
rtl.SamplingModes[mode])
} else {
log.Printf("\tSetTestMode 'On' Failed - error: %s\n", err)
}
if err = dev.SetDirectSampling(rtl.SamplingNone); err == nil {
log.Printf("\tSetDirectSampling 'On' Successful\n")
} else {
log.Printf("\tSetDirectSampling 'On' Failed - error: %s\n", err)
}
*/
//---------- Get/Set Tuner IF Gain ----------
// if err = SetTunerIfGain(stage, gain: int); err == nil {
// log.Printf("\SetTunerIfGain Successful\n")
// } else {
// log.Printf("\tSetTunerIfGain Failed - error: %s\n", err)
// }
/*
//---------- Get/Set test mode ----------
if err = dev.SetTestMode(true); err == nil {
log.Printf("\tSetTestMode 'On' Successful\n")
} else {
log.Printf("\tSetTestMode 'On' Failed - error: %s\n", err)
}
if err = dev.SetTestMode(false); err == nil {
log.Printf("\tSetTestMode 'Off' Successful\n")
} else {
log.Printf("\tSetTestMode 'Off' Fail - error: %s\n", err)
}
*/
//---------- Get/Set misc. streaming ----------
dump978.Dump978Init()
go printUAT()
go dump978.ProcessDataFromChannel()
if err = dev.ResetBuffer(); err == nil {
log.Printf("\tResetBuffer Successful\n")
} else {
log.Printf("\tResetBuffer Failed - error: %s\n", err)
}
for {
var buffer = make([]uint8, rtl.DefaultBufLength)
nRead, err := dev.ReadSync(buffer, rtl.DefaultBufLength)
if err != nil {
log.Printf("\tReadSync Failed - error: %s\n", err)
} else {
log.Printf("\tReadSync %d\n", nRead)
// buf := buffer[:nRead]
// dump978.InChan <- buf
}
}
}