Skip to content

Commit

Permalink
AP_NavEKF2: use vector comparison for new mag vector
Browse files Browse the repository at this point in the history
  • Loading branch information
tridge committed Apr 20, 2016
1 parent c9b1b02 commit ac60901
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion libraries/AP_NavEKF2/AP_NavEKF2_Measurements.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
Expand Down

0 comments on commit ac60901

Please sign in to comment.