Browse Source

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

This changes things to work like the Copter equivalent
master
Peter Barker 7 years ago committed by Randy Mackay
parent
commit
89c830e949
  1. 2
      APMrover2/mode.h
  2. 3
      APMrover2/mode_smart_rtl.cpp
  3. 3
      APMrover2/system.cpp

2
APMrover2/mode.h

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

3
APMrover2/mode_smart_rtl.cpp

@ -87,7 +87,8 @@ void ModeSmartRTL::update()
} }
// save current position for use by the smart_rtl flight mode // 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); g2.smart_rtl.update(true, save_pos);
} }

3
APMrover2/system.cpp

@ -368,8 +368,7 @@ bool Rover::disarm_motors(void)
// save current position for use by the smart_rtl mode // save current position for use by the smart_rtl mode
void Rover::smart_rtl_update() void Rover::smart_rtl_update()
{ {
const bool save_position = (control_mode != &mode_smartrtl); mode_smartrtl.save_position();
mode_smartrtl.save_position(save_position);
} }
// returns true if vehicle is a boat // returns true if vehicle is a boat

Loading…
Cancel
Save