Merge pull request #24 from cyoung/ahrs_dev

Fix nil pointer dereference crash.
pull/592/head
Eric Westphal 2017-03-30 08:12:33 -04:00 zatwierdzone przez GitHub
commit c12aa3e728
4 zmienionych plików z 38 dodań i 38 usunięć

Wyświetl plik

@ -39,8 +39,8 @@ import (
// https://www.faa.gov/nextgen/programs/adsb/Archival/ // https://www.faa.gov/nextgen/programs/adsb/Archival/
// https://www.faa.gov/nextgen/programs/adsb/Archival/media/GDL90_Public_ICD_RevA.PDF // https://www.faa.gov/nextgen/programs/adsb/Archival/media/GDL90_Public_ICD_RevA.PDF
var logDirf string // Directory for all logging var logDirf string // Directory for all logging
var debugLogf string // Set according to OS config. var debugLogf string // Set according to OS config.
var dataLogFilef string // Set according to OS config. var dataLogFilef string // Set according to OS config.
const ( const (

Wyświetl plik

@ -276,13 +276,13 @@ func handleSettingsSetRequest(w http.ResponseWriter, r *http.Request) {
globalSettings.GPS_Enabled = val.(bool) globalSettings.GPS_Enabled = val.(bool)
case "IMU_Sensor_Enabled": case "IMU_Sensor_Enabled":
globalSettings.IMU_Sensor_Enabled = val.(bool) globalSettings.IMU_Sensor_Enabled = val.(bool)
if !globalSettings.IMU_Sensor_Enabled { if !globalSettings.IMU_Sensor_Enabled && globalStatus.IMUConnected {
myIMUReader.Close() myIMUReader.Close()
globalStatus.IMUConnected = false globalStatus.IMUConnected = false
} }
case "BMP_Sensor_Enabled": case "BMP_Sensor_Enabled":
globalSettings.BMP_Sensor_Enabled = val.(bool) globalSettings.BMP_Sensor_Enabled = val.(bool)
if !globalSettings.BMP_Sensor_Enabled { if !globalSettings.BMP_Sensor_Enabled && globalStatus.BMPConnected {
myPressureReader.Close() myPressureReader.Close()
globalStatus.BMPConnected = false globalStatus.BMPConnected = false
} }
@ -397,8 +397,8 @@ func handleOrientAHRS(w http.ResponseWriter, r *http.Request) {
if r.Method == "POST" { if r.Method == "POST" {
var ( var (
action []byte = make([]byte, 1) action []byte = make([]byte, 1)
u int u int
err error err error
) )
if _, err = r.Body.Read(action); err != nil { if _, err = r.Body.Read(action); err != nil {
@ -422,7 +422,7 @@ func handleOrientAHRS(w http.ResponseWriter, r *http.Request) {
} }
log.Printf("AHRS Info: sensor orientation: received up direction %d\n", u) log.Printf("AHRS Info: sensor orientation: received up direction %d\n", u)
if f==u || f==-u { if f == u || f == -u {
log.Println("AHRS Error: sensor orientation: up and forward axes cannot be the same") log.Println("AHRS Error: sensor orientation: up and forward axes cannot be the same")
http.Error(w, "up and forward axes cannot be the same", http.StatusBadRequest) http.Error(w, "up and forward axes cannot be the same", http.StatusBadRequest)
return return

Wyświetl plik

@ -66,7 +66,7 @@ var netMutex *sync.RWMutex
var totalNetworkMessagesSent uint32 var totalNetworkMessagesSent uint32
var pingResponse map[string]time.Time // Last time an IP responded to an "echo" response. var pingResponse map[string]time.Time // Last time an IP responded to an "echo" response.
var pingResponseMutex *sync.RWMutex // For versions of Go after 1.6 we need to protect this map from concurrent reads & writes var pingResponseMutex *sync.RWMutex // For versions of Go after 1.6 we need to protect this map from concurrent reads & writes
const ( const (
NETWORK_GDL90_STANDARD = 1 NETWORK_GDL90_STANDARD = 1

Wyświetl plik

@ -21,7 +21,7 @@ var (
i2cbus embd.I2CBus i2cbus embd.I2CBus
myPressureReader sensors.PressureReader myPressureReader sensors.PressureReader
myIMUReader sensors.IMUReader myIMUReader sensors.IMUReader
cage chan(bool) cage chan (bool)
analysisLogger *ahrs.AHRSLogger analysisLogger *ahrs.AHRSLogger
ahrsCalibrating bool ahrsCalibrating bool
) )
@ -157,19 +157,19 @@ func initIMU() (ok bool) {
func sensorAttitudeSender() { func sensorAttitudeSender() {
var ( var (
roll, pitch, heading float64 roll, pitch, heading float64
t time.Time t time.Time
s ahrs.AHRSProvider s ahrs.AHRSProvider
m *ahrs.Measurement m *ahrs.Measurement
a1, a2, a3, b1, b2, b3, m1, m2, m3 float64 // IMU measurements a1, a2, a3, b1, b2, b3, m1, m2, m3 float64 // IMU measurements
ff *[3][3]float64 // Sensor orientation matrix ff *[3][3]float64 // Sensor orientation matrix
mpuError, magError error mpuError, magError error
failnum uint8 failnum uint8
) )
log.Println("AHRS Info: initializing new simple AHRS") log.Println("AHRS Info: initializing new simple AHRS")
s = ahrs.InitializeSimple() s = ahrs.InitializeSimple()
m = ahrs.NewMeasurement() m = ahrs.NewMeasurement()
cage = make(chan(bool)) cage = make(chan (bool))
// Set up loggers for analysis // Set up loggers for analysis
ahrswebListener, err := ahrsweb.NewKalmanListener() ahrswebListener, err := ahrsweb.NewKalmanListener()
@ -182,7 +182,7 @@ func sensorAttitudeSender() {
// Need a sampling freq faster than 10Hz // Need a sampling freq faster than 10Hz
timer := time.NewTicker(50 * time.Millisecond) // ~20Hz update. timer := time.NewTicker(50 * time.Millisecond) // ~20Hz update.
for { for {
if globalSettings.IMUMapping[0]==0 { // if unset, default to RY836AI if globalSettings.IMUMapping[0] == 0 { // if unset, default to RY836AI
globalSettings.IMUMapping[0] = -1 // +2 globalSettings.IMUMapping[0] = -1 // +2
globalSettings.IMUMapping[1] = -3 // +3 globalSettings.IMUMapping[1] = -3 // +3
saveSettings() saveSettings()
@ -192,18 +192,18 @@ func sensorAttitudeSender() {
// Set up orientation matrix; a bit ugly for now // Set up orientation matrix; a bit ugly for now
ff = new([3][3]float64) ff = new([3][3]float64)
if f[0] < 0 { if f[0] < 0 {
ff[0][-f[0] - 1] = -1 ff[0][-f[0]-1] = -1
} else { } else {
ff[0][+f[0] - 1] = +1 ff[0][+f[0]-1] = +1
} }
if f[1] < 0 { if f[1] < 0 {
ff[2][-f[1] - 1] = -1 ff[2][-f[1]-1] = -1
} else { } else {
ff[2][+f[1] - 1] = +1 ff[2][+f[1]-1] = +1
} }
ff[1][0] = ff[2][1] * ff[0][2] - ff[2][2] * ff[0][1] ff[1][0] = ff[2][1]*ff[0][2] - ff[2][2]*ff[0][1]
ff[1][1] = ff[2][2] * ff[0][0] - ff[2][0] * ff[0][2] ff[1][1] = ff[2][2]*ff[0][0] - ff[2][0]*ff[0][2]
ff[1][2] = ff[2][0] * ff[0][1] - ff[2][1] * ff[0][0] ff[1][2] = ff[2][0]*ff[0][1] - ff[2][1]*ff[0][0]
failnum = 0 failnum = 0
<-timer.C <-timer.C
@ -223,7 +223,7 @@ func sensorAttitudeSender() {
} }
t = stratuxClock.Time t = stratuxClock.Time
m.T = float64(t.UnixNano() / 1000) / 1e6 m.T = float64(t.UnixNano()/1000) / 1e6
_, b1, b2, b3, a1, a2, a3, m1, m2, m3, mpuError, magError = myIMUReader.Read() _, b1, b2, b3, a1, a2, a3, m1, m2, m3, mpuError, magError = myIMUReader.Read()
// This is how the RY83XAI is wired up // This is how the RY83XAI is wired up
@ -237,12 +237,12 @@ func sensorAttitudeSender() {
m.A1 = -(ff[0][0]*a1 + ff[0][1]*a2 + ff[0][2]*a3) m.A1 = -(ff[0][0]*a1 + ff[0][1]*a2 + ff[0][2]*a3)
m.A2 = -(ff[1][0]*a1 + ff[1][1]*a2 + ff[1][2]*a3) m.A2 = -(ff[1][0]*a1 + ff[1][1]*a2 + ff[1][2]*a3)
m.A3 = -(ff[2][0]*a1 + ff[2][1]*a2 + ff[2][2]*a3) m.A3 = -(ff[2][0]*a1 + ff[2][1]*a2 + ff[2][2]*a3)
m.B1 = ff[0][0]*b1 + ff[0][1]*b2 + ff[0][2]*b3 m.B1 = ff[0][0]*b1 + ff[0][1]*b2 + ff[0][2]*b3
m.B2 = ff[1][0]*b1 + ff[1][1]*b2 + ff[1][2]*b3 m.B2 = ff[1][0]*b1 + ff[1][1]*b2 + ff[1][2]*b3
m.B3 = ff[2][0]*b1 + ff[2][1]*b2 + ff[2][2]*b3 m.B3 = ff[2][0]*b1 + ff[2][1]*b2 + ff[2][2]*b3
m.M1 = ff[0][0]*m1 + ff[0][1]*m2 + ff[0][2]*m3 m.M1 = ff[0][0]*m1 + ff[0][1]*m2 + ff[0][2]*m3
m.M2 = ff[1][0]*m1 + ff[1][1]*m2 + ff[1][2]*m3 m.M2 = ff[1][0]*m1 + ff[1][1]*m2 + ff[1][2]*m3
m.M3 = ff[2][0]*m1 + ff[2][1]*m2 + ff[2][2]*m3 m.M3 = ff[2][0]*m1 + ff[2][1]*m2 + ff[2][2]*m3
m.SValid = mpuError == nil m.SValid = mpuError == nil
m.MValid = magError == nil m.MValid = magError == nil
if mpuError != nil { if mpuError != nil {
@ -263,11 +263,11 @@ func sensorAttitudeSender() {
// Don't necessarily disconnect here, unless AHRSProvider deeply depends on magnetometer // Don't necessarily disconnect here, unless AHRSProvider deeply depends on magnetometer
} }
m.TW = float64(mySituation.LastGroundTrackTime.UnixNano() / 1000) / 1e6 m.TW = float64(mySituation.LastGroundTrackTime.UnixNano()/1000) / 1e6
m.WValid = t.Sub(mySituation.LastGroundTrackTime) < 3000*time.Millisecond m.WValid = t.Sub(mySituation.LastGroundTrackTime) < 3000*time.Millisecond
if m.WValid { if m.WValid {
m.W1 = mySituation.GroundSpeed * math.Sin(float64(mySituation.TrueCourse) * ahrs.Deg) m.W1 = mySituation.GroundSpeed * math.Sin(float64(mySituation.TrueCourse)*ahrs.Deg)
m.W2 = mySituation.GroundSpeed * math.Cos(float64(mySituation.TrueCourse) * ahrs.Deg) m.W2 = mySituation.GroundSpeed * math.Cos(float64(mySituation.TrueCourse)*ahrs.Deg)
if globalSettings.BMP_Sensor_Enabled && globalStatus.BMPConnected { if globalSettings.BMP_Sensor_Enabled && globalStatus.BMPConnected {
m.W3 = mySituation.RateOfClimb * 60 / 6076.12 m.W3 = mySituation.RateOfClimb * 60 / 6076.12
} else { } else {
@ -311,7 +311,7 @@ func sensorAttitudeSender() {
} }
// Log it to csv for analysis // Log it to csv for analysis
if globalSettings.AHRSLog && usage.Usage() < 0.95 { if globalSettings.AHRSLog && usage.Usage() < 0.95 {
if analysisLogger == nil { if analysisLogger == nil {
analysisFilename := filepath.Join(logDirf, fmt.Sprintf("sensors_%s.csv", analysisFilename := filepath.Join(logDirf, fmt.Sprintf("sensors_%s.csv",
time.Now().Format("20060102_150405"))) time.Now().Format("20060102_150405")))
@ -362,7 +362,7 @@ func getMinAccelDirection() (i int, err error) {
// CageAHRS sends a signal to the AHRSProvider that it should be reset. // CageAHRS sends a signal to the AHRSProvider that it should be reset.
func CageAHRS() { func CageAHRS() {
cage<- true cage <- true
} }
func updateAHRSStatus() { func updateAHRSStatus() {