mirror of https://github.com/ArduPilot/ardupilot
Rover: guided mode fix for reached_destination during wpnav
This commit is contained in:
parent
34447fa7a8
commit
147b1284c9
|
@ -244,7 +244,7 @@ bool ModeGuided::reached_destination() const
|
||||||
{
|
{
|
||||||
switch (_guided_mode) {
|
switch (_guided_mode) {
|
||||||
case Guided_WP:
|
case Guided_WP:
|
||||||
return _reached_destination;
|
return g2.wp_nav.reached_destination();
|
||||||
case Guided_HeadingAndSpeed:
|
case Guided_HeadingAndSpeed:
|
||||||
case Guided_TurnRateAndSpeed:
|
case Guided_TurnRateAndSpeed:
|
||||||
case Guided_Loiter:
|
case Guided_Loiter:
|
||||||
|
|
Loading…
Reference in New Issue