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

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

@ -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
) )
@ -169,7 +169,7 @@ func sensorAttitudeSender() {
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
@ -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 {
@ -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() {