diff --git a/APMrover2/mode.h b/APMrover2/mode.h index 906b5c2ea6..5df9c60124 100644 --- a/APMrover2/mode.h +++ b/APMrover2/mode.h @@ -419,7 +419,7 @@ protected: struct { uint32_t timeout_ms;// timeout from the time that guided is invoked float horiz_max; // horizontal position limit in meters from where guided mode was initiated (0 = no limit) - uint32_t start_time;// system time in milliseconds that control was handed to the external computer + uint32_t start_time_ms; // system time in milliseconds that control was handed to the external computer Location start_loc; // starting location for checking horiz_max limit } limit; }; diff --git a/APMrover2/mode_guided.cpp b/APMrover2/mode_guided.cpp index 429b7d720c..e57b164ee2 100644 --- a/APMrover2/mode_guided.cpp +++ b/APMrover2/mode_guided.cpp @@ -220,7 +220,7 @@ void ModeGuided::limit_clear() // only called from AUTO mode's start_guided method void ModeGuided::limit_init_time_and_location() { - limit.start_time = AP_HAL::millis(); + limit.start_time_ms = AP_HAL::millis(); limit.start_loc = rover.current_loc; } @@ -228,7 +228,7 @@ void ModeGuided::limit_init_time_and_location() bool ModeGuided::limit_breached() const { // check if we have passed the timeout - if ((limit.timeout_ms > 0) && (millis() - limit.start_time >= limit.timeout_ms)) { + if ((limit.timeout_ms > 0) && (millis() - limit.start_time_ms >= limit.timeout_ms)) { return true; }