Browse Source

Rover: correct get_distance_to_destination in loiter mode

master
Peter Barker 6 years ago committed by Randy Mackay
parent
commit
c61412d2d1
  1. 3
      APMrover2/mode_guided.cpp

3
APMrover2/mode_guided.cpp

@ -121,8 +121,7 @@ float ModeGuided::get_distance_to_destination() const @@ -121,8 +121,7 @@ float ModeGuided::get_distance_to_destination() const
case Guided_TurnRateAndSpeed:
return 0.0f;
case Guided_Loiter:
rover.mode_loiter.get_distance_to_destination();
break;
return rover.mode_loiter.get_distance_to_destination();
}
// we should never reach here but just in case, return 0

Loading…
Cancel
Save