|
|
|
@ -1,17 +1,10 @@
@@ -1,17 +1,10 @@
|
|
|
|
|
#include "Copter.h" |
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
|
* the home_state has a number of possible values (see enum HomeState in defines.h's) |
|
|
|
|
* HOME_UNSET = home is not set, no GPS positions yet received |
|
|
|
|
* HOME_SET_NOT_LOCKED = home is set to EKF origin or armed location (can be moved) |
|
|
|
|
* HOME_SET_AND_LOCKED = home has been set by user, cannot be moved except by user initiated do-set-home command |
|
|
|
|
*/ |
|
|
|
|
|
|
|
|
|
// checks if we should update ahrs/RTL home position from the EKF
|
|
|
|
|
void Copter::update_home_from_EKF() |
|
|
|
|
{ |
|
|
|
|
// exit immediately if home already set
|
|
|
|
|
if (ap.home_state != HOME_UNSET) { |
|
|
|
|
if (ahrs.home_is_set()) { |
|
|
|
|
return; |
|
|
|
|
} |
|
|
|
|
|
|
|
|
@ -83,11 +76,12 @@ bool Copter::set_home(const Location& loc, bool lock)
@@ -83,11 +76,12 @@ bool Copter::set_home(const Location& loc, bool lock)
|
|
|
|
|
ahrs.set_home(loc); |
|
|
|
|
|
|
|
|
|
// init inav and compass declination
|
|
|
|
|
if (ap.home_state == HOME_UNSET) { |
|
|
|
|
if (!ahrs.home_is_set()) { |
|
|
|
|
// update navigation scalers. used to offset the shrinking longitude as we go towards the poles
|
|
|
|
|
scaleLongDown = longitude_scale(loc); |
|
|
|
|
// record home is set
|
|
|
|
|
set_home_state(HOME_SET_NOT_LOCKED); |
|
|
|
|
ahrs.set_home_status(HOME_SET_NOT_LOCKED); |
|
|
|
|
Log_Write_Event(DATA_SET_HOME); |
|
|
|
|
|
|
|
|
|
#if MODE_AUTO_ENABLED == ENABLED |
|
|
|
|
// log new home position which mission library will pull from ahrs
|
|
|
|
@ -102,7 +96,7 @@ bool Copter::set_home(const Location& loc, bool lock)
@@ -102,7 +96,7 @@ bool Copter::set_home(const Location& loc, bool lock)
|
|
|
|
|
|
|
|
|
|
// lock home position
|
|
|
|
|
if (lock) { |
|
|
|
|
set_home_state(HOME_SET_AND_LOCKED); |
|
|
|
|
ahrs.set_home_status(HOME_SET_AND_LOCKED); |
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
// log ahrs home and ekf origin dataflash
|
|
|
|
|