mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
Rover: sets SmartRTL home after ahrs home is set
Now uses AP_SmartRTL::set_home. It is called when arming and when GCS requests home to be set to the current location
This commit is contained in:
parent
85e1f9f9f6
commit
3edaff0309
@ -18,7 +18,12 @@ bool Rover::set_home_to_current_location(bool lock)
|
||||
// use position from EKF if available otherwise use GPS
|
||||
Location temp_loc;
|
||||
if (ahrs.have_inertial_nav() && ahrs.get_position(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;
|
||||
}
|
||||
|
@ -331,8 +331,8 @@ bool Rover::arm_motors(AP_Arming::ArmingMethod method)
|
||||
return false;
|
||||
}
|
||||
|
||||
// Reset SmartRTL return location. If activated, SmartRTL will ultimately try to land at this point
|
||||
g2.smart_rtl.reset_path(true);
|
||||
// Set the SmartRTL home location. If activated, SmartRTL will ultimately try to land at this point
|
||||
g2.smart_rtl.set_home(true);
|
||||
|
||||
change_arm_state();
|
||||
return true;
|
||||
@ -360,7 +360,7 @@ bool Rover::disarm_motors(void)
|
||||
// save current position for use by the smart_rtl mode
|
||||
void Rover::smart_rtl_update()
|
||||
{
|
||||
const bool save_position = hal.util->get_soft_armed() && (control_mode != &mode_smartrtl);
|
||||
const bool save_position = (control_mode != &mode_smartrtl);
|
||||
mode_smartrtl.save_position(save_position);
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user