kopia lustrzana https://github.com/cyoung/stratux
Merge remote-tracking branch 'cyoung/ahrs_dev' into eric
commit
52e61ca48c
6
Makefile
6
Makefile
|
@ -3,7 +3,9 @@ ifeq "$(CIRCLECI)" "true"
|
|||
BUILDINFO=
|
||||
PLATFORMDEPENDENT=
|
||||
else
|
||||
BUILDINFO=-ldflags "-X main.stratuxVersion=`git describe --tags --abbrev=0` -X main.stratuxBuild=`git log -n 1 --pretty=%H`"
|
||||
LDFLAGS_VERSION=-X main.stratuxVersion=`git describe --tags --abbrev=0` -X main.stratuxBuild=`git log -n 1 --pretty=%H`
|
||||
BUILDINFO=-ldflags "$(LDFLAGS_VERSION)"
|
||||
BUILDINFO_STATIC=-ldflags "-extldflags -static $(LDFLAGS_VERSION)"
|
||||
$(if $(GOROOT),,$(error GOROOT is not set!))
|
||||
PLATFORMDEPENDENT=fancontrol
|
||||
endif
|
||||
|
@ -17,7 +19,7 @@ xgen_gdl90:
|
|||
|
||||
fancontrol:
|
||||
go get -t -d -v ./main
|
||||
go build $(BUILDINFO) -p 4 main/fancontrol.go main/equations.go main/cputemp.go
|
||||
go build $(BUILDINFO_STATIC) -p 4 main/fancontrol.go main/equations.go main/cputemp.go
|
||||
|
||||
xdump1090:
|
||||
git submodule update --init
|
||||
|
|
2
goflying
2
goflying
|
@ -1 +1 @@
|
|||
Subproject commit 411d7ee92b96519b7b9c92e07c9e376e3a8574f4
|
||||
Subproject commit 8bd566f09abe01f42fd92aeb84591e0bee3e7ff6
|
|
@ -63,19 +63,37 @@ func fanControl(pwmDutyMin int, pin int, tempTarget float32) {
|
|||
}
|
||||
})
|
||||
pwmDuty := 0
|
||||
|
||||
tempWhenRampStarted := float32(0.)
|
||||
for {
|
||||
if temp > (tempTarget + hysteresis) {
|
||||
if tempWhenRampStarted < 1. {
|
||||
tempWhenRampStarted = temp
|
||||
}
|
||||
pwmDuty = iMax(iMin(pwmDutyMax, pwmDuty+1), pwmDutyMin)
|
||||
if pwmDuty == pwmDutyMax {
|
||||
// At the maximum duty cycle currently.
|
||||
// Has the temperature increased "substantially" since the ramp-up started?
|
||||
if temp > (tempWhenRampStarted + hysteresis) {
|
||||
// Give up. The fan does not like the PWM control.
|
||||
break
|
||||
}
|
||||
}
|
||||
} else if temp < (tempTarget - hysteresis) {
|
||||
pwmDuty = iMax(pwmDuty-1, 0)
|
||||
if pwmDuty < pwmDutyMin {
|
||||
pwmDuty = 0
|
||||
tempWhenRampStarted = 0.
|
||||
}
|
||||
}
|
||||
//log.Println(temp, " ", pwmDuty)
|
||||
C.pwmWrite(cPin, C.int(pwmDuty))
|
||||
time.Sleep(delaySeconds * time.Second)
|
||||
}
|
||||
|
||||
// Default to "ON".
|
||||
C.pinMode(cPin, C.OUTPUT)
|
||||
C.digitalWrite(cPin, C.HIGH)
|
||||
}
|
||||
|
||||
// Service has embedded daemon
|
||||
|
|
|
@ -94,6 +94,8 @@ type SituationData struct {
|
|||
AHRSSlipSkid float32
|
||||
AHRSTurnRate float32
|
||||
AHRSGLoad float32
|
||||
AHRSGLoadMin float32
|
||||
AHRSGLoadMax float32
|
||||
AHRSLastAttitudeTime time.Time
|
||||
AHRSStatus uint8
|
||||
}
|
||||
|
|
|
@ -492,6 +492,21 @@ func handleCageAHRS(w http.ResponseWriter, r *http.Request) {
|
|||
}
|
||||
}
|
||||
|
||||
func handleResetGMeter(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" {
|
||||
ResetAHRSGLoad()
|
||||
}
|
||||
}
|
||||
|
||||
func doRestartApp() {
|
||||
time.Sleep(1)
|
||||
syscall.Sync()
|
||||
|
@ -741,6 +756,7 @@ func managementInterface() {
|
|||
|
||||
http.HandleFunc("/orientAHRS", handleOrientAHRS)
|
||||
http.HandleFunc("/cageAHRS", handleCageAHRS)
|
||||
http.HandleFunc("/resetGMeter", handleResetGMeter)
|
||||
|
||||
http.HandleFunc("/deletelogfile", handleDeleteLogFile)
|
||||
http.HandleFunc("/downloadlog", handleDownloadLogRequest)
|
||||
|
|
|
@ -263,6 +263,12 @@ func sensorAttitudeSender() {
|
|||
mySituation.AHRSSlipSkid = float32(s.SlipSkid())
|
||||
mySituation.AHRSTurnRate = float32(s.RateOfTurn())
|
||||
mySituation.AHRSGLoad = float32(s.GLoad())
|
||||
if mySituation.AHRSGLoad < mySituation.AHRSGLoadMin || mySituation.AHRSGLoadMin == 0 {
|
||||
mySituation.AHRSGLoadMin = mySituation.AHRSGLoad
|
||||
}
|
||||
if mySituation.AHRSGLoad > mySituation.AHRSGLoadMax {
|
||||
mySituation.AHRSGLoadMax = mySituation.AHRSGLoad
|
||||
}
|
||||
|
||||
mySituation.AHRSLastAttitudeTime = t
|
||||
} else {
|
||||
|
@ -274,6 +280,8 @@ func sensorAttitudeSender() {
|
|||
mySituation.AHRSSlipSkid = invalid
|
||||
mySituation.AHRSTurnRate = invalid
|
||||
mySituation.AHRSGLoad = invalid
|
||||
mySituation.AHRSGLoadMin = invalid
|
||||
mySituation.AHRSGLoadMax = 0
|
||||
mySituation.AHRSLastAttitudeTime = time.Time{}
|
||||
}
|
||||
mySituation.muAttitude.Unlock()
|
||||
|
@ -373,6 +381,12 @@ func SetAHRSConfig(smoothConst, weight float64) {
|
|||
ahrs.SetConfig(smoothConst, weight)
|
||||
}
|
||||
|
||||
// ResetAHRSGLoad resets the min and max to the current G load value.
|
||||
func ResetAHRSGLoad() {
|
||||
mySituation.AHRSGLoadMax = mySituation.AHRSGLoad
|
||||
mySituation.AHRSGLoadMin = mySituation.AHRSGLoad
|
||||
}
|
||||
|
||||
func updateAHRSStatus() {
|
||||
var (
|
||||
msg uint8
|
||||
|
|
|
@ -223,7 +223,7 @@ func sendTrafficUpdates() {
|
|||
if globalSettings.DEBUG {
|
||||
log.Printf("Ownship target detected for code %X\n", code)
|
||||
}
|
||||
OwnshipTrafficInfo = ti
|
||||
// OwnshipTrafficInfo = ti
|
||||
} else {
|
||||
cur_n := len(msgs) - 1
|
||||
if len(msgs[cur_n]) >= 35 {
|
||||
|
@ -259,6 +259,10 @@ func registerTrafficUpdate(ti TrafficInfo) {
|
|||
func isTrafficAlertable(ti TrafficInfo) bool {
|
||||
// Set alert bit if possible and traffic is within some threshold
|
||||
// TODO: Could be more intelligent, taking into account headings etc.
|
||||
if !ti.BearingDist_valid {
|
||||
// If not able to calculate the distance to the target, let the alert bit be set always.
|
||||
return true
|
||||
}
|
||||
if ti.BearingDist_valid &&
|
||||
ti.Distance < 3704 { // 3704 meters, 2 nm.
|
||||
return true
|
||||
|
|
|
@ -17,6 +17,7 @@ var URL_RESTARTAPP = "http://" + URL_HOST_BASE + "/restart";
|
|||
var URL_DEV_TOGGLE_GET = "http://" + URL_HOST_BASE + "/develmodetoggle";
|
||||
var URL_AHRS_ORIENT = "http://" + URL_HOST_BASE + "/orientAHRS";
|
||||
var URL_AHRS_CAGE = "http://" + URL_HOST_BASE + "/cageAHRS";
|
||||
var URL_GMETER_RESET = "http://" + URL_HOST_BASE + "/resetGMeter";
|
||||
var URL_DELETELOGFILE = "http://" + URL_HOST_BASE + "/deletelogfile";
|
||||
var URL_DOWNLOADLOGFILE = "http://" + URL_HOST_BASE + "/downloadlog";
|
||||
var URL_DOWNLOADDB = "http://" + URL_HOST_BASE + "/downloaddb";
|
||||
|
|
|
@ -143,7 +143,7 @@ AHRSRenderer.prototype = {
|
|||
}
|
||||
};
|
||||
|
||||
function GMeterRenderer(locationId, plim, nlim) {
|
||||
function GMeterRenderer(locationId, plim, nlim, resetCallback) {
|
||||
this.plim = plim;
|
||||
this.nlim = nlim;
|
||||
this.nticks = Math.floor(plim+1) - Math.floor(nlim) + 1;
|
||||
|
@ -215,7 +215,7 @@ function GMeterRenderer(locationId, plim, nlim) {
|
|||
reset.text('RESET').cx(0).cy(0).addClass('text');
|
||||
reset.on('click', function() {
|
||||
reset.animate(200).rotate(20, 0, 0);
|
||||
this.reset();
|
||||
resetCallback();
|
||||
reset.animate(200).rotate(0, 0, 0);
|
||||
}, this);
|
||||
}
|
||||
|
@ -235,19 +235,13 @@ GMeterRenderer.prototype = {
|
|||
}
|
||||
},
|
||||
|
||||
update: function (g) {
|
||||
update: function (g, gmin, gmax) {
|
||||
this.g = g;
|
||||
this.max = g > this.max ? g : this.max;
|
||||
this.min = g < this.min ? g : this.min;
|
||||
this.min = gmin;
|
||||
this.max = gmax;
|
||||
|
||||
this.pointer_el.animate(50).rotate((g-1)/this.nticks*360, 0, 0);
|
||||
this.max_el.animate(50).rotate((this.max-1)/this.nticks*360, 0, 0);
|
||||
this.min_el.animate(50).rotate((this.min-1)/this.nticks*360, 0, 0);
|
||||
},
|
||||
|
||||
reset: function() {
|
||||
this.g = 1;
|
||||
this.max = 1;
|
||||
this.min = 1;
|
||||
}
|
||||
};
|
||||
|
|
|
@ -175,7 +175,7 @@ function GPSCtrl($rootScope, $scope, $state, $http, $interval) {
|
|||
if ($scope.ahrs_gload > 360) {
|
||||
$scope.ahrs_gload = "--";
|
||||
} else {
|
||||
gMeter.update(situation.AHRSGLoad);
|
||||
gMeter.update(situation.AHRSGLoad, situation.AHRSGLoadMin, situation.AHRSGLoadMax);
|
||||
}
|
||||
|
||||
if (situation.AHRSTurnRate > 360) {
|
||||
|
@ -204,7 +204,7 @@ function GPSCtrl($rootScope, $scope, $state, $http, $interval) {
|
|||
}
|
||||
if (situation.AHRSStatus & 0x02) {
|
||||
if (statusIMU.classList.contains("off")) {
|
||||
setTimeout(gMeter.reset(), 1000);
|
||||
setTimeout($scope.GMeterReset, 1000);
|
||||
}
|
||||
statusIMU.classList.remove("off");
|
||||
statusIMU.classList.add("on");
|
||||
|
@ -357,7 +357,15 @@ function GPSCtrl($rootScope, $scope, $state, $http, $interval) {
|
|||
return caging;
|
||||
};
|
||||
|
||||
var gMeter = new GMeterRenderer("gMeter_display", 4.4, -1.76);
|
||||
$scope.GMeterReset = function() {
|
||||
$http.post(URL_GMETER_RESET).then(function (response) {
|
||||
// do nothing
|
||||
}, function (response) {
|
||||
// do nothing
|
||||
});
|
||||
};
|
||||
|
||||
var gMeter = new GMeterRenderer("gMeter_display", 4.4, -1.76, $scope.GMeterReset);
|
||||
|
||||
// GPS Controller tasks
|
||||
connect($scope); // connect - opens a socket and listens for messages
|
||||
|
|
Ładowanie…
Reference in New Issue