2015-08-11 03:28:41 -03:00
|
|
|
#include "AC_Fence.h"
|
2019-02-14 02:40:09 -04:00
|
|
|
|
|
|
|
#include <AP_AHRS/AP_AHRS.h>
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2020-06-01 23:27:28 -03:00
|
|
|
#include <AP_Logger/AP_Logger.h>
|
2013-04-26 06:47:07 -03:00
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2020-03-26 21:51:14 -03:00
|
|
|
#if APM_BUILD_TYPE(APM_BUILD_Rover)
|
2018-10-26 00:29:02 -03:00
|
|
|
#define AC_FENCE_TYPE_DEFAULT AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON
|
|
|
|
#else
|
|
|
|
#define AC_FENCE_TYPE_DEFAULT AC_FENCE_TYPE_ALT_MAX | AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON
|
|
|
|
#endif
|
|
|
|
|
2015-10-25 14:03:46 -03:00
|
|
|
const AP_Param::GroupInfo AC_Fence::var_info[] = {
|
2013-04-26 06:47:07 -03:00
|
|
|
// @Param: ENABLE
|
|
|
|
// @DisplayName: Fence enable/disable
|
|
|
|
// @Description: Allows you to enable (1) or disable (0) the fence functionality
|
|
|
|
// @Values: 0:Disabled,1:Enabled
|
|
|
|
// @User: Standard
|
2016-08-30 20:54:57 -03:00
|
|
|
AP_GROUPINFO("ENABLE", 0, AC_Fence, _enabled, 0),
|
2013-04-26 06:47:07 -03:00
|
|
|
|
|
|
|
// @Param: TYPE
|
|
|
|
// @DisplayName: Fence Type
|
|
|
|
// @Description: Enabled fence types held as bitmask
|
2016-06-23 03:24:48 -03:00
|
|
|
// @Values: 0:None,1:Altitude,2:Circle,3:Altitude and Circle,4:Polygon,5:Altitude and Polygon,6:Circle and Polygon,7:All
|
|
|
|
// @Bitmask: 0:Altitude,1:Circle,2:Polygon
|
2013-04-26 06:47:07 -03:00
|
|
|
// @User: Standard
|
2018-10-26 00:29:02 -03:00
|
|
|
AP_GROUPINFO("TYPE", 1, AC_Fence, _enabled_fences, AC_FENCE_TYPE_DEFAULT),
|
2013-04-26 06:47:07 -03:00
|
|
|
|
|
|
|
// @Param: ACTION
|
2013-11-26 09:18:05 -04:00
|
|
|
// @DisplayName: Fence Action
|
|
|
|
// @Description: What action should be taken when fence is breached
|
2019-01-24 06:00:42 -04:00
|
|
|
// @Values{Copter}: 0:Report Only,1:RTL or Land,2:Always Land,3:SmartRTL or RTL or Land,4:Brake or Land
|
2020-02-01 22:44:26 -04:00
|
|
|
// @Values{Rover}: 0:Report Only,1:RTL,2:Hold,3:SmartRTL,4:SmartRTL or Hold
|
2019-01-24 06:00:42 -04:00
|
|
|
// @Values: 0:Report Only,1:RTL or Land
|
2013-04-26 06:47:07 -03:00
|
|
|
// @User: Standard
|
|
|
|
AP_GROUPINFO("ACTION", 2, AC_Fence, _action, AC_FENCE_ACTION_RTL_AND_LAND),
|
|
|
|
|
2020-06-09 20:09:53 -03:00
|
|
|
// @Param{Copter, Sub}: ALT_MAX
|
2013-04-26 06:47:07 -03:00
|
|
|
// @DisplayName: Fence Maximum Altitude
|
|
|
|
// @Description: Maximum altitude allowed before geofence triggers
|
2017-05-02 10:38:01 -03:00
|
|
|
// @Units: m
|
2013-05-01 05:05:04 -03:00
|
|
|
// @Range: 10 1000
|
|
|
|
// @Increment: 1
|
2013-04-26 06:47:07 -03:00
|
|
|
// @User: Standard
|
2017-07-17 05:39:26 -03:00
|
|
|
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),
|
2013-04-26 06:47:07 -03:00
|
|
|
|
|
|
|
// @Param: RADIUS
|
|
|
|
// @DisplayName: Circular Fence Radius
|
2013-05-01 05:05:04 -03:00
|
|
|
// @Description: Circle fence radius which when breached will cause an RTL
|
2017-05-02 10:38:01 -03:00
|
|
|
// @Units: m
|
2013-07-26 22:28:33 -03:00
|
|
|
// @Range: 30 10000
|
2013-04-26 06:47:07 -03:00
|
|
|
// @User: Standard
|
2013-05-01 05:05:04 -03:00
|
|
|
AP_GROUPINFO("RADIUS", 4, AC_Fence, _circle_radius, AC_FENCE_CIRCLE_RADIUS_DEFAULT),
|
2013-08-15 04:05:38 -03:00
|
|
|
|
|
|
|
// @Param: MARGIN
|
|
|
|
// @DisplayName: Fence Margin
|
|
|
|
// @Description: Distance that autopilot's should maintain from the fence to avoid a breach
|
2017-05-02 10:38:01 -03:00
|
|
|
// @Units: m
|
2013-08-15 04:05:38 -03:00
|
|
|
// @Range: 1 10
|
|
|
|
// @User: Standard
|
|
|
|
AP_GROUPINFO("MARGIN", 5, AC_Fence, _margin, AC_FENCE_MARGIN_DEFAULT),
|
2016-06-23 03:24:48 -03:00
|
|
|
|
|
|
|
// @Param: TOTAL
|
|
|
|
// @DisplayName: Fence polygon point total
|
|
|
|
// @Description: Number of polygon points saved in eeprom (do not update manually)
|
|
|
|
// @Range: 1 20
|
|
|
|
// @User: Standard
|
|
|
|
AP_GROUPINFO("TOTAL", 6, AC_Fence, _total, 0),
|
|
|
|
|
2017-02-03 00:18:25 -04:00
|
|
|
// @Param: ALT_MIN
|
|
|
|
// @DisplayName: Fence Minimum Altitude
|
|
|
|
// @Description: Minimum altitude allowed before geofence triggers
|
2017-05-02 10:38:01 -03:00
|
|
|
// @Units: m
|
2017-02-03 00:18:25 -04:00
|
|
|
// @Range: -100 100
|
|
|
|
// @Increment: 1
|
|
|
|
// @User: Standard
|
|
|
|
AP_GROUPINFO_FRAME("ALT_MIN", 7, AC_Fence, _alt_min, AC_FENCE_ALT_MIN_DEFAULT, AP_PARAM_FRAME_SUB),
|
|
|
|
|
2013-04-26 06:47:07 -03:00
|
|
|
AP_GROUPEND
|
|
|
|
};
|
|
|
|
|
|
|
|
/// Default constructor.
|
2019-01-30 20:37:22 -04:00
|
|
|
AC_Fence::AC_Fence()
|
2013-04-26 06:47:07 -03:00
|
|
|
{
|
2019-01-30 21:54:13 -04:00
|
|
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
|
|
|
if (_singleton != nullptr) {
|
|
|
|
AP_HAL::panic("Fence must be singleton");
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
_singleton = this;
|
2013-04-26 06:47:07 -03:00
|
|
|
AP_Param::setup_object_defaults(this, var_info);
|
|
|
|
}
|
|
|
|
|
2019-08-28 04:22:16 -03:00
|
|
|
/// enable the Fence code generally; a master switch for all fences
|
2017-07-20 13:42:28 -03:00
|
|
|
void AC_Fence::enable(bool value)
|
|
|
|
{
|
2020-06-01 23:27:28 -03:00
|
|
|
if (_enabled && !value) {
|
|
|
|
AP::logger().Write_Event(LogEvent::FENCE_DISABLE);
|
|
|
|
} else if (!_enabled && value) {
|
|
|
|
AP::logger().Write_Event(LogEvent::FENCE_ENABLE);
|
|
|
|
}
|
2017-07-20 13:42:28 -03:00
|
|
|
_enabled = value;
|
|
|
|
if (!value) {
|
|
|
|
clear_breach(AC_FENCE_TYPE_ALT_MAX | AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
2013-04-26 06:47:07 -03:00
|
|
|
/// get_enabled_fences - returns bitmask of enabled fences
|
2013-05-01 05:05:04 -03:00
|
|
|
uint8_t AC_Fence::get_enabled_fences() const
|
2013-04-26 06:47:07 -03:00
|
|
|
{
|
2013-05-01 05:05:04 -03:00
|
|
|
if (!_enabled) {
|
2017-12-15 06:06:56 -04:00
|
|
|
return 0;
|
2013-04-26 06:47:07 -03:00
|
|
|
}
|
2017-12-15 06:06:56 -04:00
|
|
|
return _enabled_fences;
|
2013-04-26 06:47:07 -03:00
|
|
|
}
|
|
|
|
|
2017-12-13 22:54:03 -04:00
|
|
|
// additional checks for the polygon fence:
|
|
|
|
bool AC_Fence::pre_arm_check_polygon(const char* &fail_msg) const
|
|
|
|
{
|
|
|
|
if (!(_enabled_fences & AC_FENCE_TYPE_POLYGON)) {
|
|
|
|
// not enabled; all good
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2019-08-28 04:22:16 -03:00
|
|
|
if (! _poly_loader.loaded()) {
|
|
|
|
fail_msg = "Fences invalid";
|
2017-12-13 22:54:03 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2020-07-21 14:00:57 -03:00
|
|
|
if (!_poly_loader.check_inclusion_circle_margin(_margin)) {
|
|
|
|
fail_msg = "Margin is less than inclusion circle radius";
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2017-12-13 22:54:03 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2017-12-26 22:53:39 -04:00
|
|
|
// additional checks for the circle fence:
|
|
|
|
bool AC_Fence::pre_arm_check_circle(const char* &fail_msg) const
|
|
|
|
{
|
|
|
|
if (_circle_radius < 0) {
|
|
|
|
fail_msg = "Invalid FENCE_RADIUS value";
|
|
|
|
return false;
|
|
|
|
}
|
2020-07-21 14:00:57 -03:00
|
|
|
if (_circle_radius < _margin) {
|
|
|
|
fail_msg = "FENCE_MARGIN is less than FENCE_RADIUS";
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2017-12-26 22:53:39 -04:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
|
|
|
// additional checks for the alt fence:
|
|
|
|
bool AC_Fence::pre_arm_check_alt(const char* &fail_msg) const
|
|
|
|
{
|
|
|
|
if (_alt_max < 0.0f) {
|
|
|
|
fail_msg = "Invalid FENCE_ALT_MAX value";
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2017-12-13 22:54:03 -04:00
|
|
|
|
2013-04-26 06:47:07 -03:00
|
|
|
/// pre_arm_check - returns true if all pre-takeoff checks have completed successfully
|
2017-03-24 01:38:19 -03:00
|
|
|
bool AC_Fence::pre_arm_check(const char* &fail_msg) const
|
2013-04-26 06:47:07 -03:00
|
|
|
{
|
2017-03-24 01:38:19 -03:00
|
|
|
fail_msg = nullptr;
|
|
|
|
|
2013-04-26 06:47:07 -03:00
|
|
|
// if not enabled or not fence set-up always return true
|
2017-12-15 06:06:56 -04:00
|
|
|
if (!_enabled || !_enabled_fences) {
|
2013-04-26 06:47:07 -03:00
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2017-12-07 19:25:52 -04:00
|
|
|
// if we have horizontal limits enabled, check we can get a
|
2019-01-30 20:37:22 -04:00
|
|
|
// relative position from the AHRS
|
2017-12-07 19:25:52 -04:00
|
|
|
if ((_enabled_fences & AC_FENCE_TYPE_CIRCLE) ||
|
|
|
|
(_enabled_fences & AC_FENCE_TYPE_POLYGON)) {
|
|
|
|
Vector2f position;
|
2019-03-05 23:04:58 -04:00
|
|
|
if (!AP::ahrs().get_relative_position_NE_home(position)) {
|
2020-07-03 20:29:45 -03:00
|
|
|
fail_msg = "Fence requires position";
|
2017-12-07 19:25:52 -04:00
|
|
|
return false;
|
|
|
|
}
|
2013-04-26 06:47:07 -03:00
|
|
|
}
|
|
|
|
|
2017-12-13 22:54:03 -04:00
|
|
|
if (!pre_arm_check_polygon(fail_msg)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2017-12-26 22:53:39 -04:00
|
|
|
if (!pre_arm_check_circle(fail_msg)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (!pre_arm_check_alt(fail_msg)) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2019-08-28 04:22:16 -03:00
|
|
|
// check no limits are currently breached
|
|
|
|
if (_breached_fences) {
|
|
|
|
fail_msg = "vehicle outside fence";
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2013-04-26 06:47:07 -03:00
|
|
|
// if we got this far everything must be ok
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2019-08-28 04:22:16 -03:00
|
|
|
/// returns true if we have freshly breached the maximum altitude
|
|
|
|
/// fence; also may set up a fallback fence which, if breached, will
|
|
|
|
/// cause the altitude fence to be freshly breached
|
2017-12-15 05:35:22 -04:00
|
|
|
bool AC_Fence::check_fence_alt_max()
|
2017-12-07 20:53:18 -04:00
|
|
|
{
|
|
|
|
// altitude fence check
|
|
|
|
if (!(_enabled_fences & AC_FENCE_TYPE_ALT_MAX)) {
|
|
|
|
// not enabled; no breach
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2019-01-30 20:37:22 -04:00
|
|
|
AP::ahrs().get_relative_position_D_home(_curr_alt);
|
2017-12-15 05:35:22 -04:00
|
|
|
_curr_alt = -_curr_alt; // translate Down to Up
|
|
|
|
|
2017-12-07 20:53:18 -04:00
|
|
|
// check if we are over the altitude fence
|
2017-12-15 05:35:22 -04:00
|
|
|
if(_curr_alt >= _alt_max) {
|
2017-12-07 20:53:18 -04:00
|
|
|
|
|
|
|
// record distance above breach
|
2017-12-15 05:35:22 -04:00
|
|
|
_alt_max_breach_distance = _curr_alt - _alt_max;
|
2017-12-07 20:53:18 -04:00
|
|
|
|
|
|
|
// check for a new breach or a breach of the backup fence
|
|
|
|
if (!(_breached_fences & AC_FENCE_TYPE_ALT_MAX) ||
|
2017-12-15 05:35:22 -04:00
|
|
|
(!is_zero(_alt_max_backup) && _curr_alt >= _alt_max_backup)) {
|
2017-12-07 20:53:18 -04:00
|
|
|
|
|
|
|
// new breach
|
|
|
|
record_breach(AC_FENCE_TYPE_ALT_MAX);
|
|
|
|
|
|
|
|
// create a backup fence 20m higher up
|
2017-12-15 05:35:22 -04:00
|
|
|
_alt_max_backup = _curr_alt + AC_FENCE_ALT_MAX_BACKUP_DISTANCE;
|
2017-12-07 20:53:18 -04:00
|
|
|
// new breach:
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
// old breach:
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// not breached
|
|
|
|
|
|
|
|
// clear alt breach if present
|
|
|
|
if ((_breached_fences & AC_FENCE_TYPE_ALT_MAX) != 0) {
|
|
|
|
clear_breach(AC_FENCE_TYPE_ALT_MAX);
|
|
|
|
_alt_max_backup = 0.0f;
|
|
|
|
_alt_max_breach_distance = 0.0f;
|
|
|
|
}
|
|
|
|
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2019-08-28 04:22:16 -03:00
|
|
|
// check_fence_polygon - returns true if the poly fence is freshly
|
|
|
|
// breached. That includes being inside exclusion zones and outside
|
|
|
|
// inclusions zones
|
2017-12-07 20:10:16 -04:00
|
|
|
bool AC_Fence::check_fence_polygon()
|
2019-03-06 00:45:00 -04:00
|
|
|
{
|
|
|
|
const bool was_breached = _breached_fences & AC_FENCE_TYPE_POLYGON;
|
2019-08-28 04:22:16 -03:00
|
|
|
const bool breached = ((_enabled_fences & AC_FENCE_TYPE_POLYGON) &&
|
|
|
|
_poly_loader.breached());
|
2019-03-06 00:45:00 -04:00
|
|
|
if (breached) {
|
|
|
|
if (!was_breached) {
|
|
|
|
record_breach(AC_FENCE_TYPE_POLYGON);
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
if (was_breached) {
|
|
|
|
clear_breach(AC_FENCE_TYPE_POLYGON);
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2019-08-28 04:22:16 -03:00
|
|
|
/// check_fence_circle - returns true if the circle fence (defined via
|
|
|
|
/// parameters) has been freshly breached. May also set up a backup
|
|
|
|
/// fence outside the fence and return a fresh breach if that backup
|
|
|
|
/// fence is breaced.
|
2017-12-07 20:18:29 -04:00
|
|
|
bool AC_Fence::check_fence_circle()
|
|
|
|
{
|
|
|
|
if (!(_enabled_fences & AC_FENCE_TYPE_CIRCLE)) {
|
|
|
|
// not enabled; no breach
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2017-12-13 23:46:48 -04:00
|
|
|
Vector2f home;
|
2019-01-30 20:37:22 -04:00
|
|
|
if (AP::ahrs().get_relative_position_NE_home(home)) {
|
2017-12-13 23:46:48 -04:00
|
|
|
// we (may) remain breached if we can't update home
|
|
|
|
_home_distance = home.length();
|
|
|
|
}
|
|
|
|
|
2017-12-07 20:18:29 -04:00
|
|
|
// check if we are outside the fence
|
|
|
|
if (_home_distance >= _circle_radius) {
|
|
|
|
|
|
|
|
// record distance outside the fence
|
|
|
|
_circle_breach_distance = _home_distance - _circle_radius;
|
|
|
|
|
|
|
|
// check for a new breach or a breach of the backup fence
|
|
|
|
if (!(_breached_fences & AC_FENCE_TYPE_CIRCLE) ||
|
|
|
|
(!is_zero(_circle_radius_backup) && _home_distance >= _circle_radius_backup)) {
|
|
|
|
// new breach
|
|
|
|
// create a backup fence 20m further out
|
|
|
|
record_breach(AC_FENCE_TYPE_CIRCLE);
|
|
|
|
_circle_radius_backup = _home_distance + AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE;
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
// not currently breached
|
|
|
|
|
|
|
|
// clear circle breach if present
|
|
|
|
if (_breached_fences & AC_FENCE_TYPE_CIRCLE) {
|
|
|
|
clear_breach(AC_FENCE_TYPE_CIRCLE);
|
|
|
|
_circle_radius_backup = 0.0f;
|
|
|
|
_circle_breach_distance = 0.0f;
|
|
|
|
}
|
|
|
|
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
2017-12-07 20:10:16 -04:00
|
|
|
|
2017-12-15 05:35:22 -04:00
|
|
|
/// check - returns bitmask of fence types breached (if any)
|
|
|
|
uint8_t AC_Fence::check()
|
2013-04-26 06:47:07 -03:00
|
|
|
{
|
2017-12-15 06:06:56 -04:00
|
|
|
uint8_t ret = 0;
|
2013-04-26 06:47:07 -03:00
|
|
|
|
|
|
|
// return immediately if disabled
|
2017-12-15 06:06:56 -04:00
|
|
|
if (!_enabled || !_enabled_fences) {
|
|
|
|
return 0;
|
2013-04-26 06:47:07 -03:00
|
|
|
}
|
|
|
|
|
2020-03-26 10:31:00 -03:00
|
|
|
// clear any breach from a non-enabled fence
|
|
|
|
clear_breach(~_enabled_fences);
|
|
|
|
|
2014-04-26 23:08:37 -03:00
|
|
|
// check if pilot is attempting to recover manually
|
|
|
|
if (_manual_recovery_start_ms != 0) {
|
|
|
|
// we ignore any fence breaches during the manual recovery period which is about 10 seconds
|
2015-11-19 23:05:31 -04:00
|
|
|
if ((AP_HAL::millis() - _manual_recovery_start_ms) < AC_FENCE_MANUAL_RECOVERY_TIME_MIN) {
|
2017-12-15 06:06:56 -04:00
|
|
|
return 0;
|
2014-04-26 23:08:37 -03:00
|
|
|
}
|
2017-12-15 06:06:56 -04:00
|
|
|
// recovery period has passed so reset manual recovery time
|
|
|
|
// and continue with fence breach checks
|
|
|
|
_manual_recovery_start_ms = 0;
|
2014-04-26 23:08:37 -03:00
|
|
|
}
|
|
|
|
|
2017-12-07 20:53:18 -04:00
|
|
|
// maximum altitude fence check
|
2017-12-15 05:35:22 -04:00
|
|
|
if (check_fence_alt_max()) {
|
2017-12-07 20:53:18 -04:00
|
|
|
ret |= AC_FENCE_TYPE_ALT_MAX;
|
2013-04-26 06:47:07 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// circle fence check
|
2017-12-07 20:18:29 -04:00
|
|
|
if (check_fence_circle()) {
|
|
|
|
ret |= AC_FENCE_TYPE_CIRCLE;
|
2013-04-26 06:47:07 -03:00
|
|
|
}
|
|
|
|
|
2016-06-23 03:24:48 -03:00
|
|
|
// polygon fence check
|
2017-12-07 20:10:16 -04:00
|
|
|
if (check_fence_polygon()) {
|
|
|
|
ret |= AC_FENCE_TYPE_POLYGON;
|
2016-06-23 03:24:48 -03:00
|
|
|
}
|
|
|
|
|
2013-04-26 06:47:07 -03:00
|
|
|
// return any new breaches that have occurred
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
|
2016-05-19 05:31:36 -03:00
|
|
|
// returns true if the destination is within fence (used to reject waypoints outside the fence)
|
2019-01-01 22:54:09 -04:00
|
|
|
bool AC_Fence::check_destination_within_fence(const Location& loc)
|
2016-04-28 04:29:35 -03:00
|
|
|
{
|
|
|
|
// Altitude fence check
|
2016-07-02 05:14:17 -03:00
|
|
|
if ((get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX)) {
|
|
|
|
int32_t alt_above_home_cm;
|
2019-03-14 22:45:12 -03:00
|
|
|
if (loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, alt_above_home_cm)) {
|
2016-07-02 05:14:17 -03:00
|
|
|
if ((alt_above_home_cm * 0.01f) > _alt_max) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
2016-04-28 04:29:35 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// Circular fence check
|
2016-07-02 05:14:17 -03:00
|
|
|
if ((get_enabled_fences() & AC_FENCE_TYPE_CIRCLE)) {
|
2019-02-24 20:12:59 -04:00
|
|
|
if (AP::ahrs().get_home().get_distance(loc) > _circle_radius) {
|
2016-07-02 05:14:17 -03:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
// polygon fence check
|
2019-05-29 10:02:04 -03:00
|
|
|
if ((get_enabled_fences() & AC_FENCE_TYPE_POLYGON)) {
|
|
|
|
if (_poly_loader.breached(loc)) {
|
|
|
|
return false;
|
2016-07-02 05:14:17 -03:00
|
|
|
}
|
2016-04-28 04:29:35 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2013-04-26 06:47:07 -03:00
|
|
|
/// record_breach - update breach bitmask, time and count
|
|
|
|
void AC_Fence::record_breach(uint8_t fence_type)
|
|
|
|
{
|
|
|
|
// if we haven't already breached a limit, update the breach time
|
2017-12-15 06:06:56 -04:00
|
|
|
if (!_breached_fences) {
|
2015-11-19 23:05:31 -04:00
|
|
|
_breach_time = AP_HAL::millis();
|
2013-04-26 06:47:07 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
// update breach count
|
2013-05-01 05:05:04 -03:00
|
|
|
if (_breach_count < 65500) {
|
2013-04-26 06:47:07 -03:00
|
|
|
_breach_count++;
|
|
|
|
}
|
|
|
|
|
|
|
|
// update bitmask
|
2013-05-01 05:05:04 -03:00
|
|
|
_breached_fences |= fence_type;
|
2013-04-26 06:47:07 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/// clear_breach - update breach bitmask, time and count
|
|
|
|
void AC_Fence::clear_breach(uint8_t fence_type)
|
|
|
|
{
|
2013-05-01 05:05:04 -03:00
|
|
|
_breached_fences &= ~fence_type;
|
|
|
|
}
|
2013-04-26 06:47:07 -03:00
|
|
|
|
2019-08-08 00:16:54 -03:00
|
|
|
/// get_breach_distance - returns maximum distance in meters outside
|
|
|
|
/// of the given fences. fence_type is a bitmask here.
|
2013-05-01 05:05:04 -03:00
|
|
|
float AC_Fence::get_breach_distance(uint8_t fence_type) const
|
|
|
|
{
|
2019-08-08 00:16:54 -03:00
|
|
|
float max = 0.0f;
|
|
|
|
if (fence_type & AC_FENCE_TYPE_ALT_MAX) {
|
|
|
|
max = MAX(_alt_max_breach_distance, max);
|
|
|
|
}
|
|
|
|
if (fence_type & AC_FENCE_TYPE_CIRCLE) {
|
|
|
|
max = MAX(_circle_breach_distance, max);
|
|
|
|
}
|
|
|
|
return max;
|
2013-07-24 11:05:21 -03:00
|
|
|
}
|
2014-04-26 23:08:37 -03:00
|
|
|
|
|
|
|
/// manual_recovery_start - caller indicates that pilot is re-taking manual control so fence should be disabled for 10 seconds
|
|
|
|
/// has no effect if no breaches have occurred
|
|
|
|
void AC_Fence::manual_recovery_start()
|
|
|
|
{
|
|
|
|
// return immediate if we haven't breached a fence
|
2017-12-15 06:06:56 -04:00
|
|
|
if (!_breached_fences) {
|
2014-04-26 23:08:37 -03:00
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
// record time pilot began manual recovery
|
2015-11-19 23:05:31 -04:00
|
|
|
_manual_recovery_start_ms = AP_HAL::millis();
|
2014-04-26 23:08:37 -03:00
|
|
|
}
|
2016-06-23 03:24:48 -03:00
|
|
|
|
2018-12-04 00:32:42 -04:00
|
|
|
// methods for mavlink SYS_STATUS message (send_sys_status)
|
2017-12-27 00:31:32 -04:00
|
|
|
bool AC_Fence::sys_status_present() const
|
2017-12-12 01:49:14 -04:00
|
|
|
{
|
|
|
|
return _enabled;
|
|
|
|
}
|
|
|
|
|
2017-12-27 00:31:32 -04:00
|
|
|
bool AC_Fence::sys_status_enabled() const
|
2017-12-12 01:49:14 -04:00
|
|
|
{
|
2017-12-27 00:31:32 -04:00
|
|
|
if (!sys_status_present()) {
|
2017-12-12 01:49:14 -04:00
|
|
|
return false;
|
|
|
|
}
|
|
|
|
if (_action == AC_FENCE_ACTION_REPORT_ONLY) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2017-12-27 00:31:32 -04:00
|
|
|
bool AC_Fence::sys_status_failed() const
|
2017-12-12 01:49:14 -04:00
|
|
|
{
|
2017-12-27 00:31:32 -04:00
|
|
|
if (!sys_status_present()) {
|
2017-12-12 01:49:14 -04:00
|
|
|
// not failed if not present; can fail if present but not enabled
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
if (get_breaches() != 0) {
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
return false;
|
|
|
|
}
|
2019-01-30 21:54:13 -04:00
|
|
|
|
2019-08-28 04:22:16 -03:00
|
|
|
AC_PolyFence_loader &AC_Fence::polyfence() {
|
|
|
|
return _poly_loader;
|
|
|
|
}
|
|
|
|
const AC_PolyFence_loader &AC_Fence::polyfence() const {
|
|
|
|
return _poly_loader;
|
|
|
|
}
|
|
|
|
|
2019-01-30 21:54:13 -04:00
|
|
|
// singleton instance
|
|
|
|
AC_Fence *AC_Fence::_singleton;
|
|
|
|
|
|
|
|
namespace AP {
|
|
|
|
|
|
|
|
AC_Fence *fence()
|
|
|
|
{
|
|
|
|
return AC_Fence::get_singleton();
|
|
|
|
}
|
|
|
|
|
|
|
|
}
|