kopia lustrzana https://github.com/cyoung/stratux
Merge branch 'invalid' into eric
commit
84eea16eed
|
@ -1139,9 +1139,8 @@ type status struct {
|
|||
UAT_OTHER_total uint32
|
||||
Errors []string
|
||||
Logfile_Size int64
|
||||
|
||||
BMPConnected bool
|
||||
IMUConnected bool
|
||||
BMPConnected bool
|
||||
IMUConnected bool
|
||||
}
|
||||
|
||||
var globalSettings settings
|
||||
|
|
|
@ -15,7 +15,10 @@ import (
|
|||
"github.com/westphae/goflying/ahrsweb"
|
||||
)
|
||||
|
||||
const numRetries uint8 = 5
|
||||
const (
|
||||
numRetries uint8 = 5
|
||||
invalid float32 = float32(ahrs.Invalid)
|
||||
)
|
||||
|
||||
var (
|
||||
i2cbus embd.I2CBus
|
||||
|
@ -117,6 +120,8 @@ func tempAndPressureSender() {
|
|||
mySituation.muBaro.Unlock()
|
||||
altLast = altitude
|
||||
}
|
||||
mySituation.BaroPressureAltitude = 99999
|
||||
mySituation.BaroVerticalSpeed = 99999
|
||||
}
|
||||
|
||||
func initIMU() (ok bool) {
|
||||
|
@ -245,29 +250,36 @@ func sensorAttitudeSender() {
|
|||
// Run the AHRS calcs
|
||||
s.Compute(m)
|
||||
|
||||
makeAHRSGDL90Report() // Send whether or not valid - the function will invalidate the values as appropriate
|
||||
|
||||
// If we have valid AHRS info, then update mySituation
|
||||
mySituation.muAttitude.Lock()
|
||||
if s.Valid() {
|
||||
mySituation.muAttitude.Lock()
|
||||
|
||||
roll, pitch, heading = s.RollPitchHeading()
|
||||
mySituation.AHRSRoll = float32(roll / ahrs.Deg)
|
||||
mySituation.AHRSPitch = float32(pitch / ahrs.Deg)
|
||||
mySituation.AHRSGyroHeading = float32(heading / ahrs.Deg)
|
||||
|
||||
mySituation.AHRSMagHeading = float32(s.MagHeading())
|
||||
// TODO westphae: until magnetometer calibration is performed, no mag heading
|
||||
mySituation.AHRSMagHeading = invalid
|
||||
mySituation.AHRSSlipSkid = float32(s.SlipSkid())
|
||||
mySituation.AHRSTurnRate = float32(s.RateOfTurn())
|
||||
mySituation.AHRSGLoad = float32(s.GLoad())
|
||||
|
||||
mySituation.AHRSLastAttitudeTime = t
|
||||
mySituation.muAttitude.Unlock()
|
||||
|
||||
// makeFFAHRSSimReport() // simultaneous use of GDL90 and FFSIM not supported in FF 7.5.1 or later. Function definition will be kept for AHRS debugging and future workarounds.
|
||||
} else {
|
||||
s.Reset()
|
||||
mySituation.AHRSRoll = invalid
|
||||
mySituation.AHRSPitch = invalid
|
||||
mySituation.AHRSGyroHeading = invalid
|
||||
mySituation.AHRSMagHeading = invalid
|
||||
mySituation.AHRSSlipSkid = invalid
|
||||
mySituation.AHRSTurnRate = invalid
|
||||
mySituation.AHRSGLoad = invalid
|
||||
mySituation.AHRSLastAttitudeTime = time.Time{}
|
||||
}
|
||||
mySituation.muAttitude.Unlock()
|
||||
|
||||
makeAHRSGDL90Report() // Send whether or not valid - the function will invalidate the values as appropriate
|
||||
// makeFFAHRSSimReport() // Simultaneous use of GDL90 and FFSIM not supported in FF 7.5.1 or later. Function definition will be kept for AHRS debugging and future workarounds.
|
||||
|
||||
// Send to AHRS debugging server:
|
||||
if ahrswebListener != nil {
|
||||
|
|
|
@ -52,7 +52,7 @@
|
|||
</div>
|
||||
<div class="col-xs-9">
|
||||
<div class="row">
|
||||
<strong class="col-xs-3 text-center">Track</strong>
|
||||
<strong class="col-xs-3 text-center">Heading</strong>
|
||||
<strong class="col-xs-3 text-center">Pitch</strong>
|
||||
<strong class="col-xs-3 text-center">Roll</strong>
|
||||
<strong class="col-xs-3 text-center">P-Alt</strong>
|
||||
|
|
|
@ -143,22 +143,55 @@ function GPSCtrl($rootScope, $scope, $state, $http, $interval) {
|
|||
$scope.ahrs_alt = "---";
|
||||
}
|
||||
|
||||
$scope.ahrs_heading = Math.round(situation.AHRSGyroHeading.toFixed(0));
|
||||
// pitch and roll are in degrees
|
||||
$scope.ahrs_pitch = situation.AHRSPitch.toFixed(1);
|
||||
$scope.ahrs_roll = situation.AHRSRoll.toFixed(1);
|
||||
$scope.ahrs_slip_skid = situation.AHRSSlipSkid.toFixed(1);
|
||||
ahrs.update(situation.AHRSPitch, situation.AHRSRoll, situation.AHRSGyroHeading, situation.AHRSSlipSkid);
|
||||
$scope.ahrs_time = Date.parse(situation.AHRSLastAttitudeTime);
|
||||
if ($scope.gps_time - $scope.ahrs_time < 1000) {
|
||||
// pitch, roll and heading are in degrees
|
||||
$scope.ahrs_heading = Math.round(situation.AHRSGyroHeading.toFixed(0));
|
||||
if ($scope.ahrs_heading > 360) {
|
||||
$scope.ahrs_heading = "---";
|
||||
}
|
||||
$scope.ahrs_pitch = situation.AHRSPitch.toFixed(1);
|
||||
if ($scope.ahrs_pitch > 360) {
|
||||
$scope.ahrs_pitch = "--";
|
||||
}
|
||||
$scope.ahrs_roll = situation.AHRSRoll.toFixed(1);
|
||||
if ($scope.ahrs_roll > 360) {
|
||||
$scope.ahrs_roll = "--";
|
||||
}
|
||||
$scope.ahrs_slip_skid = situation.AHRSSlipSkid.toFixed(1);
|
||||
if ($scope.ahrs_slip_skid > 360) {
|
||||
$scope.ahrs_slip_skid = "--";
|
||||
}
|
||||
ahrs.update(situation.AHRSPitch, situation.AHRSRoll, situation.AHRSGyroHeading, situation.AHRSSlipSkid);
|
||||
|
||||
$scope.ahrs_heading_mag = situation.AHRSMagHeading.toFixed(0);
|
||||
$scope.ahrs_gload = situation.AHRSGLoad.toFixed(2);
|
||||
gMeter.update(situation.AHRSGLoad);
|
||||
$scope.ahrs_heading_mag = situation.AHRSMagHeading.toFixed(0);
|
||||
if ($scope.ahrs_heading_mag > 360) {
|
||||
$scope.ahrs_heading_mag = "---";
|
||||
}
|
||||
$scope.ahrs_gload = situation.AHRSGLoad.toFixed(2);
|
||||
if ($scope.ahrs_gload > 360) {
|
||||
$scope.ahrs_gload = "--";
|
||||
} else {
|
||||
gMeter.update(situation.AHRSGLoad);
|
||||
}
|
||||
|
||||
if (situation.AHRSTurnRate> 0.6031) {
|
||||
$scope.ahrs_turn_rate = (6/situation.AHRSTurnRate).toFixed(1); // minutes/turn
|
||||
if (situation.AHRSTurnRate > 360) {
|
||||
$scope.ahrs_turn_rate = "--";
|
||||
} else if (situation.AHRSTurnRate > 0.6031) {
|
||||
$scope.ahrs_turn_rate = (6/situation.AHRSTurnRate).toFixed(1); // minutes/turn
|
||||
} else {
|
||||
$scope.ahrs_turn_rate = '\u221e';
|
||||
}
|
||||
} else {
|
||||
$scope.ahrs_turn_rate = '\u221e';
|
||||
$scope.ahrs_heading = "---";
|
||||
$scope.ahrs_pitch = "---";
|
||||
$scope.ahrs_roll = "--";
|
||||
$scope.ahrs_slip_skid = "--";
|
||||
$scope.ahrs_heading_mag = "---";
|
||||
$scope.ahrs_gload = "--";
|
||||
$scope.ahrs_turn_rate = "--";
|
||||
}
|
||||
|
||||
if (situation.AHRSStatus & 0x01) {
|
||||
statusGPS.classList.remove("off");
|
||||
statusGPS.classList.add("on");
|
||||
|
|
Ładowanie…
Reference in New Issue