mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_AHRS : altered NavEKF set home to reset position instead of reset filter
This commit is contained in:
parent
d0831c708d
commit
ab08a5c7d6
@ -192,7 +192,7 @@ void AP_AHRS_NavEKF::set_home(int32_t lat, int32_t lng, int32_t alt_cm)
|
||||
{
|
||||
AP_AHRS_DCM::set_home(lat, lng, alt_cm);
|
||||
if (ekf_started) {
|
||||
EKF.InitialiseFilter();
|
||||
EKF.ResetPosition();
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user