mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 08:23:56 -04:00
AP_NavEKF2: Change misnomer (NFC)
This commit is contained in:
parent
ada6649be3
commit
af639f7812
@ -429,7 +429,7 @@ const AP_Param::GroupInfo NavEKF2::var_info[] = {
|
||||
// 36 was LOG_MASK, used for specifying which IMUs/cores to log
|
||||
// replay data for
|
||||
|
||||
// control of magentic yaw angle fusion
|
||||
// control of magnetic yaw angle fusion
|
||||
|
||||
// @Param: YAW_M_NSE
|
||||
// @DisplayName: Yaw measurement noise (rad)
|
||||
|
@ -1144,7 +1144,7 @@ void NavEKF2_core::alignMagStateDeclination()
|
||||
}
|
||||
}
|
||||
|
||||
// record a magentic field state reset event
|
||||
// record a magnetic field state reset event
|
||||
void NavEKF2_core::recordMagReset()
|
||||
{
|
||||
magStateInitComplete = true;
|
||||
|
@ -1074,7 +1074,7 @@ private:
|
||||
uint32_t touchdownExpectedSet_ms; // system time at which expectGndEffectTouchdown was set
|
||||
float meaHgtAtTakeOff; // height measured at commencement of takeoff
|
||||
|
||||
// control of post takeoff magentic field and heading resets
|
||||
// control of post takeoff magnetic field and heading resets
|
||||
bool finalInflightYawInit; // true when the final post takeoff initialisation of yaw angle has been performed
|
||||
bool finalInflightMagInit; // true when the final post takeoff initialisation of magnetic field states been performed
|
||||
bool magStateResetRequest; // true if magnetic field states need to be reset using the magneteomter measurements
|
||||
|
Loading…
Reference in New Issue
Block a user