AC_Fence.h 9.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199
  1. #pragma once
  2. #include <inttypes.h>
  3. #include <AP_Common/AP_Common.h>
  4. #include <AP_Param/AP_Param.h>
  5. #include <AP_Math/AP_Math.h>
  6. #include <GCS_MAVLink/GCS.h>
  7. #include <AC_Fence/AC_PolyFence_loader.h>
  8. #include <AP_Common/Location.h>
  9. // bit masks for enabled fence types. Used for TYPE parameter
  10. #define AC_FENCE_TYPE_ALT_MAX 1 // high alt fence which usually initiates an RTL
  11. #define AC_FENCE_TYPE_CIRCLE 2 // circular horizontal fence (usually initiates an RTL)
  12. #define AC_FENCE_TYPE_POLYGON 4 // polygon horizontal fence
  13. // valid actions should a fence be breached
  14. #define AC_FENCE_ACTION_REPORT_ONLY 0 // report to GCS that boundary has been breached but take no further action
  15. #define AC_FENCE_ACTION_RTL_AND_LAND 1 // return to launch and, if that fails, land
  16. #define AC_FENCE_ACTION_ALWAYS_LAND 2 // always land
  17. #define AC_FENCE_ACTION_SMART_RTL 3 // smartRTL, if that fails, RTL, it that still fails, land
  18. #define AC_FENCE_ACTION_BRAKE 4 // brake, if that fails, land
  19. // default boundaries
  20. #define AC_FENCE_ALT_MAX_DEFAULT 100.0f // default max altitude is 100m
  21. #define AC_FENCE_ALT_MIN_DEFAULT -10.0f // default maximum depth in meters
  22. #define AC_FENCE_CIRCLE_RADIUS_DEFAULT 300.0f // default circular fence radius is 300m
  23. #define AC_FENCE_ALT_MAX_BACKUP_DISTANCE 20.0f // after fence is broken we recreate the fence 20m further up
  24. #define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE 20.0f // after fence is broken we recreate the fence 20m further out
  25. #define AC_FENCE_MARGIN_DEFAULT 2.0f // default distance in meters that autopilot's should maintain from the fence to avoid a breach
  26. // give up distance
  27. #define AC_FENCE_GIVE_UP_DISTANCE 100.0f // distance outside the fence at which we should give up and just land. Note: this is not used by library directly but is intended to be used by the main code
  28. #define AC_FENCE_MANUAL_RECOVERY_TIME_MIN 10000 // pilot has 10seconds to recover during which time the autopilot will not attempt to re-take control
  29. class AC_Fence
  30. {
  31. public:
  32. AC_Fence();
  33. /* Do not allow copies */
  34. AC_Fence(const AC_Fence &other) = delete;
  35. AC_Fence &operator=(const AC_Fence&) = delete;
  36. /// enable - allows fence to be enabled/disabled. Note: this does not update the eeprom saved value
  37. void enable(bool value);
  38. /// enabled - returns true if fence is enabled
  39. bool enabled() const { return _enabled; }
  40. /// get_enabled_fences - returns bitmask of enabled fences
  41. uint8_t get_enabled_fences() const;
  42. /// pre_arm_check - returns true if all pre-takeoff checks have completed successfully
  43. bool pre_arm_check(const char* &fail_msg) const;
  44. ///
  45. /// methods to check we are within the boundaries and recover
  46. ///
  47. /// check - returns the fence type that has been breached (if any)
  48. uint8_t check();
  49. // returns true if the destination is within fence (used to reject waypoints outside the fence)
  50. bool check_destination_within_fence(const Location& loc);
  51. /// get_breaches - returns bit mask of the fence types that have been breached
  52. uint8_t get_breaches() const { return _breached_fences; }
  53. /// get_breach_time - returns time the fence was breached
  54. uint32_t get_breach_time() const { return _breach_time; }
  55. /// get_breach_count - returns number of times we have breached the fence
  56. uint16_t get_breach_count() const { return _breach_count; }
  57. /// get_breach_distance - returns maximum distance in meters outside
  58. /// of the given fences. fence_type is a bitmask here.
  59. float get_breach_distance(uint8_t fence_type) const;
  60. /// get_action - getter for user requested action on limit breach
  61. uint8_t get_action() const { return _action.get(); }
  62. /// get_safe_alt - returns maximum safe altitude (i.e. alt_max - margin)
  63. float get_safe_alt_max() const { return _alt_max - _margin; }
  64. /// get_safe_alt_min - returns the minimum safe altitude (i.e. alt_min - margin)
  65. float get_safe_alt_min() const { return _alt_min + _margin; }
  66. /// get_radius - returns the fence radius in meters
  67. float get_radius() const { return _circle_radius.get(); }
  68. /// get_margin - returns the fence margin in meters
  69. float get_margin() const { return _margin.get(); }
  70. /// manual_recovery_start - caller indicates that pilot is re-taking manual control so fence should be disabled for 10 seconds
  71. /// should be called whenever the pilot changes the flight mode
  72. /// has no effect if no breaches have occurred
  73. void manual_recovery_start();
  74. ///
  75. /// polygon related methods
  76. ///
  77. /// returns true if polygon fence is valid (i.e. has at least 3 sides)
  78. bool is_polygon_valid() const { return _boundary_valid; }
  79. /// returns pointer to array of polygon points and num_points is filled in with the total number
  80. /// points are offsets from EKF origin in NE frame
  81. Vector2f* get_boundary_points(uint16_t& num_points) const;
  82. /// returns true if we've breached the polygon boundary. simple passthrough to underlying _poly_loader object
  83. bool boundary_breached(const Vector2f& location, uint16_t num_points, const Vector2f* points) const;
  84. /// handler for polygon fence messages with GCS
  85. void handle_msg(GCS_MAVLINK &link, const mavlink_message_t &msg);
  86. /// return system time of last update to the boundary (allows external detection of boundary changes)
  87. uint32_t get_boundary_update_ms() const { return _boundary_update_ms; }
  88. static const struct AP_Param::GroupInfo var_info[];
  89. // methods for mavlink SYS_STATUS message (send_sys_status)
  90. bool sys_status_present() const;
  91. bool sys_status_enabled() const;
  92. bool sys_status_failed() const;
  93. // get singleton instance
  94. static AC_Fence *get_singleton() { return _singleton; }
  95. private:
  96. static AC_Fence *_singleton;
  97. /// check_fence_alt_max - true if alt fence has been newly breached
  98. bool check_fence_alt_max();
  99. /// check_fence_polygon - true if polygon fence has been newly breached
  100. bool check_fence_polygon();
  101. /// check_fence_circle - true if circle fence has been newly breached
  102. bool check_fence_circle();
  103. /// record_breach - update breach bitmask, time and count
  104. void record_breach(uint8_t fence_type);
  105. /// clear_breach - update breach bitmask, time and count
  106. void clear_breach(uint8_t fence_type);
  107. // additional checks for the different fence types:
  108. bool pre_arm_check_polygon(const char* &fail_msg) const;
  109. bool pre_arm_check_circle(const char* &fail_msg) const;
  110. bool pre_arm_check_alt(const char* &fail_msg) const;
  111. /// load polygon points stored in eeprom into boundary array and perform validation. returns true if load successfully completed
  112. bool load_polygon_from_eeprom();
  113. // returns true if we have breached the fence:
  114. bool polygon_fence_is_breached();
  115. // parameters
  116. AP_Int8 _enabled; // top level enable/disable control
  117. AP_Int8 _enabled_fences; // bit mask holding which fences are enabled
  118. AP_Int8 _action; // recovery action specified by user
  119. AP_Float _alt_max; // altitude upper limit in meters
  120. AP_Float _alt_min; // altitude lower limit in meters
  121. AP_Float _circle_radius; // circle fence radius in meters
  122. AP_Float _margin; // distance in meters that autopilot's should maintain from the fence to avoid a breach
  123. AP_Int8 _total; // number of polygon points saved in eeprom
  124. // backup fences
  125. float _alt_max_backup; // backup altitude upper limit in meters used to refire the breach if the vehicle continues to move further away
  126. float _circle_radius_backup; // backup circle fence radius in meters used to refire the breach if the vehicle continues to move further away
  127. // breach distances
  128. float _alt_max_breach_distance; // distance above the altitude max
  129. float _circle_breach_distance; // distance beyond the circular fence
  130. // other internal variables
  131. float _home_distance; // distance from home in meters (provided by main code)
  132. float _curr_alt;
  133. // breach information
  134. uint8_t _breached_fences; // bitmask holding the fence type that was breached (i.e. AC_FENCE_TYPE_ALT_MIN, AC_FENCE_TYPE_CIRCLE)
  135. uint32_t _breach_time; // time of last breach in milliseconds
  136. uint16_t _breach_count; // number of times we have breached the fence
  137. uint32_t _manual_recovery_start_ms; // system time in milliseconds that pilot re-took manual control
  138. // polygon fence variables
  139. AC_PolyFence_loader _poly_loader; // helper for loading/saving polygon points
  140. Vector2f *_boundary = nullptr; // array of boundary points. Note: point 0 is the return point
  141. uint8_t _boundary_num_points = 0; // number of points in the boundary array (should equal _total parameter after load has completed)
  142. bool _boundary_create_attempted = false; // true if we have attempted to create the boundary array
  143. bool _boundary_valid = false; // true if boundary forms a closed polygon
  144. uint32_t _boundary_update_ms; // system time of last update to the boundary
  145. };
  146. namespace AP {
  147. AC_Fence *fence();
  148. };