Rover: make SmartRTL mode decide whether to save position or not

This changes things to work like the Copter equivalent
This commit is contained in:
Peter Barker 2018-02-12 16:16:23 +11:00 committed by Randy Mackay
parent 0ca653c8dd
commit 89c830e949
3 changed files with 4 additions and 4 deletions

View File

@ -358,7 +358,7 @@ public:
bool reached_destination() override { return smart_rtl_state == SmartRTL_StopAtHome; }
// save current position for use by the smart_rtl flight mode
void save_position(bool save_pos);
void save_position();
protected:

View File

@ -87,7 +87,8 @@ void ModeSmartRTL::update()
}
// save current position for use by the smart_rtl flight mode
void ModeSmartRTL::save_position(bool save_pos)
void ModeSmartRTL::save_position()
{
const bool save_pos = (rover.control_mode != &rover.mode_smartrtl);
g2.smart_rtl.update(true, save_pos);
}

View File

@ -368,8 +368,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 = (control_mode != &mode_smartrtl);
mode_smartrtl.save_position(save_position);
mode_smartrtl.save_position();
}
// returns true if vehicle is a boat