Copter: split home-set and home-locked state

This commit is contained in:
Peter Barker 2018-05-18 12:58:50 +10:00 committed by Andrew Tridgell
parent 7be25fccea
commit c09ccf5b61
2 changed files with 5 additions and 4 deletions

View File

@ -72,15 +72,16 @@ bool Copter::set_home(const Location& loc, bool lock)
return false;
}
const bool home_was_set = ahrs.home_is_set();
// set ahrs home (used for RTL)
ahrs.set_home(loc);
// init inav and compass declination
if (!ahrs.home_is_set()) {
if (!home_was_set) {
// update navigation scalers. used to offset the shrinking longitude as we go towards the poles
scaleLongDown = longitude_scale(loc);
// record home is set
ahrs.set_home_status(HOME_SET_NOT_LOCKED);
Log_Write_Event(DATA_SET_HOME);
#if MODE_AUTO_ENABLED == ENABLED
@ -96,7 +97,7 @@ bool Copter::set_home(const Location& loc, bool lock)
// lock home position
if (lock) {
ahrs.set_home_status(HOME_SET_AND_LOCKED);
ahrs.lock_home();
}
// log ahrs home and ekf origin dataflash

View File

@ -180,7 +180,7 @@ bool Copter::init_arm_motors(bool arming_from_gcs)
// we have reset height, so arming height is zero
arming_altitude_m = 0;
} else if (ahrs.home_status() == HOME_SET_NOT_LOCKED) {
} else if (!ahrs.home_is_locked()) {
// Reset home position if it has already been set before (but not locked)
set_home_to_current_location(false);