diff --git a/APMrover2/mode.h b/APMrover2/mode.h index a91b1f8cd2..9910c95753 100644 --- a/APMrover2/mode.h +++ b/APMrover2/mode.h @@ -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: diff --git a/APMrover2/mode_smart_rtl.cpp b/APMrover2/mode_smart_rtl.cpp index 26b20e7ca3..c451d4f076 100644 --- a/APMrover2/mode_smart_rtl.cpp +++ b/APMrover2/mode_smart_rtl.cpp @@ -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); } diff --git a/APMrover2/system.cpp b/APMrover2/system.cpp index 527047d405..f1403330b6 100644 --- a/APMrover2/system.cpp +++ b/APMrover2/system.cpp @@ -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