Browse Source

AP_SmartRTL: give warning buffer is about to fill-up

master
Henry Wurzburg 5 years ago committed by Randy Mackay
parent
commit
13e66e9f7c
  1. 7
      libraries/AP_SmartRTL/AP_SmartRTL.cpp
  2. 1
      libraries/AP_SmartRTL/AP_SmartRTL.h

7
libraries/AP_SmartRTL/AP_SmartRTL.cpp

@ -350,6 +350,13 @@ void AP_SmartRTL::run_background_cleanup() @@ -350,6 +350,13 @@ void AP_SmartRTL::run_background_cleanup()
// perform routine cleanup which removes 10 to 50 points if possible
routine_cleanup(path_points_count, path_points_completed_limit);
// warn if buffer is about to be filled
if ((path_points_count >0) && (path_points_count >= _path_points_max - 9) && (AP_HAL::millis() - _last_low_space_notify_ms > 10000)) {
gcs().send_text(MAV_SEVERITY_INFO, "SmartRTL Low on space!");
_last_low_space_notify_ms = now;
}
}
// routine cleanup is called regularly from run_background_cleanup

1
libraries/AP_SmartRTL/AP_SmartRTL.h

@ -173,6 +173,7 @@ private: @@ -173,6 +173,7 @@ private:
uint32_t _last_position_save_ms; // the system time a position was saved to the path (used for timeout)
uint32_t _thorough_clean_request_ms;// the last system time the thorough cleanup was requested (set by thorough_cleanup method, used by background cleanup)
uint32_t _thorough_clean_complete_ms; // set to _thorough_clean_request_ms when the background thread completes the thorough cleanup
uint32_t _last_low_space_notify_ms; //last time low on SmartRTL space was notified on Mavlink. Minimum time is required before re-notification to avoid nagging.
ThoroughCleanupType _thorough_clean_type; // used by example sketch to test simplify and prune separately
// path variables

Loading…
Cancel
Save