12 #define SMARTRTL_ACCURACY_DEFAULT 2.0f // default _ACCURACY parameter value. Points will be no closer than this distance (in meters) together. 13 #define SMARTRTL_POINTS_DEFAULT 150 // default _POINTS parameter value. High numbers improve path pruning but use more memory and CPU for cleanup. Memory used will be 20bytes * this number. 14 #define SMARTRTL_POINTS_MAX 500 // the absolute maximum number of points this library can support. 15 #define SMARTRTL_TIMEOUT 15000 // the time in milliseconds with no points saved to the path (for whatever reason), before SmartRTL is disabled for the flight 16 #define SMARTRTL_CLEANUP_POINT_TRIGGER 50 // simplification will trigger when this many points are added to the path 17 #define SMARTRTL_CLEANUP_START_MARGIN 10 // routine cleanup algorithms begin when the path array has only this many empty slots remaining 18 #define SMARTRTL_CLEANUP_POINT_MIN 10 // cleanup algorithms will remove points if they remove at least this many points 19 #define SMARTRTL_SIMPLIFY_EPSILON (_accuracy * 0.5f) 20 #define SMARTRTL_SIMPLIFY_STACK_LEN_MULT (2.0f/3.0f)+1 // simplify buffer size as compared to maximum number of points. 23 #define SMARTRTL_SIMPLIFY_TIME_US 200 // maximum time (in microseconds) the simplification algorithm will run before returning 24 #define SMARTRTL_PRUNING_DELTA (_accuracy * 0.99) // How many meters apart must two points be, such that we can assume that there is no obstacle between them. must be smaller than _ACCURACY parameter 25 #define SMARTRTL_PRUNING_LOOP_BUFFER_LEN_MULT 0.25f // pruning loop buffer size as compared to maximum number of points 26 #define SMARTRTL_PRUNING_LOOP_TIME_US 200 // maximum time (in microseconds) that the loop finding algorithm will run before returning 58 void update(
bool position_ok,
bool save_position);
151 bool add_loop(uint16_t start_index, uint16_t end_index,
const Vector3f& midpoint);
uint32_t _last_position_save_ms
Vector3< float > Vector3f
void restart_simplify_if_new_points(uint16_t path_points_count)
void restart_pruning_if_new_points()
bool loops_overlap(const prune_loop_t &loop1, const prune_loop_t &loop2) const
uint32_t _thorough_clean_request_ms
Interface definition for the various Ground Control System.
void remove_points_by_simplify_bitmask()
bool request_thorough_cleanup(ThoroughCleanupType clean_type=THOROUGH_CLEAN_DEFAULT)
void routine_cleanup(uint16_t path_points_count, uint16_t path_points_complete_limit)
bool add_point(const Vector3f &point)
static const struct AP_Param::GroupInfo var_info[]
const Vector3f & get_point(uint16_t index) const
#define SMARTRTL_POINTS_MAX
uint16_t _path_points_completed_limit
uint32_t _last_good_position_ms
AP_HAL::Semaphore * _path_sem
void restart_simplification(uint16_t path_points_count)
AP_SmartRTL(bool example_mode=false)
void run_background_cleanup()
uint16_t _path_points_max
uint16_t _path_points_count
simplify_start_finish_t * stack
void update(bool position_ok, bool save_position)
uint16_t get_num_points() const
uint16_t path_points_count
static dist_point segment_segment_dist(const Vector3f &p1, const Vector3f &p2, const Vector3f &p3, const Vector3f &p4)
struct AP_SmartRTL::@183 _simplify
bool pop_point(Vector3f &point)
uint16_t path_points_completed
bool remove_points_by_loops(uint16_t num_points_to_remove)
void cancel_request_for_thorough_cleanup()
bool add_loop(uint16_t start_index, uint16_t end_index, const Vector3f &midpoint)
void detect_simplifications()
struct AP_SmartRTL::@184 _prune
void set_home(bool position_ok)
void deactivate(SRTL_Actions action, const char *reason)
void reset_simplification()
void log_action(SRTL_Actions action, const Vector3f &point=Vector3f())
fifo (queue) buffer template class
bool thorough_cleanup(uint16_t path_points_count, ThoroughCleanupType clean_type)
ThoroughCleanupType _thorough_clean_type
uint32_t _thorough_clean_complete_ms
void restart_pruning(uint16_t path_points_count)