AP_SmartRTL.cpp 31 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #include "AP_SmartRTL.h"
  14. #include <AP_AHRS/AP_AHRS.h>
  15. #include <AP_Logger/AP_Logger.h>
  16. #include <GCS_MAVLink/GCS.h>
  17. extern const AP_HAL::HAL& hal;
  18. const AP_Param::GroupInfo AP_SmartRTL::var_info[] = {
  19. // @Param: ACCURACY
  20. // @DisplayName: SmartRTL accuracy
  21. // @Description: SmartRTL accuracy. The minimum distance between points.
  22. // @Units: m
  23. // @Range: 0 10
  24. // @User: Advanced
  25. AP_GROUPINFO("ACCURACY", 0, AP_SmartRTL, _accuracy, SMARTRTL_ACCURACY_DEFAULT),
  26. // @Param: POINTS
  27. // @DisplayName: SmartRTL maximum number of points on path
  28. // @Description: SmartRTL maximum number of points on path. Set to 0 to disable SmartRTL. 100 points consumes about 3k of memory.
  29. // @Range: 0 500
  30. // @User: Advanced
  31. // @RebootRequired: True
  32. AP_GROUPINFO("POINTS", 1, AP_SmartRTL, _points_max, SMARTRTL_POINTS_DEFAULT),
  33. AP_GROUPEND
  34. };
  35. /*
  36. * This library is used for the Safe Return-to-Launch feature. The vehicle's
  37. * position (aka "bread crumbs") are stored into an array in memory at
  38. * regular intervals. After a certain number of bread crumbs have been
  39. * stored and space within the array is low, clean-up algorithms are run to
  40. * reduce the total number of points. When Safe-RTL is initiated by the
  41. * vehicle code, a more thorough cleanup runs and the resulting path is fed
  42. * into navigation controller to return the vehicle to home.
  43. *
  44. * The cleanup consists of two parts, pruning and simplification:
  45. *
  46. * 1. Pruning calculates the closest distance between two line segments formed
  47. * by two pairs of sequential points, and then cuts out anything between two
  48. * points when their line segments get close. This algorithm will never
  49. * compare two consecutive line segments. Obviously the segments (p1,p2) and
  50. * (p2,p3) will get very close (they touch), but there would be nothing to
  51. * trim between them.
  52. *
  53. * 2. Simplification uses the Ramer-Douglas-Peucker algorithm. See Wikipedia
  54. * for a more complete description.
  55. *
  56. * The simplification and pruning algorithms run in the background and do not
  57. * alter the path in memory. Two definitions, SMARTRTL_SIMPLIFY_TIME_US and
  58. * SMARTRTL_PRUNING_LOOP_TIME_US are used to limit how long each algorithm will
  59. * be run before they save their state and return.
  60. *
  61. * Both algorithms are "anytime algorithms" meaning they can be interrupted
  62. * before they complete which is helpful when memory is filling up and we just
  63. * need to quickly identify a handful of points which can be deleted.
  64. *
  65. * Once the algorithms have completed the simplify.complete and
  66. * prune.complete flags are set to true. The "thorough cleanup" procedure,
  67. * which is run as the vehicle initiates the SmartRTL flight mode, waits for
  68. * these flags to become true. This can force the vehicle to pause for a few
  69. * seconds before initiating the return journey.
  70. */
  71. AP_SmartRTL::AP_SmartRTL(bool example_mode) :
  72. _example_mode(example_mode)
  73. {
  74. AP_Param::setup_object_defaults(this, var_info);
  75. _simplify.bitmask.setall();
  76. }
  77. // initialise safe rtl including setting up background processes
  78. void AP_SmartRTL::init()
  79. {
  80. // protect against repeated call to init
  81. if (_path != nullptr) {
  82. return;
  83. }
  84. // constrain the path length, in case the user decided to make the path unreasonably long.
  85. _points_max = constrain_int16(_points_max, 0, SMARTRTL_POINTS_MAX);
  86. // check if user has disabled SmartRTL
  87. if (_points_max == 0 || !is_positive(_accuracy)) {
  88. return;
  89. }
  90. // allocate arrays
  91. _path = (Vector3f*)calloc(_points_max, sizeof(Vector3f));
  92. _prune.loops_max = _points_max * SMARTRTL_PRUNING_LOOP_BUFFER_LEN_MULT;
  93. _prune.loops = (prune_loop_t*)calloc(_prune.loops_max, sizeof(prune_loop_t));
  94. _simplify.stack_max = _points_max * SMARTRTL_SIMPLIFY_STACK_LEN_MULT;
  95. _simplify.stack = (simplify_start_finish_t*)calloc(_simplify.stack_max, sizeof(simplify_start_finish_t));
  96. // check if memory allocation failed
  97. if (_path == nullptr || _prune.loops == nullptr || _simplify.stack == nullptr) {
  98. log_action(SRTL_DEACTIVATED_INIT_FAILED);
  99. gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL deactivated: init failed");
  100. free(_path);
  101. free(_prune.loops);
  102. free(_simplify.stack);
  103. return;
  104. }
  105. _path_points_max = _points_max;
  106. // when running the example sketch, we want the cleanup tasks to run when we tell them to, not in the background (so that they can be timed.)
  107. if (!_example_mode){
  108. // register background cleanup to run in IO thread
  109. hal.scheduler->register_io_process(FUNCTOR_BIND_MEMBER(&AP_SmartRTL::run_background_cleanup, void));
  110. }
  111. }
  112. // returns number of points on the path
  113. uint16_t AP_SmartRTL::get_num_points() const
  114. {
  115. return _path_points_count;
  116. }
  117. // get next point on the path to home, returns true on success
  118. bool AP_SmartRTL::pop_point(Vector3f& point)
  119. {
  120. // check we are active
  121. if (!_active) {
  122. return false;
  123. }
  124. // get semaphore
  125. if (!_path_sem.take_nonblocking()) {
  126. log_action(SRTL_POP_FAILED_NO_SEMAPHORE);
  127. return false;
  128. }
  129. // check we have another point
  130. if (_path_points_count == 0) {
  131. _path_sem.give();
  132. return false;
  133. }
  134. // return last point and remove from path
  135. point = _path[--_path_points_count];
  136. // record count of last point popped
  137. _path_points_completed_limit = _path_points_count;
  138. _path_sem.give();
  139. return true;
  140. }
  141. // clear return path and set home location. This should be called as part of the arming procedure
  142. void AP_SmartRTL::set_home(bool position_ok)
  143. {
  144. Vector3f current_pos;
  145. position_ok &= AP::ahrs().get_relative_position_NED_origin(current_pos);
  146. set_home(position_ok, current_pos);
  147. }
  148. void AP_SmartRTL::set_home(bool position_ok, const Vector3f& current_pos)
  149. {
  150. if (_path == nullptr) {
  151. return;
  152. }
  153. // clear path
  154. _path_points_count = 0;
  155. // reset simplification and pruning. These functions access members that should normally only
  156. // be touched by the background thread but it will not be running because active should be false
  157. reset_simplification();
  158. reset_pruning();
  159. // don't continue if no position at take-off
  160. if (!position_ok) {
  161. return;
  162. }
  163. // save current position as first point in path
  164. if (!add_point(current_pos)) {
  165. return;
  166. }
  167. // successfully added point and reset path
  168. _last_good_position_ms = AP_HAL::millis();
  169. _active = true;
  170. _home_saved = true;
  171. }
  172. // call this at 3hz (or higher) regardless of what mode the vehicle is in
  173. void AP_SmartRTL::update(bool position_ok, bool save_position)
  174. {
  175. // try to save home if not already saved
  176. if (position_ok && !_home_saved) {
  177. set_home(true);
  178. }
  179. if (!_active || !save_position) {
  180. return;
  181. }
  182. Vector3f current_pos;
  183. position_ok &= AP::ahrs().get_relative_position_NED_origin(current_pos);
  184. update(position_ok, current_pos);
  185. }
  186. void AP_SmartRTL::update(bool position_ok, const Vector3f& current_pos)
  187. {
  188. if (!_active) {
  189. return;
  190. }
  191. if (position_ok) {
  192. const uint32_t now = AP_HAL::millis();
  193. _last_good_position_ms = now;
  194. // add the point
  195. if (add_point(current_pos)) {
  196. _last_position_save_ms = now;
  197. } else if (AP_HAL::millis() - _last_position_save_ms > SMARTRTL_TIMEOUT) {
  198. // deactivate after timeout due to failure to save points to path (most likely due to buffer filling up)
  199. deactivate(SRTL_DEACTIVATED_PATH_FULL_TIMEOUT, "buffer full");
  200. }
  201. } else {
  202. // check for timeout due to bad position
  203. if (AP_HAL::millis() - _last_good_position_ms > SMARTRTL_TIMEOUT) {
  204. deactivate(SRTL_DEACTIVATED_BAD_POSITION_TIMEOUT, "bad position");
  205. return;
  206. }
  207. }
  208. }
  209. // request thorough cleanup including simplification, pruning and removal of all unnecessary points
  210. // returns true if the thorough cleanup was completed, false if it has not yet completed
  211. // this method should be called repeatedly until it returns true before initiating the return journey
  212. bool AP_SmartRTL::request_thorough_cleanup(ThoroughCleanupType clean_type)
  213. {
  214. // this should never happen but just in case
  215. if (!_active) {
  216. return false;
  217. }
  218. // request thorough cleanup
  219. if (_thorough_clean_request_ms == 0) {
  220. _thorough_clean_request_ms = AP_HAL::millis();
  221. if (clean_type != THOROUGH_CLEAN_DEFAULT) {
  222. _thorough_clean_type = clean_type;
  223. }
  224. return false;
  225. }
  226. // check if background thread has completed request
  227. if (_thorough_clean_complete_ms == _thorough_clean_request_ms) {
  228. _thorough_clean_request_ms = 0;
  229. return true;
  230. }
  231. return false;
  232. }
  233. // cancel request for thorough cleanup
  234. void AP_SmartRTL::cancel_request_for_thorough_cleanup()
  235. {
  236. _thorough_clean_request_ms = 0;
  237. }
  238. //
  239. // Private methods
  240. //
  241. // add point to end of path (if necessary), returns true on success
  242. bool AP_SmartRTL::add_point(const Vector3f& point)
  243. {
  244. // get semaphore
  245. if (!_path_sem.take_nonblocking()) {
  246. log_action(SRTL_ADD_FAILED_NO_SEMAPHORE, point);
  247. return false;
  248. }
  249. // check if we have traveled far enough
  250. if (_path_points_count > 0) {
  251. const Vector3f& last_pos = _path[_path_points_count-1];
  252. if (last_pos.distance_squared(point) < sq(_accuracy.get())) {
  253. _path_sem.give();
  254. return true;
  255. }
  256. }
  257. // check we have space in the path
  258. if (_path_points_count >= _path_points_max) {
  259. _path_sem.give();
  260. log_action(SRTL_ADD_FAILED_PATH_FULL, point);
  261. return false;
  262. }
  263. // add point to path
  264. _path[_path_points_count++] = point;
  265. log_action(SRTL_POINT_ADD, point);
  266. _path_sem.give();
  267. return true;
  268. }
  269. // run background cleanup - should be run regularly from the IO thread
  270. void AP_SmartRTL::run_background_cleanup()
  271. {
  272. if (!_active) {
  273. return;
  274. }
  275. // get semaphore
  276. if (!_path_sem.take_nonblocking()) {
  277. return;
  278. }
  279. // local copy of _path_points_count and _path_points_completed_limit
  280. const uint16_t path_points_count = _path_points_count;
  281. const uint16_t path_points_completed_limit = _path_points_completed_limit;
  282. _path_points_completed_limit = SMARTRTL_POINTS_MAX;
  283. _path_sem.give();
  284. // check if thorough cleanup is required
  285. if (_thorough_clean_request_ms > 0) {
  286. // check if we have already completed the request
  287. if (_thorough_clean_complete_ms != _thorough_clean_request_ms) {
  288. if (thorough_cleanup(path_points_count, _thorough_clean_type)) {
  289. // record completion
  290. _thorough_clean_complete_ms = _thorough_clean_request_ms;
  291. }
  292. }
  293. // we do not perform any further detection or cleanup until the requester acknowledges
  294. // they have what they need by setting _thorough_clean_request_ms back to zero
  295. return;
  296. }
  297. // ensure clean complete time is zero
  298. _thorough_clean_complete_ms = 0;
  299. // perform routine cleanup which removes 10 to 50 points if possible
  300. routine_cleanup(path_points_count, path_points_completed_limit);
  301. }
  302. // routine cleanup is called regularly from run_background_cleanup
  303. // simplifies the path after SMARTRTL_CLEANUP_POINT_TRIGGER points (50 points) have been added OR
  304. // SMARTRTL_CLEANUP_POINT_MIN (10 points) have been added and the path has less than SMARTRTL_CLEANUP_START_MARGIN spaces (10 spaces) remaining
  305. // prunes the path if the path has less than SMARTRTL_CLEANUP_START_MARGIN spaces (10 spaces) remaining
  306. void AP_SmartRTL::routine_cleanup(uint16_t path_points_count, uint16_t path_points_completed_limit)
  307. {
  308. // if simplify is running, let it run to completion
  309. if (!_simplify.complete) {
  310. detect_simplifications();
  311. return;
  312. }
  313. // remove simplified from path if required
  314. if (_simplify.removal_required) {
  315. remove_points_by_simplify_bitmask();
  316. return;
  317. }
  318. // if necessary restart detect_pruning up to last point simplified
  319. if (_prune.complete) {
  320. restart_pruning_if_new_points();
  321. }
  322. // if pruning is running, let it run to completion
  323. if (!_prune.complete) {
  324. detect_loops();
  325. return;
  326. }
  327. // detect path shrinkage and reduce simplify and prune path_points_completed count
  328. if (_simplify.path_points_completed > path_points_completed_limit) {
  329. _simplify.path_points_completed = path_points_completed_limit;
  330. }
  331. if (_prune.path_points_completed > path_points_completed_limit) {
  332. _prune.path_points_completed = path_points_completed_limit;
  333. }
  334. // calculate the number of points we could simplify
  335. const uint16_t points_to_simplify = (path_points_count > _simplify.path_points_completed) ? (path_points_count - _simplify.path_points_completed) : 0 ;
  336. const bool low_on_space = (_path_points_max - path_points_count) <= SMARTRTL_CLEANUP_START_MARGIN;
  337. // if 50 points can be simplified or we are low on space and at least 10 points can be simplified
  338. if ((points_to_simplify >= SMARTRTL_CLEANUP_POINT_TRIGGER) || (low_on_space && (points_to_simplify >= SMARTRTL_CLEANUP_POINT_MIN))) {
  339. restart_simplification(path_points_count);
  340. return;
  341. }
  342. // we are low on space, prune
  343. if (low_on_space) {
  344. // remove at least 10 points
  345. remove_points_by_loops(SMARTRTL_CLEANUP_POINT_MIN);
  346. }
  347. }
  348. // thorough cleanup simplifies and prunes all loops. returns true if the cleanup was completed.
  349. // path_points_count is _path_points_count but passed in to avoid having to take the semaphore
  350. bool AP_SmartRTL::thorough_cleanup(uint16_t path_points_count, ThoroughCleanupType clean_type)
  351. {
  352. if (clean_type != THOROUGH_CLEAN_PRUNE_ONLY) {
  353. // restart simplify if new points have appeared on path
  354. if (_simplify.complete) {
  355. restart_simplify_if_new_points(path_points_count);
  356. }
  357. // if simplification is not complete, run it
  358. if (!_simplify.complete) {
  359. detect_simplifications();
  360. return false;
  361. }
  362. // remove simplified points from path if required
  363. if (_simplify.removal_required) {
  364. remove_points_by_simplify_bitmask();
  365. return false;
  366. }
  367. }
  368. if (clean_type != THOROUGH_CLEAN_SIMPLIFY_ONLY) {
  369. // if necessary restart detect_pruning up to last point simplified
  370. if (_prune.complete) {
  371. restart_pruning_if_new_points();
  372. }
  373. // if pruning is not complete, run it
  374. if (!_prune.complete) {
  375. detect_loops();
  376. return false;
  377. }
  378. // remove pruning points
  379. if (!remove_points_by_loops(SMARTRTL_POINTS_MAX)) {
  380. return false;
  381. }
  382. }
  383. return true;
  384. }
  385. // Simplifies a 3D path, according to the Ramer-Douglas-Peucker algorithm.
  386. // _simplify.complete is set to true when all simplifications on the path have been identified
  387. void AP_SmartRTL::detect_simplifications()
  388. {
  389. // complete immediately if only one segment
  390. if (_simplify.path_points_count < 3) {
  391. _simplify.complete = true;
  392. return;
  393. }
  394. // if not complete but also nothing to do, we must be restarting
  395. if (_simplify.stack_count == 0) {
  396. // reset to beginning state. add a single element in the array with:
  397. // start = first path point OR the index of the last already-simplified point
  398. // finish = final path point
  399. _simplify.stack[0].start = (_simplify.path_points_completed > 0) ? _simplify.path_points_completed - 1 : 0;
  400. _simplify.stack[0].finish = _simplify.path_points_count-1;
  401. _simplify.stack_count++;
  402. }
  403. const uint32_t start_time_us = AP_HAL::micros();
  404. while (_simplify.stack_count > 0) { // while there is something to do
  405. // if this method has run for long enough, exit
  406. if (AP_HAL::micros() - start_time_us > SMARTRTL_SIMPLIFY_TIME_US) {
  407. return;
  408. }
  409. // pop last item off the simplify stack
  410. const simplify_start_finish_t tmp = _simplify.stack[--_simplify.stack_count];
  411. const uint16_t start_index = tmp.start;
  412. const uint16_t end_index = tmp.finish;
  413. // find the point between start and end points that is farthest from the start-end line segment
  414. float max_dist = 0.0f;
  415. uint16_t farthest_point_index = start_index;
  416. for (uint16_t i = start_index + 1; i < end_index; i++) {
  417. // only check points that have not already been flagged for simplification
  418. if (_simplify.bitmask.get(i)) {
  419. const float dist = _path[i].distance_to_segment(_path[start_index], _path[end_index]);
  420. if (dist > max_dist) {
  421. farthest_point_index = i;
  422. max_dist = dist;
  423. }
  424. }
  425. }
  426. // if the farthest point is more than ACCURACY * 0.5 add two new elements to the _simplification_stack
  427. // so that on the next iteration we will check between start-to-farthestpoint and farthestpoint-to-end
  428. if (max_dist > SMARTRTL_SIMPLIFY_EPSILON) {
  429. // if the to-do list is full, give up on simplifying. This should never happen.
  430. if (_simplify.stack_count >= _simplify.stack_max) {
  431. _simplify.complete = true;
  432. return;
  433. }
  434. _simplify.stack[_simplify.stack_count++] = simplify_start_finish_t {start_index, farthest_point_index};
  435. _simplify.stack[_simplify.stack_count++] = simplify_start_finish_t {farthest_point_index, end_index};
  436. } else {
  437. // if the farthest point was closer than ACCURACY * 0.5 we can simplify all points between start and end
  438. for (uint16_t i = start_index + 1; i < end_index; i++) {
  439. _simplify.bitmask.clear(i);
  440. _simplify.removal_required = true;
  441. }
  442. }
  443. }
  444. _simplify.path_points_completed = _simplify.path_points_count;
  445. _simplify.complete = true;
  446. }
  447. /**
  448. * This method runs for the allotted time, and detects loops in a path. Any detected loops are added to _prune.loops,
  449. * this function does not alter the path in memory. It works by comparing the line segment between any two sequential points
  450. * to the line segment between any other two sequential points. If they get close enough, anything between them could be pruned.
  451. *
  452. * reset_pruning should have been called at least once before this function is called to setup the indexes (_prune.i, etc)
  453. */
  454. void AP_SmartRTL::detect_loops()
  455. {
  456. // if there are less than 4 points (3 segments), mark complete
  457. if (_prune.path_points_count < 4) {
  458. _prune.complete = true;
  459. return;
  460. }
  461. // capture start time
  462. const uint32_t start_time_us = AP_HAL::micros();
  463. // run for defined amount of time
  464. while (AP_HAL::micros() - start_time_us < SMARTRTL_PRUNING_LOOP_TIME_US) {
  465. // advance inner loop
  466. _prune.j++;
  467. if (_prune.j > _prune.i - 2) {
  468. // set inner loop back to first point
  469. _prune.j = 1;
  470. // reduce outer loop
  471. _prune.i--;
  472. // complete when outer loop has run out of new points to check
  473. if (_prune.i < 4 || _prune.i < _prune.path_points_completed) {
  474. _prune.complete = true;
  475. _prune.path_points_completed = _prune.path_points_count;
  476. return;
  477. }
  478. }
  479. // find the closest distance between two line segments and the mid-point
  480. dist_point dp = segment_segment_dist(_path[_prune.i], _path[_prune.i-1], _path[_prune.j-1], _path[_prune.j]);
  481. if (dp.distance < SMARTRTL_PRUNING_DELTA) {
  482. // if there is a loop here, add to loop array
  483. if (!add_loop(_prune.j, _prune.i-1, dp.midpoint)) {
  484. // if the buffer is full, stop trying to prune
  485. _prune.complete = true;
  486. }
  487. // set inner loop forward to trigger outer loop move to next segment
  488. _prune.j = _prune.i;
  489. }
  490. }
  491. }
  492. // restart simplify if new points have been added to path
  493. // path_points_count is _path_points_count but passed in to avoid having to take the semaphore
  494. void AP_SmartRTL::restart_simplify_if_new_points(uint16_t path_points_count)
  495. {
  496. // any difference in the number of points is because of new points being added to path
  497. if (_simplify.path_points_count != path_points_count) {
  498. restart_simplification(path_points_count);
  499. }
  500. }
  501. // reset pruning if new points have been simplified
  502. void AP_SmartRTL::restart_pruning_if_new_points()
  503. {
  504. // any difference in the number of points is because of new points being added to path
  505. if (_prune.path_points_count != _simplify.path_points_completed) {
  506. restart_pruning(_simplify.path_points_completed);
  507. }
  508. }
  509. // restart simplification algorithm so that it will check new points in the path
  510. void AP_SmartRTL::restart_simplification(uint16_t path_points_count)
  511. {
  512. _simplify.complete = false;
  513. _simplify.removal_required = false;
  514. _simplify.bitmask.setall();
  515. _simplify.stack_count = 0;
  516. _simplify.path_points_count = path_points_count;
  517. }
  518. // reset simplification algorithm so that it will re-check all points in the path
  519. void AP_SmartRTL::reset_simplification()
  520. {
  521. restart_simplification(0);
  522. _simplify.path_points_completed = 0;
  523. }
  524. // restart pruning algorithm to check new points that have arrived
  525. void AP_SmartRTL::restart_pruning(uint16_t path_points_count)
  526. {
  527. _prune.complete = false;
  528. _prune.i = (path_points_count > 0) ? path_points_count - 1 : 0;
  529. _prune.j = 0;
  530. _prune.path_points_count = path_points_count;
  531. }
  532. // reset pruning algorithm so that it will re-check all points in the path
  533. void AP_SmartRTL::reset_pruning()
  534. {
  535. restart_pruning(0);
  536. _prune.loops_count = 0; // clear the loops that we've recorded
  537. _prune.path_points_completed = 0;
  538. }
  539. // remove all simplify-able points from the path
  540. void AP_SmartRTL::remove_points_by_simplify_bitmask()
  541. {
  542. // get semaphore before modifying path
  543. if (!_path_sem.take_nonblocking()) {
  544. return;
  545. }
  546. uint16_t dest = 1;
  547. uint16_t removed = 0;
  548. for (uint16_t src = 1; src < _path_points_count; src++) {
  549. if (!_simplify.bitmask.get(src)) {
  550. log_action(SRTL_POINT_SIMPLIFY, _path[src]);
  551. removed++;
  552. } else {
  553. _path[dest] = _path[src];
  554. dest++;
  555. }
  556. }
  557. // reduce count of the number of points simplified
  558. if (_path_points_count > removed && _simplify.path_points_count > removed) {
  559. _path_points_count -= removed;
  560. _simplify.path_points_count -= removed;
  561. _simplify.path_points_completed = _simplify.path_points_count;
  562. } else {
  563. // this is an error that should never happen so deactivate
  564. deactivate(SRTL_DEACTIVATED_PROGRAM_ERROR, "program error");
  565. }
  566. _path_sem.give();
  567. // flag point removal is complete
  568. _simplify.bitmask.setall();
  569. _simplify.removal_required = false;
  570. }
  571. // remove loops until at least num_point_to_delete have been removed from path
  572. // does not necessarily prune all loops
  573. // returns false if it failed to remove points (because it could not take semaphore)
  574. bool AP_SmartRTL::remove_points_by_loops(uint16_t num_points_to_remove)
  575. {
  576. // exit immediately if no loops to prune
  577. if (_prune.loops_count == 0) {
  578. return true;
  579. }
  580. // get semaphore before modifying path
  581. if (!_path_sem.take_nonblocking()) {
  582. return false;
  583. }
  584. uint16_t removed_points = 0;
  585. uint16_t i = _prune.loops_count;
  586. while ((i > 0) && (removed_points < num_points_to_remove)) {
  587. i--;
  588. prune_loop_t loop = _prune.loops[i];
  589. // midpoint goes into start_index (this is the end point of the first segment)
  590. _path[loop.start_index] = loop.midpoint;
  591. // shift points after the end of the loop down by the number of points in the loop
  592. uint16_t loop_num_points_to_remove = loop.end_index - loop.start_index;
  593. for (uint16_t dest = loop.start_index + 1; dest < _path_points_count - loop_num_points_to_remove; dest++) {
  594. log_action(SRTL_POINT_PRUNE, _path[dest]);
  595. _path[dest] = _path[dest + loop_num_points_to_remove];
  596. }
  597. if (_path_points_count > loop_num_points_to_remove) {
  598. _path_points_count -= loop_num_points_to_remove;
  599. removed_points += loop_num_points_to_remove;
  600. } else {
  601. // this is an error that should never happen so deactivate
  602. deactivate(SRTL_DEACTIVATED_PROGRAM_ERROR, "program error");
  603. _path_sem.give();
  604. // we return true so thorough_cleanup does not get stuck
  605. return true;
  606. }
  607. // fix the indices of any existing prune loops
  608. // we do not check for overlapping loops because add_loops should have caught them
  609. for (uint16_t loop_cnt = 0; loop_cnt < i; loop_cnt++) {
  610. if (_prune.loops[loop_cnt].start_index >= loop.end_index) {
  611. _prune.loops[loop_cnt].start_index -= loop_num_points_to_remove;
  612. }
  613. if (_prune.loops[loop_cnt].end_index >= loop.end_index) {
  614. _prune.loops[loop_cnt].end_index -= loop_num_points_to_remove;
  615. }
  616. }
  617. // remove last prune loop from array
  618. _prune.loops_count--;
  619. }
  620. _path_sem.give();
  621. return true;
  622. }
  623. // add loop to loops array
  624. // returns true if loop added successfully, false if loop array is full
  625. // checks if loop overlaps with an existing loop, keeps only the longer loop
  626. bool AP_SmartRTL::add_loop(uint16_t start_index, uint16_t end_index, const Vector3f& midpoint)
  627. {
  628. // if the buffer is full, return failure
  629. if (_prune.loops_count >= _prune.loops_max) {
  630. return false;
  631. }
  632. // sanity check indices
  633. if (end_index <= start_index) {
  634. return false;
  635. }
  636. // create new loop structure and calculate length squared of loop
  637. prune_loop_t new_loop = {start_index, end_index, midpoint, 0.0f};
  638. new_loop.length_squared = midpoint.distance_squared(_path[start_index]) + midpoint.distance_squared(_path[end_index]);
  639. for (uint16_t i = start_index; i < end_index; i++) {
  640. new_loop.length_squared += _path[i].distance_squared(_path[i+1]);
  641. }
  642. // look for overlapping loops and find their combined length
  643. bool overlapping_loops = false;
  644. float overlapping_loop_length = 0.0f;
  645. for (uint16_t loop_idx = 0; loop_idx < _prune.loops_count; loop_idx++) {
  646. if (loops_overlap(_prune.loops[loop_idx], new_loop)) {
  647. overlapping_loops = true;
  648. overlapping_loop_length += _prune.loops[loop_idx].length_squared;
  649. }
  650. }
  651. // handle overlapping loops
  652. if (overlapping_loops) {
  653. // if adding this loop would lengthen the path, discard the new loop but return success
  654. if (overlapping_loop_length > new_loop.length_squared) {
  655. return true;
  656. }
  657. // remove overlapping loops
  658. uint16_t dest_idx = 0;
  659. uint16_t removed = 0;
  660. for (uint16_t src_idx = 0; src_idx < _prune.loops_count; src_idx++) {
  661. if (loops_overlap(_prune.loops[src_idx], new_loop)) {
  662. removed++;
  663. } else {
  664. _prune.loops[dest_idx] = _prune.loops[src_idx];
  665. dest_idx++;
  666. }
  667. }
  668. _prune.loops_count -= removed;
  669. }
  670. // add new loop to _prune.loops array
  671. _prune.loops[_prune.loops_count] = new_loop;
  672. _prune.loops_count++;
  673. return true;
  674. }
  675. /**
  676. * Returns the closest distance in 3D space between any part of two input segments, defined from p1 to p2 and from p3 to p4.
  677. * Also returns the point which is halfway between
  678. *
  679. * Limitation: This function does not work for parallel lines. In this case, dist_point.distance will be FLT_MAX.
  680. * This does not matter for the path cleanup algorithm because the pruning will still occur fine between the first
  681. * parallel segment and a segment which is directly before or after the second segment.
  682. */
  683. AP_SmartRTL::dist_point AP_SmartRTL::segment_segment_dist(const Vector3f &p1, const Vector3f &p2, const Vector3f &p3, const Vector3f &p4)
  684. {
  685. const Vector3f line1 = p2-p1;
  686. const Vector3f line2 = p4-p3;
  687. const Vector3f line_start_diff = p1-p3; // from the beginning of the second line to the beginning of the first line
  688. // these don't really have a physical representation. They're only here to break up the longer formulas below.
  689. const float a = line1*line1;
  690. const float b = line1*line2;
  691. const float c = line2*line2;
  692. const float d = line1*line_start_diff;
  693. const float e = line2*line_start_diff;
  694. // the parameter for the position on line1 and line2 which define the closest points.
  695. float t1 = 0.0f;
  696. float t2 = 0.0f;
  697. // if lines are almost parallel, return a garbage answer. This is irrelevant, since the loop
  698. // could always be pruned start/end of the previous/subsequent line segment
  699. if (is_zero((a*c)-(b*b))) {
  700. return {FLT_MAX, Vector3f(0.0f, 0.0f, 0.0f)};
  701. }
  702. t1 = (b*e-c*d)/(a*c-b*b);
  703. t2 = (a*e-b*d)/(a*c-b*b);
  704. // restrict both parameters between 0 and 1.
  705. t1 = constrain_float(t1, 0.0f, 1.0f);
  706. t2 = constrain_float(t2, 0.0f, 1.0f);
  707. // difference between two closest points
  708. const Vector3f dP = line_start_diff+line1*t1-line2*t2;
  709. const Vector3f midpoint = (p1+line1*t1 + p3+line2*t2)/2.0f;
  710. return {dP.length(), midpoint};
  711. }
  712. // de-activate SmartRTL, send warning to GCS and logger
  713. void AP_SmartRTL::deactivate(SRTL_Actions action, const char *reason)
  714. {
  715. _active = false;
  716. log_action(action);
  717. gcs().send_text(MAV_SEVERITY_WARNING, "SmartRTL deactivated: %s", reason);
  718. }
  719. // logging
  720. void AP_SmartRTL::log_action(SRTL_Actions action, const Vector3f &point)
  721. {
  722. if (!_example_mode) {
  723. AP::logger().Write_SRTL(_active, _path_points_count, _path_points_max, action, point);
  724. }
  725. }
  726. // returns true if the two loops overlap (used within add_loop to determine which loops to keep or throw away)
  727. bool AP_SmartRTL::loops_overlap(const prune_loop_t &loop1, const prune_loop_t &loop2) const
  728. {
  729. // check if loop1 within loop2
  730. if (loop1.start_index >= loop2.start_index && loop1.end_index <= loop2.end_index) {
  731. return true;
  732. }
  733. // check if loop2 within loop1
  734. if (loop2.start_index >= loop1.start_index && loop2.end_index <= loop1.end_index) {
  735. return true;
  736. }
  737. // check for partial overlap (loop1's start OR end point is within loop2)
  738. const bool loop1_start_in_loop2 = (loop1.start_index >= loop2.start_index) && (loop1.start_index <= loop2.end_index);
  739. const bool loop1_end_in_loop2 = (loop1.end_index >= loop2.start_index) && (loop1.end_index <= loop2.end_index);
  740. if (loop1_start_in_loop2 != loop1_end_in_loop2) {
  741. return true;
  742. }
  743. // if we got here, no overlap
  744. return false;
  745. }