mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
AP_NavEKF3: Change misnomer (NFC)
This commit is contained in:
parent
af639f7812
commit
ae565aef1a
@ -419,7 +419,7 @@ const AP_Param::GroupInfo NavEKF3::var_info[] = {
|
|||||||
// 36 was LOG_MASK, used for specifying which IMUs/cores to log
|
// 36 was LOG_MASK, used for specifying which IMUs/cores to log
|
||||||
// replay data for
|
// replay data for
|
||||||
|
|
||||||
// control of magentic yaw angle fusion
|
// control of magnetic yaw angle fusion
|
||||||
|
|
||||||
// @Param: YAW_M_NSE
|
// @Param: YAW_M_NSE
|
||||||
// @DisplayName: Yaw measurement noise (rad)
|
// @DisplayName: Yaw measurement noise (rad)
|
||||||
|
@ -1299,7 +1299,7 @@ private:
|
|||||||
uint32_t takeoffExpectedSet_ms; // system time at which expectTakeoff was set
|
uint32_t takeoffExpectedSet_ms; // system time at which expectTakeoff was set
|
||||||
bool expectTakeoff; // external state from vehicle conrol code - takeoff expected
|
bool expectTakeoff; // external state from vehicle conrol code - takeoff expected
|
||||||
|
|
||||||
// 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 finalInflightYawInit; // true when the final post takeoff initialisation of yaw angle has been performed
|
||||||
uint8_t magYawAnomallyCount; // Number of times the yaw has been reset due to a magnetic anomaly during initial ascent
|
uint8_t magYawAnomallyCount; // Number of times the yaw has been reset due to a magnetic anomaly during initial ascent
|
||||||
bool finalInflightMagInit; // true when the final post takeoff initialisation of magnetic field states been performed
|
bool finalInflightMagInit; // true when the final post takeoff initialisation of magnetic field states been performed
|
||||||
|
Loading…
Reference in New Issue
Block a user