mirror of https://github.com/ArduPilot/ardupilot
InertialNav: get_origin returns zero when no origin
If the EKF has not yet set the origin return location of all zeros instead of uninitialised location
This commit is contained in:
parent
da4a36c4e0
commit
8e75c9580c
|
@ -57,7 +57,10 @@ nav_filter_status AP_InertialNav_NavEKF::get_filter_status() const
|
|||
struct Location AP_InertialNav_NavEKF::get_origin() const {
|
||||
if (_ahrs.have_inertial_nav()) {
|
||||
struct Location ret;
|
||||
_ahrs_ekf.get_NavEKF().getOriginLLH(ret);
|
||||
if (!_ahrs_ekf.get_NavEKF().getOriginLLH(ret)) {
|
||||
// initialise location to all zeros if origin not yet set
|
||||
memset(&ret, 0, sizeof(ret));
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
return AP_InertialNav::get_origin();
|
||||
|
|
Loading…
Reference in New Issue