Rover: follow mode restores offsets to zero on exit

This commit is contained in:
Randy Mackay 2019-10-04 10:24:36 +09:00 committed by Andrew Tridgell
parent da0c1d1b42
commit c06957ccdd
2 changed files with 7 additions and 0 deletions

View File

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

View File

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