Browse Source

Rover: follow mode restores offsets to zero on exit

master
Randy Mackay 5 years ago
parent
commit
0ab5ebbd9b
  1. 1
      APMrover2/mode.h
  2. 6
      APMrover2/mode_follow.cpp

1
APMrover2/mode.h

@ -630,6 +630,7 @@ public:
protected: protected:
bool _enter() override; bool _enter() override;
void _exit() override;
}; };
class ModeSimple : public Mode class ModeSimple : public Mode

6
APMrover2/mode_follow.cpp

@ -14,6 +14,12 @@ bool ModeFollow::_enter()
return true; return true;
} }
// exit handling
void ModeFollow::_exit()
{
g2.follow.clear_offsets_if_required();
}
void ModeFollow::update() void ModeFollow::update()
{ {
// stop vehicle if no speed estimate // stop vehicle if no speed estimate

Loading…
Cancel
Save