kopia lustrzana https://github.com/cyoung/stratux
commit
af317bc834
2
goflying
2
goflying
|
@ -1 +1 @@
|
|||
Subproject commit 7e5c2828807d8074f7fd432df4baeb5e0ac44ece
|
||||
Subproject commit 2a2fd99f9b9c0222344924b86d45f93d6f982cee
|
|
@ -270,23 +270,23 @@ func makeOwnshipReport() bool {
|
|||
}
|
||||
|
||||
// This is **PRESSURE ALTITUDE**
|
||||
//FIXME: Temporarily removing "invalid altitude" when pressure altitude not available - using GPS altitude instead.
|
||||
// alt := uint16(0xFFF) // 0xFFF "invalid altitude."
|
||||
alt := uint16(0xFFF) // 0xFFF "invalid altitude."
|
||||
validAltf := false
|
||||
|
||||
var alt uint16
|
||||
var altf float64
|
||||
|
||||
if selfOwnshipValid {
|
||||
altf = float64(curOwnship.Alt)
|
||||
validAltf = true
|
||||
} else if isTempPressValid() {
|
||||
altf = float64(mySituation.BaroPressureAltitude)
|
||||
} else {
|
||||
altf = float64(mySituation.GPSAltitudeMSL) //FIXME: Pass GPS altitude if PA not available. **WORKAROUND FOR FF**
|
||||
validAltf = true
|
||||
}
|
||||
|
||||
altf = (altf + 1000) / 25
|
||||
|
||||
alt = uint16(altf) & 0xFFF // Should fit in 12 bits.
|
||||
if validAltf {
|
||||
altf = (altf + 1000) / 25
|
||||
alt = uint16(altf) & 0xFFF // Should fit in 12 bits.
|
||||
}
|
||||
|
||||
msg[11] = byte((alt & 0xFF0) >> 4) // Altitude.
|
||||
msg[12] = byte((alt & 0x00F) << 4)
|
||||
|
@ -1048,14 +1048,12 @@ type settings struct {
|
|||
DEBUG bool
|
||||
ReplayLog bool
|
||||
AHRSLog bool
|
||||
IMUMapping [2]int // Map from aircraft axis to sensor axis: accelerometer
|
||||
IMUMapping [2]int // Map from aircraft axis to sensor axis: accelerometer
|
||||
SensorQuaternion [4]float64 // Quaternion mapping from sensor frame to aircraft frame
|
||||
PPM int
|
||||
OwnshipModeS string
|
||||
WatchList string
|
||||
DeveloperMode bool
|
||||
AHRSSmoothingConstant float64
|
||||
AHRSGPSWeight float64
|
||||
GLimits string
|
||||
StaticIps []string
|
||||
}
|
||||
|
@ -1125,8 +1123,6 @@ func defaultSettings() {
|
|||
globalSettings.ReplayLog = false //TODO: 'true' for debug builds.
|
||||
globalSettings.AHRSLog = false
|
||||
globalSettings.IMUMapping = [2]int{-1, -3} // OpenFlightBox AHRS normal mapping
|
||||
globalSettings.AHRSSmoothingConstant = 0.9
|
||||
globalSettings.AHRSGPSWeight = 0.05
|
||||
globalSettings.OwnshipModeS = "F00000"
|
||||
globalSettings.DeveloperMode = false
|
||||
globalSettings.StaticIps = make([]string, 0)
|
||||
|
|
|
@ -326,14 +326,6 @@ func handleSettingsSetRequest(w http.ResponseWriter, r *http.Request) {
|
|||
globalSettings.WatchList = val.(string)
|
||||
case "GLimits":
|
||||
globalSettings.GLimits = val.(string)
|
||||
case "AHRSSmoothingConstant":
|
||||
globalSettings.AHRSSmoothingConstant = val.(float64)
|
||||
SetAHRSConfig(globalSettings.AHRSSmoothingConstant, globalSettings.AHRSGPSWeight)
|
||||
log.Printf("AHRS Info: Smoothing Constant set to %6f\n", globalSettings.AHRSSmoothingConstant)
|
||||
case "AHRSGPSWeight":
|
||||
globalSettings.AHRSGPSWeight = val.(float64)
|
||||
SetAHRSConfig(globalSettings.AHRSSmoothingConstant, globalSettings.AHRSGPSWeight)
|
||||
log.Printf("AHRS Info: GPS Weight set to %6f\n", globalSettings.AHRSGPSWeight)
|
||||
case "OwnshipModeS":
|
||||
// Expecting a hex string less than 6 characters (24 bits) long.
|
||||
if len(val.(string)) > 6 { // Too long.
|
||||
|
@ -459,8 +451,9 @@ func handleOrientAHRS(w http.ResponseWriter, r *http.Request) {
|
|||
log.Printf("AHRS Info: sensor orientation: received up direction %d\n", u)
|
||||
|
||||
if f == u || f == -u {
|
||||
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)
|
||||
log.Printf("AHRS Error: sensor orientation: up (%d) and forward (%d) axes cannot be the same\n", u, f)
|
||||
http.Error(w, fmt.Sprintf("up (%d) and forward (%d) axes cannot be the same", u, f),
|
||||
http.StatusBadRequest)
|
||||
return
|
||||
}
|
||||
|
||||
|
|
|
@ -155,7 +155,6 @@ func sensorAttitudeSender() {
|
|||
|
||||
log.Println("AHRS Info: initializing new Simple AHRS")
|
||||
s = ahrs.InitializeSimple()
|
||||
SetAHRSConfig(globalSettings.AHRSSmoothingConstant, globalSettings.AHRSGPSWeight)
|
||||
m = ahrs.NewMeasurement()
|
||||
cal = make(chan (bool), 1)
|
||||
needsCage = true
|
||||
|
@ -376,6 +375,8 @@ func makeSensorRotationMatrix(g [3]float64) (rotmat *[3][3]float64) {
|
|||
|
||||
// This is used in the orientation process where the user specifies the forward and up directions.
|
||||
func getMinAccelDirection() (i int, err error) {
|
||||
myIMUReader.Read() // Clear out the averages
|
||||
time.Sleep(500 * time.Millisecond) // Ensure we have enough values
|
||||
_, _, _, _, a1, a2, a3, _, _, _, err, _ := myIMUReader.Read()
|
||||
if err != nil {
|
||||
return
|
||||
|
@ -413,11 +414,6 @@ func CageAHRS() {
|
|||
cal <- true
|
||||
}
|
||||
|
||||
// SetAHRSConfig changes some AHRS parameters, intended for developers.
|
||||
func SetAHRSConfig(smoothConst, weight float64) {
|
||||
s.SetConfig(map[string]float64{"uiSmoothConst": smoothConst, "gpsWeight": weight})
|
||||
}
|
||||
|
||||
// ResetAHRSGLoad resets the min and max to the current G load value.
|
||||
func ResetAHRSGLoad() {
|
||||
mySituation.AHRSGLoadMax = mySituation.AHRSGLoad
|
||||
|
|
|
@ -62,9 +62,10 @@ cp -f motd /etc/motd
|
|||
#remove old script
|
||||
rm -f /usr/bin/fancontrol.py
|
||||
#install new program
|
||||
/usr/bin/fancontrol stop
|
||||
/usr/bin/fancontrol remove
|
||||
cp -f fancontrol /usr/bin/
|
||||
chmod 755 /usr/bin/fancontrol
|
||||
/usr/bin/fancontrol remove
|
||||
/usr/bin/fancontrol install
|
||||
|
||||
cp -f dump1090 /usr/bin/
|
||||
|
|
|
@ -61,7 +61,7 @@
|
|||
<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>
|
||||
<span class="col-xs-3 text-center">{{ahrs_alt}}'</span>
|
||||
</div>
|
||||
<div class="row">
|
||||
<strong class="col-xs-3 text-center">Mag Hdg</strong>
|
||||
|
|
|
@ -37,8 +37,6 @@ function SettingsCtrl($rootScope, $scope, $state, $location, $window, $http) {
|
|||
|
||||
$scope.PPM = settings.PPM;
|
||||
$scope.WatchList = settings.WatchList;
|
||||
$scope.AHRSSmoothingConstant = settings.AHRSSmoothingConstant;
|
||||
$scope.AHRSGPSWeight = settings.AHRSGPSWeight;
|
||||
$scope.OwnshipModeS = settings.OwnshipModeS;
|
||||
$scope.DeveloperMode = settings.DeveloperMode;
|
||||
$scope.GLimits = settings.GLimits;
|
||||
|
@ -131,34 +129,6 @@ function SettingsCtrl($rootScope, $scope, $state, $location, $window, $http) {
|
|||
}
|
||||
};
|
||||
|
||||
$scope.updateAHRSSmoothingConst = function () {
|
||||
if ($scope.AHRSSmoothingConstant !== settings["AHRSSmoothingConstant"]) {
|
||||
settings["AHRSSmoothingConstant"] = "0.8";
|
||||
if ($scope.AHRSSmoothingConstant!== undefined) {
|
||||
settings["AHRSSmoothingConstant"] = parseFloat($scope.AHRSSmoothingConstant);
|
||||
}
|
||||
newsettings = {
|
||||
"AHRSSmoothingConstant": settings["AHRSSmoothingConstant"]
|
||||
};
|
||||
// console.log(angular.toJson(newsettings));
|
||||
setSettings(angular.toJson(newsettings));
|
||||
}
|
||||
};
|
||||
|
||||
$scope.updateAHRSGPSWeight = function () {
|
||||
if ($scope.AHRSGPSWeight !== settings["AHRSGPSWeight"]) {
|
||||
settings["AHRSGPSWeight"] = "0.05";
|
||||
if ($scope.AHRSGPSWeight!== undefined) {
|
||||
settings["AHRSGPSWeight"] = parseFloat($scope.AHRSGPSWeight);
|
||||
}
|
||||
newsettings = {
|
||||
"AHRSGPSWeight": settings["AHRSGPSWeight"]
|
||||
};
|
||||
// console.log(angular.toJson(newsettings));
|
||||
setSettings(angular.toJson(newsettings));
|
||||
}
|
||||
};
|
||||
|
||||
$scope.updatemodes = function () {
|
||||
if ($scope.OwnshipModeS !== settings["OwnshipModeS"]) {
|
||||
settings["OwnshipModeS"] = $scope.OwnshipModeS.toUpperCase();
|
||||
|
|
|
@ -180,20 +180,6 @@
|
|||
<input class="col-xs-7" type="string" required ng-model="StaticIps" ng-list=" " ng-trim="false" placeholder="space-delimited ip's to send network data" ng-blur="updatestaticips()" />
|
||||
</form>
|
||||
</div>
|
||||
<div class="form-group reset-flow">
|
||||
<label class="control-label col-xs-5">AHRS Responsiveness</label>
|
||||
<form name="watchForm" ng-submit="updateAHRSSmoothingConst()" novalidate>
|
||||
<input class="col-xs-7" type="string" required ng-model="AHRSSmoothingConstant"
|
||||
placeholder="0 is smoother, 1 is faster" ng-blur="updateAHRSSmoothingConst()" />
|
||||
</form>
|
||||
</div>
|
||||
<div class="form-group reset-flow">
|
||||
<label class="control-label col-xs-5">AHRS GPS Weight</label>
|
||||
<form name="watchForm" ng-submit="updateAHRSGPSWeight()" novalidate>
|
||||
<input class="col-xs-7" type="string" required ng-model="AHRSGPSWeight"
|
||||
placeholder="0-1, lower uses more gyro" ng-blur="updateAHRSGPSWeight()" />
|
||||
</form>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
|
|
Ładowanie…
Reference in New Issue