Copter: sets SmartRTL home after AHRS home is set

Now calls AP_SmartRTL::set_home when arming. In addition, it calls it whenever
the ahrs home is set to the current location, whether by GCS or in-flight

Copter: merge
This commit is contained in:
Dylan Herman 2018-01-15 12:03:41 -05:00 committed by Randy Mackay
parent 3edaff0309
commit c772e2d3fd
2 changed files with 12 additions and 3 deletions

View File

@ -31,7 +31,11 @@ void Copter::set_home_to_current_location_inflight() {
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, false);
if (!set_home(temp_loc, false)) {
return;
}
// we have successfully set AHRS home, set it for SmartRTL
g2.smart_rtl.set_home(true);
}
}
@ -40,7 +44,12 @@ bool Copter::set_home_to_current_location(bool lock) {
// get current location from EKF
Location temp_loc;
if (inertial_nav.get_location(temp_loc)) {
return set_home(temp_loc, lock);
if (!set_home(temp_loc, lock)) {
return false;
}
// we have successfully set AHRS home, set it for SmartRTL
g2.smart_rtl.set_home(true);
return true;
}
return false;
}

View File

@ -180,7 +180,7 @@ bool Copter::init_arm_motors(bool arming_from_gcs)
update_super_simple_bearing(false);
// Reset SmartRTL return location. If activated, SmartRTL will ultimately try to land at this point
g2.smart_rtl.reset_path(position_ok());
g2.smart_rtl.set_home(position_ok());
// enable gps velocity based centrefugal force compensation
ahrs.set_correct_centrifugal(true);