AP_NavEKF2: Don't attempt to compensate for external mag calibration

This was problematic to implement with magnetometer switching. It is likely that slow magnetometer learning can still be performed externally (eg plane) but this will need to be monitored to see if it causes issues.
This commit is contained in:
Paul Riseborough 2015-11-08 20:32:23 +11:00 committed by Andrew Tridgell
parent 6524222397
commit afeadfca51
2 changed files with 0 additions and 14 deletions

View File

@ -206,19 +206,6 @@ void NavEKF2_core::readMagData()
// check for consistent data between magnetometers
consistentMagData = _ahrs->get_compass()->consistent();
// check if compass offsets have been changed and adjust EKF bias states to maintain consistent innovations
if (_ahrs->get_compass()->healthy(0)) {
Vector3f nowMagOffsets = _ahrs->get_compass()->get_offsets(0);
bool changeDetected = (!is_equal(nowMagOffsets.x,lastMagOffsets.x) || !is_equal(nowMagOffsets.y,lastMagOffsets.y) || !is_equal(nowMagOffsets.z,lastMagOffsets.z));
// Ignore bias changes before final mag field and yaw initialisation, as there may have been a compass calibration
if (changeDetected && firstMagYawInit) {
stateStruct.body_magfield.x += (nowMagOffsets.x - lastMagOffsets.x) * 0.001f;
stateStruct.body_magfield.y += (nowMagOffsets.y - lastMagOffsets.y) * 0.001f;
stateStruct.body_magfield.z += (nowMagOffsets.z - lastMagOffsets.z) * 0.001f;
}
lastMagOffsets = nowMagOffsets;
}
// save magnetometer measurement to buffer to be fused later
StoreMag();
}

View File

@ -734,7 +734,6 @@ private:
bool validOrigin; // true when the EKF origin is valid
float gpsSpdAccuracy; // estimated speed accuracy in m/s returned by the UBlox GPS receiver
uint32_t lastGpsVelFail_ms; // time of last GPS vertical velocity consistency check fail
Vector3f lastMagOffsets; // magnetometer offsets returned by compass object from previous update
uint32_t lastGpsAidBadTime_ms; // time in msec gps aiding was last detected to be bad
float posDownAtTakeoff; // flight vehicle vertical position at arming used as a reference point
bool useGpsVertVel; // true if GPS vertical velocity should be used