AP_NavEKF3: minor comment and format fixes

This commit is contained in:
Randy Mackay 2020-10-28 11:32:05 +09:00
parent fccc1fcb72
commit 7b898ee001
3 changed files with 2 additions and 3 deletions

View File

@ -557,7 +557,7 @@ private:
uint32_t lastLaneSwitch_ms;
struct {
uint32_t last_function_call; // last time getLastYawYawResetAngle was called
uint32_t last_function_call; // last time getLastYawResetAngle was called
bool core_changed; // true when a core change happened and hasn't been consumed, false otherwise
uint32_t last_primary_change; // last time a primary has changed
float core_delta; // the amount of yaw change between cores when a change happened

View File

@ -419,7 +419,7 @@ void NavEKF3_core::checkAttitudeAlignmentStatus()
// submit yaw and magnetic field reset request
if (!yawAlignComplete && tiltAlignComplete && use_compass()) {
magYawResetRequest = true;
magYawResetRequest = true;
}
}

View File

@ -1897,7 +1897,6 @@ void NavEKF3_core::setYawFromMag()
return;
}
//Vector3f magMeasNED = Tbn_zeroYaw * magDataDelayed.mag;
Vector3f magMeasNED = Tbn_zeroYaw * magDataDelayed.mag;
float yawAngMeasured = wrap_PI(-atan2f(magMeasNED.y, magMeasNED.x) + MagDeclination());