AP_NavEKF2: use vector comparison for new mag vector

This commit is contained in:
Andrew Tridgell 2016-04-21 09:56:22 +10:00
parent c9b1b02b8e
commit ac60901b0c
1 changed files with 1 additions and 1 deletions

View File

@ -185,7 +185,7 @@ void NavEKF2_core::readMagData()
// detect changes to magnetometer offset parameters and reset states
Vector3f nowMagOffsets = _ahrs->get_compass()->get_offsets(magSelectIndex);
bool changeDetected = lastMagOffsetsValid && (!is_equal(nowMagOffsets.x,lastMagOffsets.x) || !is_equal(nowMagOffsets.y,lastMagOffsets.y) || !is_equal(nowMagOffsets.z,lastMagOffsets.z));
bool changeDetected = lastMagOffsetsValid && (nowMagOffsets != lastMagOffsets);
if (changeDetected) {
// zero the learned magnetometer bias states
stateStruct.body_magfield.zero();