mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Rover: follow mode restores offsets to zero on exit
This commit is contained in:
parent
e4336551cd
commit
0ab5ebbd9b
@ -630,6 +630,7 @@ public:
|
|||||||
protected:
|
protected:
|
||||||
|
|
||||||
bool _enter() override;
|
bool _enter() override;
|
||||||
|
void _exit() override;
|
||||||
};
|
};
|
||||||
|
|
||||||
class ModeSimple : public Mode
|
class ModeSimple : public Mode
|
||||||
|
@ -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…
Reference in New Issue
Block a user