kopia lustrzana https://github.com/cyoung/stratux
Add AHRS status indicators to web UI.
rodzic
5f8718c96a
commit
8ce402a33f
|
@ -94,6 +94,7 @@ type SituationData struct {
|
|||
RateOfTurn float64
|
||||
GLoad float64
|
||||
LastAttitudeTime time.Time
|
||||
AHRSStatus uint8
|
||||
}
|
||||
|
||||
/*
|
||||
|
|
|
@ -22,6 +22,8 @@ var (
|
|||
myPressureReader sensors.PressureReader
|
||||
myIMUReader sensors.IMUReader
|
||||
cage chan(bool)
|
||||
analysisLogger *ahrs.AHRSLogger
|
||||
ahrsCalibrating bool
|
||||
)
|
||||
|
||||
func initI2CSensors() {
|
||||
|
@ -29,6 +31,7 @@ func initI2CSensors() {
|
|||
|
||||
go pollSensors()
|
||||
go sensorAttitudeSender()
|
||||
go updateAHRSStatus()
|
||||
}
|
||||
|
||||
func pollSensors() {
|
||||
|
@ -134,11 +137,14 @@ func initIMU() (ok bool) {
|
|||
myIMUReader = imu
|
||||
time.Sleep(200 * time.Millisecond)
|
||||
log.Println("AHRS Info: Successfully connected MPU9250, running calibration")
|
||||
ahrsCalibrating = true
|
||||
if err := myIMUReader.Calibrate(1, 1); err == nil {
|
||||
log.Println("AHRS Info: Successfully calibrated MPU9250")
|
||||
ahrsCalibrating = false
|
||||
return true
|
||||
} else {
|
||||
log.Println("AHRS Info: couldn't calibrate MPU9250")
|
||||
ahrsCalibrating = false
|
||||
return false
|
||||
}
|
||||
}
|
||||
|
@ -159,7 +165,6 @@ func sensorAttitudeSender() {
|
|||
ff *[3][3]float64 // Sensor orientation matrix
|
||||
mpuError, magError error
|
||||
failnum uint8
|
||||
analysisLogger *ahrs.AHRSLogger
|
||||
)
|
||||
log.Println("AHRS Info: initializing new simple AHRS")
|
||||
s = ahrs.InitializeSimple()
|
||||
|
@ -206,11 +211,13 @@ func sensorAttitudeSender() {
|
|||
<-timer.C
|
||||
select {
|
||||
case <-cage:
|
||||
ahrsCalibrating = true
|
||||
if err := myIMUReader.Calibrate(1, 1); err == nil {
|
||||
log.Println("AHRS Info: Successfully recalibrated MPU9250")
|
||||
} else {
|
||||
log.Println("AHRS Info: couldn't recalibrate MPU9250")
|
||||
}
|
||||
ahrsCalibrating = false
|
||||
s.Reset()
|
||||
default:
|
||||
}
|
||||
|
@ -353,6 +360,45 @@ func getMinAccelDirection() (i int, err error) {
|
|||
return
|
||||
}
|
||||
|
||||
// CageAHRS sends a signal to the AHRSProvider that it should be reset.
|
||||
func CageAHRS() {
|
||||
cage<- true
|
||||
}
|
||||
|
||||
func updateAHRSStatus() {
|
||||
var (
|
||||
msg uint8
|
||||
imu bool
|
||||
ticker *time.Ticker
|
||||
)
|
||||
|
||||
ticker = time.NewTicker(250 * time.Millisecond)
|
||||
|
||||
for {
|
||||
<-ticker.C
|
||||
msg = 0
|
||||
|
||||
// GPS valid
|
||||
if stratuxClock.Time.Sub(mySituation.LastGroundTrackTime) < 3000*time.Millisecond {
|
||||
msg += 1
|
||||
}
|
||||
// IMU is being used
|
||||
imu = globalSettings.IMU_Sensor_Enabled && globalStatus.IMUConnected
|
||||
if imu {
|
||||
msg += 1 << 1
|
||||
}
|
||||
// BMP is being used
|
||||
if globalSettings.BMP_Sensor_Enabled && globalStatus.BMPConnected {
|
||||
msg += 1 << 2
|
||||
}
|
||||
// IMU is doing a calibration
|
||||
if ahrsCalibrating {
|
||||
msg += 1 << 3
|
||||
}
|
||||
// Logging to csv
|
||||
if imu && analysisLogger != nil {
|
||||
msg += 1 << 4
|
||||
}
|
||||
mySituation.AHRSStatus = msg
|
||||
}
|
||||
}
|
||||
|
|
|
@ -439,4 +439,58 @@ body {
|
|||
-moz-transition: -moz-transform 0 ease;
|
||||
transition: transform 0 ease;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/* Thanks to https://codepen.io/fskirschbaum/pen/MYJNaj for the indicator template */
|
||||
|
||||
.indicator {
|
||||
margin: 0 1%;
|
||||
width: 18%;
|
||||
height: 100%;
|
||||
background-color: #ABFF00;
|
||||
border-radius: 10%;
|
||||
box-shadow: rgba(0, 0, 0, 0.2) 0 -1px 7px 1px, inset #304701 0 -1px 9px, #89FF00 0 2px 12px;
|
||||
}
|
||||
|
||||
.indicator.off {
|
||||
background-color: #F00;
|
||||
}
|
||||
|
||||
.indicator.on {
|
||||
background-color: #ABFF00;
|
||||
}
|
||||
|
||||
.indicator.blink {
|
||||
background-color: #F00;
|
||||
-webkit-animation: blinkRed 1s infinite;
|
||||
-moz-animation: blinkRed 1s infinite;
|
||||
-ms-animation: blinkRed 1s infinite;
|
||||
-o-animation: blinkRed 1s infinite;
|
||||
animation: blinkRed 1s infinite;
|
||||
}
|
||||
|
||||
@-webkit-keyframes blinkRed {
|
||||
from { background-color: #F22; }
|
||||
50% { background-color: #A00; box-shadow: rgba(0, 0, 0, 0.2) 0 -1px 7px 1px, inset #441313 0 -1px 9px, rgba(255, 0, 0, 0.5) 0 2px 0;}
|
||||
to { background-color: #F22; }
|
||||
}
|
||||
@-moz-keyframes blinkRed {
|
||||
from { background-color: #F22; }
|
||||
50% { background-color: #A00; box-shadow: rgba(0, 0, 0, 0.2) 0 -1px 7px 1px, inset #441313 0 -1px 9px, rgba(255, 0, 0, 0.5) 0 2px 0;}
|
||||
to { background-color: #F22; }
|
||||
}
|
||||
@-ms-keyframes blinkRed {
|
||||
from { background-color: #F22; }
|
||||
50% { background-color: #A00; box-shadow: rgba(0, 0, 0, 0.2) 0 -1px 7px 1px, inset #441313 0 -1px 9px, rgba(255, 0, 0, 0.5) 0 2px 0;}
|
||||
to { background-color: #F22; }
|
||||
}
|
||||
@-o-keyframes blinkRed {
|
||||
from { background-color: #F22; }
|
||||
50% { background-color: #A00; box-shadow: rgba(0, 0, 0, 0.2) 0 -1px 7px 1px, inset #441313 0 -1px 9px, rgba(255, 0, 0, 0.5) 0 2px 0;}
|
||||
to { background-color: #F22; }
|
||||
}
|
||||
@keyframes blinkRed {
|
||||
from { background-color: #F22; }
|
||||
50% { background-color: #A00; box-shadow: rgba(0, 0, 0, 0.2) 0 -1px 7px 1px, inset #441313 0 -1px 9px, rgba(255, 0, 0, 0.5) 0 2px 0;}
|
||||
to { background-color: #F22; }
|
||||
}
|
||||
|
|
|
@ -39,34 +39,45 @@
|
|||
</div>
|
||||
</span>
|
||||
</div>
|
||||
<div class="separator"></div>
|
||||
<div class="col-xs-3">
|
||||
<a ng-click="AHRSCage()" class="btn btn-primary">Cage</a>
|
||||
<div class="col-xs-12">
|
||||
<div class="row" style="margin-bottom: 4px;">
|
||||
<div class="col-xs-3 text-center indicator off" id="status-calibrating">Ready</div>
|
||||
<div class="col-xs-2 text-center indicator off" id="status-gps">GPS</div>
|
||||
<div class="col-xs-2 text-center indicator off" id="status-imu">IMU</div>
|
||||
<div class="col-xs-2 text-center indicator off" id="status-bmp">BMP</div>
|
||||
<div class="col-xs-3 text-center indicator off" id="status-logging">Logging</div>
|
||||
</div>
|
||||
</div>
|
||||
<div class="col-xs-9">
|
||||
<div class="row">
|
||||
<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>
|
||||
<div class="col-xs-12">
|
||||
<div class="separator"></div>
|
||||
<div class="col-xs-3">
|
||||
<a ng-click="AHRSCage()" class="btn btn-primary" ng-disabled="IsCaging()">Cage</a>
|
||||
</div>
|
||||
<div class="row">
|
||||
<span class="col-xs-3 text-center">{{ahrs_heading}}°</span>
|
||||
<span class="col-xs-3 text-center">{{ahrs_pitch}}°</span>
|
||||
<span class="col-xs-3 text-center">{{ahrs_roll}}°</span>
|
||||
<span class="col-xs-3 text-center">{{ahrs_alt}} ft</span>
|
||||
</div>
|
||||
<div class="row">
|
||||
<strong class="col-xs-3 text-center">Mag Hdg:</strong>
|
||||
<strong class="col-xs-3 text-center">Slip/Skid:</strong>
|
||||
<strong class="col-xs-3 text-center">Turn Rate:</strong>
|
||||
<strong class="col-xs-3 text-center">G Load:</strong>
|
||||
</div>
|
||||
<div class="row">
|
||||
<span class="col-xs-3 text-center">{{ahrs_heading_mag}}°</span>
|
||||
<span class="col-xs-3 text-center">{{ahrs_slip_skid}}°</span>
|
||||
<span class="col-xs-3 text-center">{{ahrs_turn_rate}} s</span>
|
||||
<span class="col-xs-3 text-center">{{ahrs_gload}}G</span>
|
||||
<div class="col-xs-9">
|
||||
<div class="row">
|
||||
<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>
|
||||
</div>
|
||||
<div class="row">
|
||||
<span class="col-xs-3 text-center">{{ahrs_heading}}°</span>
|
||||
<span class="col-xs-3 text-center">{{ahrs_pitch}}°</span>
|
||||
<span class="col-xs-3 text-center">{{ahrs_roll}}°</span>
|
||||
<span class="col-xs-3 text-center">{{ahrs_alt}} ft</span>
|
||||
</div>
|
||||
<div class="row">
|
||||
<strong class="col-xs-3 text-center">Mag Hdg</strong>
|
||||
<strong class="col-xs-3 text-center" >Slip/<wbr>Skid</strong>
|
||||
<strong class="col-xs-3 text-center">Turn Rate</strong>
|
||||
<strong class="col-xs-3 text-center">G Load</strong>
|
||||
</div>
|
||||
<div class="row">
|
||||
<span class="col-xs-3 text-center">{{ahrs_heading_mag}}°</span>
|
||||
<span class="col-xs-3 text-center">{{ahrs_slip_skid}}°</span>
|
||||
<span class="col-xs-3 text-center">{{ahrs_turn_rate}} min</span>
|
||||
<span class="col-xs-3 text-center">{{ahrs_gload}}G</span>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
|
|
|
@ -10,6 +10,12 @@ function GPSCtrl($rootScope, $scope, $state, $http, $interval) {
|
|||
var status = {};
|
||||
var display_area_size = -1;
|
||||
|
||||
var statusGPS = document.getElementById("status-gps"),
|
||||
statusIMU = document.getElementById("status-imu"),
|
||||
statusBMP = document.getElementById("status-bmp"),
|
||||
statusLog = document.getElementById("status-logging"),
|
||||
statusCal = document.getElementById("status-calibrating");
|
||||
|
||||
function sizeMap() {
|
||||
var width = 0;
|
||||
var el = document.getElementById("map_display").parentElement;
|
||||
|
@ -106,15 +112,53 @@ function GPSCtrl($rootScope, $scope, $state, $http, $interval) {
|
|||
// pitch and roll are in degrees
|
||||
$scope.ahrs_pitch = Math.round(status.Pitch*10)/10;
|
||||
$scope.ahrs_roll = Math.round(status.Roll*10)/10;
|
||||
$scope.ahrs_slip_skid = Math.round(status.SlipSkid*10)/10;
|
||||
ahrs.animate(0.1, $scope.ahrs_pitch, $scope.ahrs_roll, $scope.ahrs_heading, $scope.ahrs_slip_skid);
|
||||
|
||||
$scope.ahrs_heading_mag = Math.round(status.Mag_heading);
|
||||
$scope.ahrs_slip_skid = Math.round(status.SlipSkid*10)/10;
|
||||
if (status.RateOfTurn > 0.001) {
|
||||
$scope.ahrs_turn_rate = Math.round(360/status.RateOfTurn);
|
||||
} else {
|
||||
$scope.ahrs_turn_rate = '--'
|
||||
}
|
||||
$scope.ahrs_gload = Math.round(status.GLoad*100)/100;
|
||||
if (status.RateOfTurn > 0.001) {
|
||||
$scope.ahrs_turn_rate = Math.round(360/status.RateOfTurn/60*10)/10; // minutes/turn
|
||||
} else {
|
||||
$scope.ahrs_turn_rate = '---'
|
||||
}
|
||||
if (status.AHRSStatus & 0x01) {
|
||||
statusGPS.classList.remove("off");
|
||||
statusGPS.classList.add("on");
|
||||
} else {
|
||||
statusGPS.classList.add("off");
|
||||
statusGPS.classList.remove("on");
|
||||
}
|
||||
if (status.AHRSStatus & 0x02) {
|
||||
statusIMU.classList.remove("off");
|
||||
statusIMU.classList.add("on");
|
||||
} else {
|
||||
statusIMU.classList.add("off");
|
||||
statusIMU.classList.remove("on");
|
||||
}
|
||||
if (status.AHRSStatus & 0x04) {
|
||||
statusBMP.classList.remove("off");
|
||||
statusBMP.classList.add("on");
|
||||
} else {
|
||||
statusBMP.classList.add("off");
|
||||
statusBMP.classList.remove("on");
|
||||
}
|
||||
if (status.AHRSStatus & 0x10) {
|
||||
statusLog.classList.remove("off");
|
||||
statusLog.classList.add("on");
|
||||
} else {
|
||||
statusLog.classList.add("off");
|
||||
statusLog.classList.remove("on");
|
||||
}
|
||||
if (status.AHRSStatus & 0x08) {
|
||||
statusCal.classList.add("blink");
|
||||
statusCal.classList.remove("on");
|
||||
statusCal.innerText = "Caging";
|
||||
} else {
|
||||
statusCal.classList.remove("blink");
|
||||
statusCal.classList.add("on");
|
||||
statusCal.innerText = "Ready";
|
||||
}
|
||||
// "LastAttitudeTime":"2015-10-11T16:47:03.534615187Z"
|
||||
|
||||
setGeoReferenceMap(status.Lat, status.Lng);
|
||||
|
@ -123,11 +167,10 @@ function GPSCtrl($rootScope, $scope, $state, $http, $interval) {
|
|||
}
|
||||
|
||||
function getStatus() {
|
||||
// Simple GET request example (note: responce is asynchronous)
|
||||
// Simple GET request example (note: response is asynchronous)
|
||||
$http.get(URL_GPS_GET).
|
||||
then(function (response) {
|
||||
loadStatus(response.data);
|
||||
ahrs.animate(0.1, $scope.ahrs_pitch, $scope.ahrs_roll, $scope.ahrs_heading, $scope.ahrs_slip_skid);
|
||||
// $scope.$apply();
|
||||
}, function (response) {
|
||||
$scope.raw_data = "error getting gps / ahrs status";
|
||||
|
@ -207,11 +250,16 @@ function GPSCtrl($rootScope, $scope, $state, $http, $interval) {
|
|||
};
|
||||
|
||||
$scope.AHRSCage = function() {
|
||||
$http.post(URL_AHRS_CAGE).
|
||||
then(function (response) {
|
||||
// do nothing
|
||||
}, function (response) {
|
||||
// do nothing
|
||||
});
|
||||
if (!$scope.IsCaging()) {
|
||||
$http.post(URL_AHRS_CAGE).then(function (response) {
|
||||
// do nothing
|
||||
}, function (response) {
|
||||
// do nothing
|
||||
});
|
||||
}
|
||||
};
|
||||
|
||||
$scope.IsCaging = function() {
|
||||
return statusCal.innerText == "Caging";
|
||||
}
|
||||
}
|
||||
|
|
Ładowanie…
Reference in New Issue