Copter: home-alt set to EKF-origin if captured in flight

This commit is contained in:
Randy Mackay 2015-05-13 15:25:50 +09:00
parent 2a1a105462
commit 1f96cbd015
1 changed files with 18 additions and 2 deletions

View File

@ -15,9 +15,25 @@ static void update_home_from_EKF()
return;
}
// special logic if home is set in-flight
if (motors.armed()) {
set_home_to_current_location_inflight();
} else {
// move home to current ekf location (this will set home_state to HOME_SET)
set_home_to_current_location();
}
}
// set_home_to_current_location_inflight - set home to current GPS location (horizontally) and EKF origin+ takeoff_alt_above_origin
static void set_home_to_current_location_inflight() {
// get current location from EKF
Location temp_loc;
if (inertial_nav.get_location(temp_loc)) {
const struct Location &ekf_origin = inertial_nav.get_origin();
temp_loc.alt = ekf_origin.alt;
set_home(temp_loc);
}
}
// set_home_to_current_location - set home to current GPS location
static bool set_home_to_current_location() {