kopia lustrzana https://github.com/cyoung/stratux
Add Cage button to Attitude Indicator/AHRS.
rodzic
59da452770
commit
5ab394b31d
|
@ -380,7 +380,7 @@ func handleOrientAHRS(w http.ResponseWriter, r *http.Request) {
|
||||||
w.Header().Set("Access-Control-Allow-Headers", "Origin, X-Requested-With, Content-Type, Accept")
|
w.Header().Set("Access-Control-Allow-Headers", "Origin, X-Requested-With, Content-Type, Accept")
|
||||||
|
|
||||||
// For an OPTION method request, we return header without processing.
|
// For an OPTION method request, we return header without processing.
|
||||||
// This insures we are recognized as supporting cross-domain AJAX REST calls.
|
// This ensures we are recognized as supporting cross-domain AJAX REST calls.
|
||||||
if r.Method == "POST" {
|
if r.Method == "POST" {
|
||||||
var (
|
var (
|
||||||
action []byte = make([]byte, 1)
|
action []byte = make([]byte, 1)
|
||||||
|
@ -427,6 +427,21 @@ func handleOrientAHRS(w http.ResponseWriter, r *http.Request) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
func handleCageAHRS(w http.ResponseWriter, r *http.Request) {
|
||||||
|
// define header in support of cross-domain AJAX
|
||||||
|
setNoCache(w)
|
||||||
|
w.Header().Set("Content-Type", "text/plain")
|
||||||
|
w.Header().Set("Access-Control-Allow-Origin", "*")
|
||||||
|
w.Header().Set("Access-Control-Allow-Method", "GET, POST, OPTIONS")
|
||||||
|
w.Header().Set("Access-Control-Allow-Headers", "Origin, X-Requested-With, Content-Type, Accept")
|
||||||
|
|
||||||
|
// For an OPTION method request, we return header without processing.
|
||||||
|
// This ensures we are recognized as supporting cross-domain AJAX REST calls.
|
||||||
|
if r.Method == "POST" {
|
||||||
|
CageAHRS()
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
func doRestartApp() {
|
func doRestartApp() {
|
||||||
time.Sleep(1)
|
time.Sleep(1)
|
||||||
syscall.Sync()
|
syscall.Sync()
|
||||||
|
@ -660,6 +675,7 @@ func managementInterface() {
|
||||||
http.HandleFunc("/roPartitionRebuild", handleroPartitionRebuild)
|
http.HandleFunc("/roPartitionRebuild", handleroPartitionRebuild)
|
||||||
http.HandleFunc("/develmodetoggle", handleDevelModeToggle)
|
http.HandleFunc("/develmodetoggle", handleDevelModeToggle)
|
||||||
http.HandleFunc("/orientAHRS", handleOrientAHRS)
|
http.HandleFunc("/orientAHRS", handleOrientAHRS)
|
||||||
|
http.HandleFunc("/cageAHRS", handleCageAHRS)
|
||||||
|
|
||||||
err := http.ListenAndServe(managementAddr, nil)
|
err := http.ListenAndServe(managementAddr, nil)
|
||||||
|
|
||||||
|
|
|
@ -21,6 +21,7 @@ var (
|
||||||
i2cbus embd.I2CBus
|
i2cbus embd.I2CBus
|
||||||
myPressureReader sensors.PressureReader
|
myPressureReader sensors.PressureReader
|
||||||
myIMUReader sensors.IMUReader
|
myIMUReader sensors.IMUReader
|
||||||
|
cage chan(bool)
|
||||||
)
|
)
|
||||||
|
|
||||||
func initI2CSensors() {
|
func initI2CSensors() {
|
||||||
|
@ -166,6 +167,7 @@ func sensorAttitudeSender() {
|
||||||
failnum uint8
|
failnum uint8
|
||||||
)
|
)
|
||||||
m = ahrs.NewMeasurement()
|
m = ahrs.NewMeasurement()
|
||||||
|
cage = make(chan(bool))
|
||||||
|
|
||||||
//TODO westphae: remove this logging when finished testing, or make it optional in settings
|
//TODO westphae: remove this logging when finished testing, or make it optional in settings
|
||||||
logger := ahrs.NewSensorLogger(fmt.Sprintf("/var/log/sensors_%s.csv", time.Now().Format("20060102_150405")),
|
logger := ahrs.NewSensorLogger(fmt.Sprintf("/var/log/sensors_%s.csv", time.Now().Format("20060102_150405")),
|
||||||
|
@ -204,6 +206,12 @@ func sensorAttitudeSender() {
|
||||||
<-timer.C
|
<-timer.C
|
||||||
for (globalSettings.Sensors_Enabled && globalStatus.IMUConnected) {
|
for (globalSettings.Sensors_Enabled && globalStatus.IMUConnected) {
|
||||||
<-timer.C
|
<-timer.C
|
||||||
|
select {
|
||||||
|
case <-cage:
|
||||||
|
s = nil
|
||||||
|
default:
|
||||||
|
}
|
||||||
|
|
||||||
t = stratuxClock.Time
|
t = stratuxClock.Time
|
||||||
m.T = float64(t.UnixNano() / 1000) / 1e6
|
m.T = float64(t.UnixNano() / 1000) / 1e6
|
||||||
|
|
||||||
|
@ -340,3 +348,7 @@ func getMinAccelDirection() (i int, err error) {
|
||||||
|
|
||||||
return
|
return
|
||||||
}
|
}
|
||||||
|
|
||||||
|
func CageAHRS() {
|
||||||
|
cage<- true
|
||||||
|
}
|
||||||
|
|
|
@ -16,6 +16,7 @@ var URL_SHUTDOWN = "http://" + URL_HOST_BASE + "/shutdown";
|
||||||
var URL_RESTARTAPP = "http://" + URL_HOST_BASE + "/restart";
|
var URL_RESTARTAPP = "http://" + URL_HOST_BASE + "/restart";
|
||||||
var URL_DEV_TOGGLE_GET = "http://" + URL_HOST_BASE + "/develmodetoggle";
|
var URL_DEV_TOGGLE_GET = "http://" + URL_HOST_BASE + "/develmodetoggle";
|
||||||
var URL_AHRS_ORIENT = "http://" + URL_HOST_BASE + "/orientAHRS";
|
var URL_AHRS_ORIENT = "http://" + URL_HOST_BASE + "/orientAHRS";
|
||||||
|
var URL_AHRS_CAGE = "http://" + URL_HOST_BASE + "/cageAHRS";
|
||||||
|
|
||||||
// define the module with dependency on mobile-angular-ui
|
// define the module with dependency on mobile-angular-ui
|
||||||
//var app = angular.module('stratux', ['ngRoute', 'mobile-angular-ui', 'mobile-angular-ui.gestures', 'appControllers']);
|
//var app = angular.module('stratux', ['ngRoute', 'mobile-angular-ui', 'mobile-angular-ui.gestures', 'appControllers']);
|
||||||
|
|
|
@ -40,17 +40,22 @@
|
||||||
</span>
|
</span>
|
||||||
</div>
|
</div>
|
||||||
<div class="separator"></div>
|
<div class="separator"></div>
|
||||||
<div class="row">
|
<div class="col-xs-2">
|
||||||
<strong class="col-xs-3 text-center">Heading:</strong>
|
<a ng-click="AHRSCage()" class="btn btn-primary">Cage</a>
|
||||||
<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>
|
||||||
<div class="row">
|
<div class="col-xs-10">
|
||||||
<span class="col-xs-3 text-center">{{ahrs_heading}}°</span>
|
<div class="row">
|
||||||
<span class="col-xs-3 text-center">{{ahrs_pitch}}°</span>
|
<strong class="col-xs-3 text-center">Heading:</strong>
|
||||||
<span class="col-xs-3 text-center">{{ahrs_roll}}°</span>
|
<strong class="col-xs-3 text-center">Pitch:</strong>
|
||||||
<span class="col-xs-3 text-center">{{ahrs_alt}} ft</span>
|
<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>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
</div>
|
</div>
|
||||||
|
|
|
@ -189,5 +189,14 @@ function GPSCtrl($rootScope, $scope, $state, $http, $interval) {
|
||||||
for (var i=0; i < hiders.length; i++) {
|
for (var i=0; i < hiders.length; i++) {
|
||||||
hiders[i].style.display = disp;
|
hiders[i].style.display = disp;
|
||||||
}
|
}
|
||||||
}
|
};
|
||||||
|
|
||||||
|
$scope.AHRSCage = function() {
|
||||||
|
$http.post(URL_AHRS_CAGE).
|
||||||
|
then(function (response) {
|
||||||
|
// do nothing
|
||||||
|
}, function (response) {
|
||||||
|
// do nothing
|
||||||
|
});
|
||||||
|
};
|
||||||
}
|
}
|
||||||
|
|
Ładowanie…
Reference in New Issue