Skip to content

Commit

Permalink
Rover: fix loiter_delay, cmd <0 sets a delay of 0 seconds
Browse files Browse the repository at this point in the history
  • Loading branch information
hendjoshsr71 authored and rmackay9 committed Jun 7, 2021
1 parent 96d0e8c commit 8b83b49
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions Rover/mode_auto.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -560,8 +560,8 @@ bool ModeAuto::do_nav_wp(const AP_Mission::Mission_Command& cmd, bool always_sto
// this will be used to remember the time in millis after we reach or pass the WP.
loiter_start_time = 0;

// this is the delay, stored in seconds
loiter_duration = cmd.p1;
// this is the delay, stored in seconds, checked such that commanded delays < 0 delay 0 seconds
loiter_duration = ((int16_t) cmd.p1 < 0) ? 0 : cmd.p1;

return true;
}
Expand Down

0 comments on commit 8b83b49

Please sign in to comment.