Plane: use ahrs.get_origin instead of ekf.getOriginLLH
This ensures we get the origin from the active EKF
This commit is contained in:
parent
62435d3a11
commit
f66d5f7a8c
@ -471,7 +471,7 @@ void Plane::Log_Write_Home_And_Origin()
|
|||||||
#if AP_AHRS_NAVEKF_AVAILABLE
|
#if AP_AHRS_NAVEKF_AVAILABLE
|
||||||
// log ekf origin if set
|
// log ekf origin if set
|
||||||
Location ekf_orig;
|
Location ekf_orig;
|
||||||
if (ahrs.get_NavEKF_const().getOriginLLH(ekf_orig)) {
|
if (ahrs.get_origin(ekf_orig)) {
|
||||||
DataFlash.Log_Write_Origin(LogOriginType::ekf_origin, ekf_orig);
|
DataFlash.Log_Write_Origin(LogOriginType::ekf_origin, ekf_orig);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user