AP_OAPathPlanner.cpp 9.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292
  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_OAPathPlanner.h"
  14. #include <AP_Math/AP_Math.h>
  15. #include <AP_AHRS/AP_AHRS.h>
  16. #include <AC_Fence/AC_Fence.h>
  17. #include <AP_Logger/AP_Logger.h>
  18. #include "AP_OABendyRuler.h"
  19. #include "AP_OADijkstra.h"
  20. extern const AP_HAL::HAL &hal;
  21. // parameter defaults
  22. const float OA_LOOKAHEAD_DEFAULT = 15;
  23. const float OA_MARGIN_MAX_DEFAULT = 5;
  24. const int16_t OA_TIMEOUT_MS = 2000; // avoidance results over 2 seconds old are ignored
  25. const AP_Param::GroupInfo AP_OAPathPlanner::var_info[] = {
  26. // @Param: TYPE
  27. // @DisplayName: Object Avoidance Path Planning algorithm to use
  28. // @Description: Enabled/disable path planning around obstacles
  29. // @Values: 0:Disabled,1:BendyRuler,2:Dijkstra
  30. // @User: Standard
  31. AP_GROUPINFO_FLAGS("TYPE", 1, AP_OAPathPlanner, _type, OA_PATHPLAN_DISABLED, AP_PARAM_FLAG_ENABLE),
  32. // @Param: LOOKAHEAD
  33. // @DisplayName: Object Avoidance look ahead distance maximum
  34. // @Description: Object Avoidance will look this many meters ahead of vehicle
  35. // @Units: m
  36. // @Range: 1 100
  37. // @Increment: 1
  38. // @User: Standard
  39. AP_GROUPINFO("LOOKAHEAD", 2, AP_OAPathPlanner, _lookahead, OA_LOOKAHEAD_DEFAULT),
  40. // @Param: MARGIN_MAX
  41. // @DisplayName: Object Avoidance wide margin distance
  42. // @Description: Object Avoidance will ignore objects more than this many meters from vehicle
  43. // @Units: m
  44. // @Range: 0.1 100
  45. // @Increment: 1
  46. // @User: Standard
  47. AP_GROUPINFO("MARGIN_MAX", 3, AP_OAPathPlanner, _margin_max, OA_MARGIN_MAX_DEFAULT),
  48. #if !HAL_MINIMIZE_FEATURES
  49. // @Group: DB_
  50. // @Path: AP_OADatabase.cpp
  51. AP_SUBGROUPINFO(_oadatabase, "DB_", 4, AP_OAPathPlanner, AP_OADatabase),
  52. #endif
  53. AP_GROUPEND
  54. };
  55. /// Constructor
  56. AP_OAPathPlanner::AP_OAPathPlanner()
  57. {
  58. _singleton = this;
  59. AP_Param::setup_object_defaults(this, var_info);
  60. }
  61. // perform any required initialisation
  62. void AP_OAPathPlanner::init()
  63. {
  64. // run background task looking for best alternative destination
  65. switch (_type) {
  66. case OA_PATHPLAN_DISABLED:
  67. // do nothing
  68. return;
  69. case OA_PATHPLAN_BENDYRULER:
  70. if (_oabendyruler == nullptr) {
  71. _oabendyruler = new AP_OABendyRuler();
  72. }
  73. break;
  74. case OA_PATHPLAN_DIJKSTRA:
  75. if (_oadijkstra == nullptr) {
  76. _oadijkstra = new AP_OADijkstra();
  77. }
  78. break;
  79. }
  80. _oadatabase.init();
  81. start_thread();
  82. }
  83. // pre-arm checks that algorithms have been initialised successfully
  84. bool AP_OAPathPlanner::pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const
  85. {
  86. // check if initialisation has succeeded
  87. switch (_type) {
  88. case OA_PATHPLAN_DISABLED:
  89. // do nothing
  90. break;
  91. case OA_PATHPLAN_BENDYRULER:
  92. if (_oabendyruler == nullptr) {
  93. hal.util->snprintf(failure_msg, failure_msg_len, "BendyRuler OA requires reboot");
  94. return false;
  95. }
  96. break;
  97. case OA_PATHPLAN_DIJKSTRA:
  98. if (_oadijkstra == nullptr) {
  99. hal.util->snprintf(failure_msg, failure_msg_len, "Dijkstra OA requires reboot");
  100. return false;
  101. }
  102. break;
  103. }
  104. return true;
  105. }
  106. bool AP_OAPathPlanner::start_thread()
  107. {
  108. WITH_SEMAPHORE(_rsem);
  109. if (_thread_created) {
  110. return true;
  111. }
  112. if (_type == OA_PATHPLAN_DISABLED) {
  113. return false;
  114. }
  115. // create the avoidance thread as low priority. It should soak
  116. // up spare CPU cycles to fill in the avoidance_result structure based
  117. // on requests in avoidance_request
  118. if (!hal.scheduler->thread_create(FUNCTOR_BIND_MEMBER(&AP_OAPathPlanner::avoidance_thread, void),
  119. "avoidance",
  120. 8192, AP_HAL::Scheduler::PRIORITY_IO, -1)) {
  121. return false;
  122. }
  123. _thread_created = true;
  124. return true;
  125. }
  126. // provides an alternative target location if path planning around obstacles is required
  127. // returns true and updates result_loc with an intermediate location
  128. AP_OAPathPlanner::OA_RetState AP_OAPathPlanner::mission_avoidance(const Location &current_loc,
  129. const Location &origin,
  130. const Location &destination,
  131. Location &result_origin,
  132. Location &result_destination)
  133. {
  134. // exit immediately if disabled or thread is not running from a failed init
  135. if (_type == OA_PATHPLAN_DISABLED || !_thread_created) {
  136. return OA_NOT_REQUIRED;
  137. }
  138. const uint32_t now = AP_HAL::millis();
  139. WITH_SEMAPHORE(_rsem);
  140. // place new request for the thread to work on
  141. avoidance_request.current_loc = current_loc;
  142. avoidance_request.origin = origin;
  143. avoidance_request.destination = destination;
  144. avoidance_request.ground_speed_vec = AP::ahrs().groundspeed_vector();
  145. avoidance_request.request_time_ms = now;
  146. // check result's destination matches our request
  147. const bool destination_matches = (destination.lat == avoidance_result.destination.lat) && (destination.lng == avoidance_result.destination.lng);
  148. // check results have not timed out
  149. const bool timed_out = now - avoidance_result.result_time_ms > OA_TIMEOUT_MS;
  150. // return results from background thread's latest checks
  151. if (destination_matches && !timed_out) {
  152. // we have a result from the thread
  153. result_origin = avoidance_result.origin_new;
  154. result_destination = avoidance_result.destination_new;
  155. return avoidance_result.ret_state;
  156. }
  157. // if timeout then path planner is taking too long to respond
  158. if (timed_out) {
  159. return OA_ERROR;
  160. }
  161. // background thread is working on a new destination
  162. return OA_PROCESSING;
  163. }
  164. // avoidance thread that continually updates the avoidance_result structure based on avoidance_request
  165. void AP_OAPathPlanner::avoidance_thread()
  166. {
  167. while (true) {
  168. #if !HAL_MINIMIZE_FEATURES
  169. // if database queue needs attention, service it faster
  170. if (_oadatabase.process_queue()) {
  171. hal.scheduler->delay(1);
  172. } else {
  173. hal.scheduler->delay(20);
  174. }
  175. const uint32_t now = AP_HAL::millis();
  176. if (now - avoidance_latest_ms < 100) {
  177. continue;
  178. }
  179. avoidance_latest_ms = now;
  180. _oadatabase.update();
  181. #else
  182. hal.scheduler->delay(100);
  183. const uint32_t now = AP_HAL::millis();
  184. #endif
  185. Location origin_new;
  186. Location destination_new;
  187. {
  188. WITH_SEMAPHORE(_rsem);
  189. if (now - avoidance_request.request_time_ms > OA_TIMEOUT_MS) {
  190. // this is a very old request, don't process it
  191. continue;
  192. }
  193. // copy request to avoid conflict with main thread
  194. avoidance_request2 = avoidance_request;
  195. // store passed in origin and destination so we can return it if object avoidance is not required
  196. origin_new = avoidance_request.origin;
  197. destination_new = avoidance_request.destination;
  198. }
  199. // run background task looking for best alternative destination
  200. OA_RetState res = OA_NOT_REQUIRED;
  201. switch (_type) {
  202. case OA_PATHPLAN_DISABLED:
  203. continue;
  204. case OA_PATHPLAN_BENDYRULER:
  205. if (_oabendyruler == nullptr) {
  206. continue;
  207. }
  208. _oabendyruler->set_config(_lookahead, _margin_max);
  209. if (_oabendyruler->update(avoidance_request2.current_loc, avoidance_request2.destination, avoidance_request2.ground_speed_vec, origin_new, destination_new)) {
  210. res = OA_SUCCESS;
  211. }
  212. break;
  213. case OA_PATHPLAN_DIJKSTRA:
  214. if (_oadijkstra == nullptr) {
  215. continue;
  216. }
  217. _oadijkstra->set_fence_margin(_margin_max);
  218. const AP_OADijkstra::AP_OADijkstra_State dijkstra_state = _oadijkstra->update(avoidance_request2.current_loc, avoidance_request2.destination, origin_new, destination_new);
  219. switch (dijkstra_state) {
  220. case AP_OADijkstra::DIJKSTRA_STATE_NOT_REQUIRED:
  221. res = OA_NOT_REQUIRED;
  222. break;
  223. case AP_OADijkstra::DIJKSTRA_STATE_ERROR:
  224. res = OA_ERROR;
  225. break;
  226. case AP_OADijkstra::DIJKSTRA_STATE_SUCCESS:
  227. res = OA_SUCCESS;
  228. break;
  229. }
  230. break;
  231. }
  232. {
  233. // give the main thread the avoidance result
  234. WITH_SEMAPHORE(_rsem);
  235. avoidance_result.destination = avoidance_request2.destination;
  236. avoidance_result.origin_new = (res == OA_SUCCESS) ? origin_new : avoidance_result.origin_new;
  237. avoidance_result.destination_new = (res == OA_SUCCESS) ? destination_new : avoidance_result.destination;
  238. avoidance_result.result_time_ms = AP_HAL::millis();
  239. avoidance_result.ret_state = res;
  240. }
  241. }
  242. }
  243. // singleton instance
  244. AP_OAPathPlanner *AP_OAPathPlanner::_singleton;
  245. namespace AP {
  246. AP_OAPathPlanner *ap_oapathplanner()
  247. {
  248. return AP_OAPathPlanner::get_singleton();
  249. }
  250. }