AC_Fence.cpp 18 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632
  1. #include "AC_Fence.h"
  2. #include <AP_AHRS/AP_AHRS.h>
  3. #include <AP_HAL/AP_HAL.h>
  4. extern const AP_HAL::HAL& hal;
  5. #if APM_BUILD_TYPE(APM_BUILD_APMrover2)
  6. #define AC_FENCE_TYPE_DEFAULT AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON
  7. #else
  8. #define AC_FENCE_TYPE_DEFAULT AC_FENCE_TYPE_ALT_MAX | AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON
  9. #endif
  10. const AP_Param::GroupInfo AC_Fence::var_info[] = {
  11. // @Param: ENABLE
  12. // @DisplayName: Fence enable/disable
  13. // @Description: Allows you to enable (1) or disable (0) the fence functionality
  14. // @Values: 0:Disabled,1:Enabled
  15. // @User: Standard
  16. AP_GROUPINFO("ENABLE", 0, AC_Fence, _enabled, 0),
  17. // @Param: TYPE
  18. // @DisplayName: Fence Type
  19. // @Description: Enabled fence types held as bitmask
  20. // @Values: 0:None,1:Altitude,2:Circle,3:Altitude and Circle,4:Polygon,5:Altitude and Polygon,6:Circle and Polygon,7:All
  21. // @Bitmask: 0:Altitude,1:Circle,2:Polygon
  22. // @User: Standard
  23. AP_GROUPINFO("TYPE", 1, AC_Fence, _enabled_fences, AC_FENCE_TYPE_DEFAULT),
  24. // @Param: ACTION
  25. // @DisplayName: Fence Action
  26. // @Description: What action should be taken when fence is breached
  27. // @Values{Copter}: 0:Report Only,1:RTL or Land,2:Always Land,3:SmartRTL or RTL or Land,4:Brake or Land
  28. // @Values: 0:Report Only,1:RTL or Land
  29. // @User: Standard
  30. AP_GROUPINFO("ACTION", 2, AC_Fence, _action, AC_FENCE_ACTION_RTL_AND_LAND),
  31. // @Param: ALT_MAX
  32. // @DisplayName: Fence Maximum Altitude
  33. // @Description: Maximum altitude allowed before geofence triggers
  34. // @Units: m
  35. // @Range: 10 1000
  36. // @Increment: 1
  37. // @User: Standard
  38. AP_GROUPINFO_FRAME("ALT_MAX", 3, AC_Fence, _alt_max, AC_FENCE_ALT_MAX_DEFAULT, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_SUB | AP_PARAM_FRAME_TRICOPTER | AP_PARAM_FRAME_HELI),
  39. // @Param: RADIUS
  40. // @DisplayName: Circular Fence Radius
  41. // @Description: Circle fence radius which when breached will cause an RTL
  42. // @Units: m
  43. // @Range: 30 10000
  44. // @User: Standard
  45. AP_GROUPINFO("RADIUS", 4, AC_Fence, _circle_radius, AC_FENCE_CIRCLE_RADIUS_DEFAULT),
  46. // @Param: MARGIN
  47. // @DisplayName: Fence Margin
  48. // @Description: Distance that autopilot's should maintain from the fence to avoid a breach
  49. // @Units: m
  50. // @Range: 1 10
  51. // @User: Standard
  52. AP_GROUPINFO("MARGIN", 5, AC_Fence, _margin, AC_FENCE_MARGIN_DEFAULT),
  53. // @Param: TOTAL
  54. // @DisplayName: Fence polygon point total
  55. // @Description: Number of polygon points saved in eeprom (do not update manually)
  56. // @Range: 1 20
  57. // @User: Standard
  58. AP_GROUPINFO("TOTAL", 6, AC_Fence, _total, 0),
  59. // @Param: ALT_MIN
  60. // @DisplayName: Fence Minimum Altitude
  61. // @Description: Minimum altitude allowed before geofence triggers
  62. // @Units: m
  63. // @Range: -100 100
  64. // @Increment: 1
  65. // @User: Standard
  66. AP_GROUPINFO_FRAME("ALT_MIN", 7, AC_Fence, _alt_min, AC_FENCE_ALT_MIN_DEFAULT, AP_PARAM_FRAME_SUB),
  67. AP_GROUPEND
  68. };
  69. /// Default constructor.
  70. AC_Fence::AC_Fence()
  71. {
  72. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  73. if (_singleton != nullptr) {
  74. AP_HAL::panic("Fence must be singleton");
  75. }
  76. #endif
  77. _singleton = this;
  78. AP_Param::setup_object_defaults(this, var_info);
  79. }
  80. void AC_Fence::enable(bool value)
  81. {
  82. _enabled = value;
  83. if (!value) {
  84. clear_breach(AC_FENCE_TYPE_ALT_MAX | AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON);
  85. }
  86. }
  87. /// get_enabled_fences - returns bitmask of enabled fences
  88. uint8_t AC_Fence::get_enabled_fences() const
  89. {
  90. if (!_enabled) {
  91. return 0;
  92. }
  93. return _enabled_fences;
  94. }
  95. // additional checks for the polygon fence:
  96. bool AC_Fence::pre_arm_check_polygon(const char* &fail_msg) const
  97. {
  98. if (!(_enabled_fences & AC_FENCE_TYPE_POLYGON)) {
  99. // not enabled; all good
  100. return true;
  101. }
  102. if (!_boundary_valid) {
  103. fail_msg = "Polygon boundary invalid";
  104. return false;
  105. }
  106. return true;
  107. }
  108. // additional checks for the circle fence:
  109. bool AC_Fence::pre_arm_check_circle(const char* &fail_msg) const
  110. {
  111. if (_circle_radius < 0) {
  112. fail_msg = "Invalid FENCE_RADIUS value";
  113. return false;
  114. }
  115. return true;
  116. }
  117. // additional checks for the alt fence:
  118. bool AC_Fence::pre_arm_check_alt(const char* &fail_msg) const
  119. {
  120. if (_alt_max < 0.0f) {
  121. fail_msg = "Invalid FENCE_ALT_MAX value";
  122. return false;
  123. }
  124. return true;
  125. }
  126. /// pre_arm_check - returns true if all pre-takeoff checks have completed successfully
  127. bool AC_Fence::pre_arm_check(const char* &fail_msg) const
  128. {
  129. fail_msg = nullptr;
  130. // if not enabled or not fence set-up always return true
  131. if (!_enabled || !_enabled_fences) {
  132. return true;
  133. }
  134. // check no limits are currently breached
  135. if (_breached_fences) {
  136. fail_msg = "vehicle outside fence";
  137. return false;
  138. }
  139. // if we have horizontal limits enabled, check we can get a
  140. // relative position from the AHRS
  141. if ((_enabled_fences & AC_FENCE_TYPE_CIRCLE) ||
  142. (_enabled_fences & AC_FENCE_TYPE_POLYGON)) {
  143. Vector2f position;
  144. if (!AP::ahrs().get_relative_position_NE_home(position)) {
  145. fail_msg = "fence requires position";
  146. return false;
  147. }
  148. }
  149. if (!pre_arm_check_polygon(fail_msg)) {
  150. return false;
  151. }
  152. if (!pre_arm_check_circle(fail_msg)) {
  153. return false;
  154. }
  155. if (!pre_arm_check_alt(fail_msg)) {
  156. return false;
  157. }
  158. // if we got this far everything must be ok
  159. return true;
  160. }
  161. bool AC_Fence::check_fence_alt_max()
  162. {
  163. // altitude fence check
  164. if (!(_enabled_fences & AC_FENCE_TYPE_ALT_MAX)) {
  165. // not enabled; no breach
  166. return false;
  167. }
  168. AP::ahrs().get_relative_position_D_home(_curr_alt);
  169. _curr_alt = -_curr_alt; // translate Down to Up
  170. // check if we are over the altitude fence
  171. if(_curr_alt >= _alt_max) {
  172. // record distance above breach
  173. _alt_max_breach_distance = _curr_alt - _alt_max;
  174. // check for a new breach or a breach of the backup fence
  175. if (!(_breached_fences & AC_FENCE_TYPE_ALT_MAX) ||
  176. (!is_zero(_alt_max_backup) && _curr_alt >= _alt_max_backup)) {
  177. // new breach
  178. record_breach(AC_FENCE_TYPE_ALT_MAX);
  179. // create a backup fence 20m higher up
  180. _alt_max_backup = _curr_alt + AC_FENCE_ALT_MAX_BACKUP_DISTANCE;
  181. // new breach:
  182. return true;
  183. }
  184. // old breach:
  185. return false;
  186. }
  187. // not breached
  188. // clear alt breach if present
  189. if ((_breached_fences & AC_FENCE_TYPE_ALT_MAX) != 0) {
  190. clear_breach(AC_FENCE_TYPE_ALT_MAX);
  191. _alt_max_backup = 0.0f;
  192. _alt_max_breach_distance = 0.0f;
  193. }
  194. return false;
  195. }
  196. // check_fence_polygon - returns true if the polygon fence is freshly breached
  197. bool AC_Fence::check_fence_polygon()
  198. {
  199. const bool was_breached = _breached_fences & AC_FENCE_TYPE_POLYGON;
  200. const bool breached = polygon_fence_is_breached();
  201. if (breached) {
  202. if (!was_breached) {
  203. record_breach(AC_FENCE_TYPE_POLYGON);
  204. return true;
  205. }
  206. return false;
  207. }
  208. if (was_breached) {
  209. clear_breach(AC_FENCE_TYPE_POLYGON);
  210. }
  211. return false;
  212. }
  213. bool AC_Fence::polygon_fence_is_breached()
  214. {
  215. if (!(_enabled_fences & AC_FENCE_TYPE_POLYGON)) {
  216. // not enabled; no breach
  217. return false;
  218. }
  219. // check consistency of number of points
  220. if (_boundary_num_points != _total) {
  221. // Fence is currently not completely loaded. Can't breach it?!
  222. load_polygon_from_eeprom();
  223. return false;
  224. }
  225. if (!_boundary_valid) {
  226. // fence isn't valid - can't breach it?!
  227. return false;
  228. }
  229. // check if vehicle is outside the polygon fence
  230. Vector2f position;
  231. if (!AP::ahrs().get_relative_position_NE_origin(position)) {
  232. // we have no idea where we are; can't breach the fence
  233. return false;
  234. }
  235. position = position * 100.0f; // m to cm
  236. return _poly_loader.boundary_breached(position, _boundary_num_points, _boundary);
  237. }
  238. bool AC_Fence::check_fence_circle()
  239. {
  240. if (!(_enabled_fences & AC_FENCE_TYPE_CIRCLE)) {
  241. // not enabled; no breach
  242. return false;
  243. }
  244. Vector2f home;
  245. if (AP::ahrs().get_relative_position_NE_home(home)) {
  246. // we (may) remain breached if we can't update home
  247. _home_distance = home.length();
  248. }
  249. // check if we are outside the fence
  250. if (_home_distance >= _circle_radius) {
  251. // record distance outside the fence
  252. _circle_breach_distance = _home_distance - _circle_radius;
  253. // check for a new breach or a breach of the backup fence
  254. if (!(_breached_fences & AC_FENCE_TYPE_CIRCLE) ||
  255. (!is_zero(_circle_radius_backup) && _home_distance >= _circle_radius_backup)) {
  256. // new breach
  257. // create a backup fence 20m further out
  258. record_breach(AC_FENCE_TYPE_CIRCLE);
  259. _circle_radius_backup = _home_distance + AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE;
  260. return true;
  261. }
  262. return false;
  263. }
  264. // not currently breached
  265. // clear circle breach if present
  266. if (_breached_fences & AC_FENCE_TYPE_CIRCLE) {
  267. clear_breach(AC_FENCE_TYPE_CIRCLE);
  268. _circle_radius_backup = 0.0f;
  269. _circle_breach_distance = 0.0f;
  270. }
  271. return false;
  272. }
  273. /// check - returns bitmask of fence types breached (if any)
  274. uint8_t AC_Fence::check()
  275. {
  276. uint8_t ret = 0;
  277. // return immediately if disabled
  278. if (!_enabled || !_enabled_fences) {
  279. return 0;
  280. }
  281. // check if pilot is attempting to recover manually
  282. if (_manual_recovery_start_ms != 0) {
  283. // we ignore any fence breaches during the manual recovery period which is about 10 seconds
  284. if ((AP_HAL::millis() - _manual_recovery_start_ms) < AC_FENCE_MANUAL_RECOVERY_TIME_MIN) {
  285. return 0;
  286. }
  287. // recovery period has passed so reset manual recovery time
  288. // and continue with fence breach checks
  289. _manual_recovery_start_ms = 0;
  290. }
  291. // maximum altitude fence check
  292. if (check_fence_alt_max()) {
  293. ret |= AC_FENCE_TYPE_ALT_MAX;
  294. }
  295. // circle fence check
  296. if (check_fence_circle()) {
  297. ret |= AC_FENCE_TYPE_CIRCLE;
  298. }
  299. // polygon fence check
  300. if (check_fence_polygon()) {
  301. ret |= AC_FENCE_TYPE_POLYGON;
  302. }
  303. // return any new breaches that have occurred
  304. return ret;
  305. }
  306. // returns true if the destination is within fence (used to reject waypoints outside the fence)
  307. bool AC_Fence::check_destination_within_fence(const Location& loc)
  308. {
  309. // Altitude fence check
  310. if ((get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX)) {
  311. int32_t alt_above_home_cm;
  312. if (loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, alt_above_home_cm)) {
  313. if ((alt_above_home_cm * 0.01f) > _alt_max) {
  314. return false;
  315. }
  316. }
  317. }
  318. // Circular fence check
  319. if ((get_enabled_fences() & AC_FENCE_TYPE_CIRCLE)) {
  320. if (AP::ahrs().get_home().get_distance(loc) > _circle_radius) {
  321. return false;
  322. }
  323. }
  324. // polygon fence check
  325. if ((get_enabled_fences() & AC_FENCE_TYPE_POLYGON) && _boundary_num_points > 0) {
  326. // check ekf has a good location
  327. Vector2f posNE;
  328. if (loc.get_vector_xy_from_origin_NE(posNE)) {
  329. if (_poly_loader.boundary_breached(posNE, _boundary_num_points, _boundary)) {
  330. return false;
  331. }
  332. }
  333. }
  334. return true;
  335. }
  336. /// record_breach - update breach bitmask, time and count
  337. void AC_Fence::record_breach(uint8_t fence_type)
  338. {
  339. // if we haven't already breached a limit, update the breach time
  340. if (!_breached_fences) {
  341. _breach_time = AP_HAL::millis();
  342. }
  343. // update breach count
  344. if (_breach_count < 65500) {
  345. _breach_count++;
  346. }
  347. // update bitmask
  348. _breached_fences |= fence_type;
  349. }
  350. /// clear_breach - update breach bitmask, time and count
  351. void AC_Fence::clear_breach(uint8_t fence_type)
  352. {
  353. _breached_fences &= ~fence_type;
  354. }
  355. /// get_breach_distance - returns maximum distance in meters outside
  356. /// of the given fences. fence_type is a bitmask here.
  357. float AC_Fence::get_breach_distance(uint8_t fence_type) const
  358. {
  359. float max = 0.0f;
  360. if (fence_type & AC_FENCE_TYPE_ALT_MAX) {
  361. max = MAX(_alt_max_breach_distance, max);
  362. }
  363. if (fence_type & AC_FENCE_TYPE_CIRCLE) {
  364. max = MAX(_circle_breach_distance, max);
  365. }
  366. return max;
  367. }
  368. /// manual_recovery_start - caller indicates that pilot is re-taking manual control so fence should be disabled for 10 seconds
  369. /// has no effect if no breaches have occurred
  370. void AC_Fence::manual_recovery_start()
  371. {
  372. // return immediate if we haven't breached a fence
  373. if (!_breached_fences) {
  374. return;
  375. }
  376. // record time pilot began manual recovery
  377. _manual_recovery_start_ms = AP_HAL::millis();
  378. }
  379. /// returns pointer to array of polygon points and num_points is filled in with the total number
  380. Vector2f* AC_Fence::get_boundary_points(uint16_t& num_points) const
  381. {
  382. // return array minus the first point which holds the return location
  383. if (_boundary == nullptr) {
  384. return nullptr;
  385. }
  386. if (!_boundary_valid) {
  387. return nullptr;
  388. }
  389. // minus one for return point, minus one for closing point
  390. // (_boundary_valid is not true unless we have a closing point AND
  391. // we have a minumum number of points)
  392. if (_boundary_num_points < 2) {
  393. return nullptr;
  394. }
  395. num_points = _boundary_num_points - 2;
  396. return &_boundary[1];
  397. }
  398. /// returns true if we've breached the polygon boundary. simple passthrough to underlying _poly_loader object
  399. bool AC_Fence::boundary_breached(const Vector2f& location, uint16_t num_points, const Vector2f* points) const
  400. {
  401. return _poly_loader.boundary_breached(location, num_points, points);
  402. }
  403. /// handler for polygon fence messages with GCS
  404. void AC_Fence::handle_msg(GCS_MAVLINK &link, const mavlink_message_t &msg)
  405. {
  406. switch (msg.msgid) {
  407. // receive a fence point from GCS and store in EEPROM
  408. case MAVLINK_MSG_ID_FENCE_POINT: {
  409. mavlink_fence_point_t packet;
  410. mavlink_msg_fence_point_decode(&msg, &packet);
  411. if (!check_latlng(packet.lat,packet.lng)) {
  412. link.send_text(MAV_SEVERITY_WARNING, "Invalid fence point, lat or lng too large");
  413. } else {
  414. Vector2l point;
  415. point.x = packet.lat*1.0e7f;
  416. point.y = packet.lng*1.0e7f;
  417. if (!_poly_loader.save_point_to_eeprom(packet.idx, point)) {
  418. link.send_text(MAV_SEVERITY_WARNING, "Failed to save polygon point, too many points?");
  419. } else {
  420. // trigger reload of points
  421. _boundary_num_points = 0;
  422. }
  423. }
  424. break;
  425. }
  426. // send a fence point to GCS
  427. case MAVLINK_MSG_ID_FENCE_FETCH_POINT: {
  428. mavlink_fence_fetch_point_t packet;
  429. mavlink_msg_fence_fetch_point_decode(&msg, &packet);
  430. // attempt to retrieve from eeprom
  431. Vector2l point;
  432. if (_poly_loader.load_point_from_eeprom(packet.idx, point)) {
  433. mavlink_msg_fence_point_send(link.get_chan(), msg.sysid, msg.compid, packet.idx, _total, point.x*1.0e-7f, point.y*1.0e-7f);
  434. } else {
  435. link.send_text(MAV_SEVERITY_WARNING, "Bad fence point");
  436. }
  437. break;
  438. }
  439. default:
  440. // do nothing
  441. break;
  442. }
  443. }
  444. /// load polygon points stored in eeprom into boundary array and perform validation
  445. bool AC_Fence::load_polygon_from_eeprom()
  446. {
  447. // check if we need to create array
  448. if (!_boundary_create_attempted) {
  449. _boundary = (Vector2f *)_poly_loader.create_point_array(sizeof(Vector2f));
  450. _boundary_create_attempted = true;
  451. }
  452. // exit if we could not allocate RAM for the boundary
  453. if (_boundary == nullptr) {
  454. return false;
  455. }
  456. // get current location from EKF
  457. Location temp_loc;
  458. if (!AP::ahrs_navekf().get_location(temp_loc)) {
  459. return false;
  460. }
  461. struct Location ekf_origin {};
  462. if (!AP::ahrs().get_origin(ekf_origin)) {
  463. return false;
  464. }
  465. // sanity check total
  466. _total = constrain_int16(_total, 0, _poly_loader.max_points());
  467. // load each point from eeprom
  468. Vector2l temp_latlon;
  469. for (uint16_t index=0; index<_total; index++) {
  470. // load boundary point as lat/lon point
  471. if (!_poly_loader.load_point_from_eeprom(index, temp_latlon)) {
  472. return false;
  473. }
  474. // move into location structure and convert to offset from ekf origin
  475. temp_loc.lat = temp_latlon.x;
  476. temp_loc.lng = temp_latlon.y;
  477. _boundary[index] = ekf_origin.get_distance_NE(temp_loc) * 100.0f;
  478. }
  479. _boundary_num_points = _total;
  480. _boundary_update_ms = AP_HAL::millis();
  481. // update validity of polygon
  482. _boundary_valid = _poly_loader.boundary_valid(_boundary_num_points, _boundary);
  483. return true;
  484. }
  485. // methods for mavlink SYS_STATUS message (send_sys_status)
  486. bool AC_Fence::sys_status_present() const
  487. {
  488. return _enabled;
  489. }
  490. bool AC_Fence::sys_status_enabled() const
  491. {
  492. if (!sys_status_present()) {
  493. return false;
  494. }
  495. if (_action == AC_FENCE_ACTION_REPORT_ONLY) {
  496. return false;
  497. }
  498. return true;
  499. }
  500. bool AC_Fence::sys_status_failed() const
  501. {
  502. if (!sys_status_present()) {
  503. // not failed if not present; can fail if present but not enabled
  504. return false;
  505. }
  506. if (get_breaches() != 0) {
  507. return true;
  508. }
  509. if (_enabled_fences & AC_FENCE_TYPE_POLYGON) {
  510. if (!_boundary_valid) {
  511. return true;
  512. }
  513. }
  514. if (_enabled_fences & AC_FENCE_TYPE_CIRCLE) {
  515. if (_circle_radius < 0) {
  516. return true;
  517. }
  518. }
  519. if (_enabled_fences & AC_FENCE_TYPE_ALT_MAX) {
  520. if (_alt_max < 0.0f) {
  521. return true;
  522. }
  523. }
  524. if ((_enabled_fences & AC_FENCE_TYPE_CIRCLE) ||
  525. (_enabled_fences & AC_FENCE_TYPE_POLYGON)) {
  526. Vector2f position;
  527. if (!AP::ahrs().get_relative_position_NE_home(position)) {
  528. // both these fence types require position
  529. return true;
  530. }
  531. }
  532. return false;
  533. }
  534. // singleton instance
  535. AC_Fence *AC_Fence::_singleton;
  536. namespace AP {
  537. AC_Fence *fence()
  538. {
  539. return AC_Fence::get_singleton();
  540. }
  541. }