#include "AC_Fence.h"
#if AP_FENCE_ENABLED
#include <AP_Vehicle/AP_Vehicle_Type.h>
#ifndef AC_FENCE_DUMMY_METHODS_ENABLED
#define AC_FENCE_DUMMY_METHODS_ENABLED (!(APM_BUILD_TYPE(APM_BUILD_Rover) | APM_BUILD_COPTER_OR_HELI | APM_BUILD_TYPE(APM_BUILD_ArduPlane) | APM_BUILD_TYPE(APM_BUILD_ArduSub) | (AP_FENCE_ENABLED == 1)))
#endif
#if !AC_FENCE_DUMMY_METHODS_ENABLED
#include <AP_AHRS/AP_AHRS.h>
#include <AP_HAL/AP_HAL.h>
#include <AP_Logger/AP_Logger.h>
#include <GCS_MAVLink/GCS.h>
extern const AP_HAL::HAL& hal;
#if APM_BUILD_TYPE(APM_BUILD_Rover)
#define AC_FENCE_TYPE_DEFAULT AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON
#elif APM_BUILD_TYPE(APM_BUILD_ArduPlane)
#define AC_FENCE_TYPE_DEFAULT AC_FENCE_TYPE_POLYGON
#else
#define AC_FENCE_TYPE_DEFAULT AC_FENCE_TYPE_ALT_MAX | AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_POLYGON
#endif
#define AC_FENCE_ALT_MAX_DEFAULT 100.0f
#define AC_FENCE_ALT_MIN_DEFAULT -10.0f
#define AC_FENCE_CIRCLE_RADIUS_DEFAULT 300.0f
#define AC_FENCE_ALT_MAX_BACKUP_DISTANCE 20.0f
#define AC_FENCE_ALT_MIN_BACKUP_DISTANCE 20.0f
#define AC_FENCE_MARGIN_DEFAULT 2.0f
#define AC_FENCE_MANUAL_RECOVERY_TIME_MIN 10000
#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
#define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE 100.0
#define AC_FENCE_OPTIONS_DEFAULT OPTIONS::DISABLE_MODE_CHANGE
#else
#define AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE 20.0
#define AC_FENCE_OPTIONS_DEFAULT 0
#endif
#define AC_FENCE_NOTIFY_DEFAULT 1.0f
const AP_Param::GroupInfo AC_Fence::var_info[] = {
AP_GROUPINFO("ENABLE", 0, AC_Fence, _enabled, 0),
AP_GROUPINFO("TYPE", 1, AC_Fence, _configured_fences, AC_FENCE_TYPE_DEFAULT),
AP_GROUPINFO("ACTION", 2, AC_Fence, _action, float(Action::RTL_AND_LAND)),
AP_GROUPINFO_FRAME("ALT_MAX", 3, AC_Fence, _alt_max_m, AC_FENCE_ALT_MAX_DEFAULT, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_SUB | AP_PARAM_FRAME_TRICOPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_PLANE),
AP_GROUPINFO("RADIUS", 4, AC_Fence, _circle_radius_m, AC_FENCE_CIRCLE_RADIUS_DEFAULT),
AP_GROUPINFO("MARGIN", 5, AC_Fence, _margin_m, AC_FENCE_MARGIN_DEFAULT),
AP_GROUPINFO("TOTAL", 6, AC_Fence, _total, 0),
AP_GROUPINFO_FRAME("ALT_MIN", 7, AC_Fence, _alt_min_m, AC_FENCE_ALT_MIN_DEFAULT, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_SUB | AP_PARAM_FRAME_TRICOPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_PLANE),
AP_GROUPINFO_FRAME("RET_RALLY", 8, AC_Fence, _ret_rally, 0, AP_PARAM_FRAME_PLANE),
AP_GROUPINFO_FRAME("RET_ALT", 9, AC_Fence, _ret_altitude, 0.0f, AP_PARAM_FRAME_PLANE),
AP_GROUPINFO_FRAME("AUTOENABLE", 10, AC_Fence, _auto_enabled, static_cast<uint8_t>(AutoEnable::ALWAYS_DISABLED), AP_PARAM_FRAME_PLANE | AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_TRICOPTER | AP_PARAM_FRAME_HELI),
AP_GROUPINFO("OPTIONS", 11, AC_Fence, _options, static_cast<uint16_t>(AC_FENCE_OPTIONS_DEFAULT)),
AP_GROUPINFO("NTF_FREQ", 12, AC_Fence, _notify_freq, static_cast<float>(AC_FENCE_NOTIFY_DEFAULT)),
AP_GROUPINFO("MARGIN_XY", 13, AC_Fence, _margin_ne_m, 0),
AP_GROUPEND
};
AC_Fence::AC_Fence()
{
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
if (_singleton != nullptr) {
AP_HAL::panic("Fence must be singleton");
}
#endif
_singleton = this;
AP_Param::setup_object_defaults(this, var_info);
if (_enabled) {
_enabled_fences = _configured_fences.get() & ~AC_FENCE_TYPE_ALT_MIN;
}
}
void AC_Fence::get_fence_names(uint8_t fences, ExpandingString& msg)
{
if (!fences) {
return;
}
static const char* FENCE_NAMES[] = {
"Max Alt",
"Circle",
"Polygon",
"Min Alt",
};
uint8_t i = 0;
uint8_t nfences = 0;
while (fences !=0) {
if (fences & 0x1) {
if (nfences > 0) {
if (!(fences & ~1U)) {
msg.printf(" and ");
} else {
msg.printf(", ");
}
}
msg.printf("%s", FENCE_NAMES[i]);
nfences++;
}
fences >>= 1;
i++;
}
msg.printf(" fence");
if (nfences>1) {
msg.printf("s");
}
}
void AC_Fence::print_fence_message(const char* message, uint8_t fences) const
{
if (!fences) {
return;
}
char msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
ExpandingString e(msg, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
AC_Fence::get_fence_names(fences, e);
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "%s %s", e.get_writeable_string(), message);
}
void AC_Fence::update()
{
_poly_loader.update();
if (_enabled != _last_enabled || _auto_enabled != _last_auto_enabled) {
_last_enabled = _enabled;
_last_auto_enabled = _auto_enabled;
if (_enabled) {
_enabled_fences = _configured_fences.get() & ~AC_FENCE_TYPE_ALT_MIN;
} else {
_enabled_fences = 0;
}
}
#ifdef AC_FENCE_DEBUG
static uint32_t last_msg_count = 0;
if (get_enabled_fences() && last_msg_count++ % 10 == 0) {
print_fence_message("active", get_enabled_fences());
print_fence_message("breached", get_breaches());
}
#endif
}
uint8_t AC_Fence::enable(bool value, uint8_t fence_types, bool update_auto_enable)
{
uint8_t fences = _configured_fences.get() & fence_types;
uint8_t enabled_fences = _enabled_fences;
if (value) {
enabled_fences |= fences;
} else {
enabled_fences &= ~fences;
}
if (update_auto_enable && (fences & AC_FENCE_TYPE_ALT_MIN) != 0) {
_min_alt_state = value ? MinAltState::MANUALLY_ENABLED : MinAltState::MANUALLY_DISABLED;
}
uint8_t fences_to_change = _enabled_fences ^ enabled_fences;
if (!fences_to_change) {
return 0;
}
#if HAL_LOGGING_ENABLED
AP::logger().Write_Event(value ? LogEvent::FENCE_ENABLE : LogEvent::FENCE_DISABLE);
if (fences_to_change & AC_FENCE_TYPE_ALT_MAX) {
AP::logger().Write_Event(value ? LogEvent::FENCE_ALT_MAX_ENABLE : LogEvent::FENCE_ALT_MAX_DISABLE);
}
if (fences_to_change & AC_FENCE_TYPE_CIRCLE) {
AP::logger().Write_Event(value ? LogEvent::FENCE_CIRCLE_ENABLE : LogEvent::FENCE_CIRCLE_DISABLE);
}
if (fences_to_change & AC_FENCE_TYPE_ALT_MIN) {
AP::logger().Write_Event(value ? LogEvent::FENCE_ALT_MIN_ENABLE : LogEvent::FENCE_ALT_MIN_DISABLE);
}
if (fences_to_change & AC_FENCE_TYPE_POLYGON) {
AP::logger().Write_Event(value ? LogEvent::FENCE_POLYGON_ENABLE : LogEvent::FENCE_POLYGON_DISABLE);
}
#endif
_enabled_fences = enabled_fences;
if (!value) {
clear_breach(fences_to_change);
}
return fences_to_change;
}
void AC_Fence::enable_floor()
{
enable(true, AC_FENCE_TYPE_ALT_MIN);
}
void AC_Fence::disable_floor()
{
enable(false, AC_FENCE_TYPE_ALT_MIN);
}
void AC_Fence::auto_enable_fence_on_arming(void)
{
if (auto_enabled() != AC_Fence::AutoEnable::ONLY_WHEN_ARMED) {
return;
}
_min_alt_state = MinAltState::DEFAULT;
const uint8_t fences = enable(true, AC_FENCE_ARMING_FENCES, false);
print_fence_message("auto-enabled", fences);
}
void AC_Fence::auto_disable_fence_on_disarming(void)
{
if (auto_enabled() != AC_Fence::AutoEnable::ONLY_WHEN_ARMED) {
return;
}
const uint8_t fences = enable(false, AC_FENCE_ALL_FENCES, false);
print_fence_message("auto-disabled", fences);
}
void AC_Fence::auto_enable_fence_after_takeoff(void)
{
if (auto_enabled() != AutoEnable::ENABLE_ON_AUTO_TAKEOFF &&
auto_enabled() != AutoEnable::ENABLE_DISABLE_FLOOR_ONLY) {
return;
}
_min_alt_state = MinAltState::DEFAULT;
const uint8_t fences = enable(true, AC_FENCE_ALL_FENCES, false);
print_fence_message("auto-enabled", fences);
}
uint8_t AC_Fence::get_auto_disable_fences(void) const
{
uint8_t auto_disable = 0;
switch (auto_enabled()) {
case AC_Fence::AutoEnable::ENABLE_ON_AUTO_TAKEOFF:
auto_disable = AC_FENCE_ALL_FENCES;
break;
case AC_Fence::AutoEnable::ENABLE_DISABLE_FLOOR_ONLY:
case AC_Fence::AutoEnable::ONLY_WHEN_ARMED:
default:
auto_disable = AC_FENCE_TYPE_ALT_MIN;
break;
}
if (_min_alt_state == MinAltState::MANUALLY_ENABLED) {
auto_disable &= ~AC_FENCE_TYPE_ALT_MIN;
}
return auto_disable;
}
uint8_t AC_Fence::present() const
{
uint8_t mask = AC_FENCE_TYPE_CIRCLE | AC_FENCE_TYPE_ALT_MIN | AC_FENCE_TYPE_ALT_MAX;
if (_poly_loader.total_fence_count() > 0) {
mask |= AC_FENCE_TYPE_POLYGON;
}
return _configured_fences.get() & mask;
}
uint8_t AC_Fence::get_enabled_fences() const
{
return _enabled_fences & present();
}
float AC_Fence::get_margin_ne_m() const
{
return is_positive(_margin_ne_m.get()) ? _margin_ne_m.get() : _margin_m.get();
}
bool AC_Fence::pre_arm_check_polygon(char *failure_msg, const uint8_t failure_msg_len) const
{
if (!(_configured_fences & AC_FENCE_TYPE_POLYGON)) {
return true;
}
if (! _poly_loader.loaded()) {
hal.util->snprintf(failure_msg, failure_msg_len, "Polygon fence(s) invalid");
return false;
}
if (!_poly_loader.check_inclusion_circle_margin(get_margin_ne_m())) {
hal.util->snprintf(failure_msg, failure_msg_len, "Polygon fence margin is greater than inclusion circle radius");
return false;
}
return true;
}
bool AC_Fence::pre_arm_check_circle(char *failure_msg, const uint8_t failure_msg_len) const
{
if (_circle_radius_m < 0) {
hal.util->snprintf(failure_msg, failure_msg_len, "Invalid Circle FENCE_RADIUS value");
return false;
}
if (_circle_radius_m < get_margin_ne_m()) {
hal.util->snprintf(failure_msg, failure_msg_len, "Circle FENCE_MARGIN is greater than FENCE_RADIUS");
return false;
}
return true;
}
bool AC_Fence::pre_arm_check_alt(char *failure_msg, const uint8_t failure_msg_len) const
{
if (_alt_max_m < 0.0f) {
hal.util->snprintf(failure_msg, failure_msg_len, "Invalid FENCE_ALT_MAX value");
return false;
}
if (_alt_min_m < -100.0f) {
hal.util->snprintf(failure_msg, failure_msg_len, "Invalid FENCE_ALT_MIN value");
return false;
}
return true;
}
bool AC_Fence::pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const
{
if (_enabled && !present()) {
hal.util->snprintf(failure_msg, failure_msg_len, "Fences enabled, but none selected");
return false;
}
if (_auto_enabled == 1 || _auto_enabled == 2) {
static uint32_t last_autoenable_warn_ms;
const uint32_t now_ms = AP_HAL::millis();
if (now_ms - last_autoenable_warn_ms > 60000) {
GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "FENCE_AUTOENABLE is %u, will be removed in 4.7, use 3", unsigned(_auto_enabled));
last_autoenable_warn_ms = now_ms;
}
}
if ((!enabled() && !_auto_enabled) || !_configured_fences) {
return true;
}
if ((_configured_fences & AC_FENCE_TYPE_CIRCLE) ||
(_configured_fences & AC_FENCE_TYPE_POLYGON)) {
Vector2f position;
if (!AP::ahrs().get_relative_position_NE_home(position)) {
hal.util->snprintf(failure_msg, failure_msg_len, "Fence requires position");
return false;
}
}
if (!pre_arm_check_polygon(failure_msg, failure_msg_len)) {
return false;
}
if (!pre_arm_check_circle(failure_msg, failure_msg_len)) {
return false;
}
if (!pre_arm_check_alt(failure_msg, failure_msg_len)) {
return false;
}
auto breached_fences = _breached_fences;
if (auto_enabled() == AC_Fence::AutoEnable::ONLY_WHEN_ARMED) {
Location loc;
if (!AP::ahrs().get_location(loc)) {
hal.util->snprintf(failure_msg, failure_msg_len, "Fence requires position");
return false;
}
if (_poly_loader.breached(loc)) {
breached_fences |= AC_FENCE_TYPE_POLYGON;
}
}
if (breached_fences) {
char msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
ExpandingString e(msg, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
AC_Fence::get_fence_names(_breached_fences, e);
hal.util->snprintf(failure_msg, failure_msg_len, "Vehicle breaching %s", e.get_writeable_string());
return false;
}
if (_margin_m < 0.0f) {
hal.util->snprintf(failure_msg, failure_msg_len, "Invalid FENCE_MARGIN value");
return false;
}
if (_margin_ne_m < 0.0f) {
hal.util->snprintf(failure_msg, failure_msg_len, "Invalid FENCE_MARGIN_XY value");
return false;
}
if (_alt_max_m < _alt_min_m) {
hal.util->snprintf(failure_msg, failure_msg_len, "FENCE_ALT_MAX < FENCE_ALT_MIN");
return false;
}
if (_alt_max_m - _alt_min_m <= 2.0f * _margin_m) {
hal.util->snprintf(failure_msg, failure_msg_len, "FENCE_MARGIN too big");
return false;
}
return true;
}
bool AC_Fence::check_fence_alt_max()
{
if (!(get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX)) {
return false;
}
float curr_alt_d_m;
AP::ahrs().get_relative_position_D_home(curr_alt_d_m);
const float _curr_alt_u_m = -curr_alt_d_m;
_alt_max_breach_distance_m = _curr_alt_u_m - _alt_max_m;
if (_curr_alt_u_m >= _alt_max_m) {
if (!(_breached_fences & AC_FENCE_TYPE_ALT_MAX) ||
(!is_zero(_alt_max_backup_m) && _curr_alt_u_m >= _alt_max_backup_m)) {
record_breach(AC_FENCE_TYPE_ALT_MAX);
_alt_max_backup_m = _curr_alt_u_m + AC_FENCE_ALT_MAX_BACKUP_DISTANCE;
return true;
}
return false;
} else if (_curr_alt_u_m >= get_safe_alt_max_m()) {
record_margin_breach(AC_FENCE_TYPE_ALT_MAX);
} else {
clear_margin_breach(AC_FENCE_TYPE_ALT_MAX);
}
if ((_breached_fences & AC_FENCE_TYPE_ALT_MAX) != 0) {
clear_breach(AC_FENCE_TYPE_ALT_MAX);
_alt_max_backup_m = 0.0f;
}
return false;
}
bool AC_Fence::check_fence_alt_min()
{
if (!(get_enabled_fences() & AC_FENCE_TYPE_ALT_MIN)) {
return false;
}
float curr_alt_d_m;
AP::ahrs().get_relative_position_D_home(curr_alt_d_m);
const float _curr_alt_u_m = -curr_alt_d_m;
_alt_min_breach_distance_m = _alt_min_m - _curr_alt_u_m;
if (_curr_alt_u_m <= _alt_min_m) {
if (!(_breached_fences & AC_FENCE_TYPE_ALT_MIN) ||
(!is_zero(_alt_min_backup_m) && _curr_alt_u_m <= _alt_min_backup_m)) {
record_breach(AC_FENCE_TYPE_ALT_MIN);
_alt_min_backup_m = _curr_alt_u_m - AC_FENCE_ALT_MIN_BACKUP_DISTANCE;
return true;
}
return false;
} else if (_curr_alt_u_m <= get_safe_alt_min_m()) {
record_margin_breach(AC_FENCE_TYPE_ALT_MIN);
} else {
clear_margin_breach(AC_FENCE_TYPE_ALT_MIN);
}
if ((_breached_fences & AC_FENCE_TYPE_ALT_MIN) != 0) {
clear_breach(AC_FENCE_TYPE_ALT_MIN);
_alt_min_backup_m = 0.0f;
}
return false;
}
bool AC_Fence::auto_enable_fence_floor()
{
if (!(_configured_fences & AC_FENCE_TYPE_ALT_MIN)
|| (get_enabled_fences() & AC_FENCE_TYPE_ALT_MIN)
|| _min_alt_state == MinAltState::MANUALLY_DISABLED
|| (!_enabled && (auto_enabled() == AC_Fence::AutoEnable::ALWAYS_DISABLED
|| auto_enabled() == AutoEnable::ENABLE_ON_AUTO_TAKEOFF))) {
return false;
}
float _curr_alt_d_m;
AP::ahrs().get_relative_position_D_home(_curr_alt_d_m);
const float _curr_alt_u_m = -_curr_alt_d_m;
if (!floor_enabled() && _curr_alt_u_m >= get_safe_alt_min_m()) {
enable(true, AC_FENCE_TYPE_ALT_MIN, false);
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "Min Alt fence enabled (auto enable)");
return true;
}
return false;
}
bool AC_Fence::check_fence_polygon()
{
if (!(get_enabled_fences() & AC_FENCE_TYPE_POLYGON)) {
clear_breach(AC_FENCE_TYPE_POLYGON);
return false;
}
const bool was_breached = _breached_fences & AC_FENCE_TYPE_POLYGON;
if (_last_fence_check_loc_valid && _poly_loader.breached(_last_fence_check_loc, _polygon_breach_distance_m, _polygon_nearest_point)) {
if (!was_breached) {
record_breach(AC_FENCE_TYPE_POLYGON);
return true;
}
return false;
} else if (_polygon_breach_distance_m < 0 && fabsf(_polygon_breach_distance_m) < get_margin_ne_m()) {
record_margin_breach(AC_FENCE_TYPE_POLYGON);
} else {
clear_margin_breach(AC_FENCE_TYPE_POLYGON);
}
if (was_breached) {
clear_breach(AC_FENCE_TYPE_POLYGON);
}
return false;
}
bool AC_Fence::check_fence_circle()
{
if (!(get_enabled_fences() & AC_FENCE_TYPE_CIRCLE)) {
return false;
}
Vector2f home;
if (AP::ahrs().get_relative_position_NE_home(home)) {
_home_distance_m = home.length();
if (is_zero(home.length_squared())) {
_circle_breach_direction.x = _circle_radius_m;
_circle_breach_direction.y = 0.0f;
} else {
_circle_breach_direction = home.normalized() * _circle_radius_m.get() - home;
}
}
_circle_breach_distance_m = _home_distance_m - _circle_radius_m;
if (_home_distance_m >= _circle_radius_m) {
if (!(_breached_fences & AC_FENCE_TYPE_CIRCLE) ||
(!is_zero(_circle_radius_backup_m) && _home_distance_m >= _circle_radius_backup_m)) {
record_breach(AC_FENCE_TYPE_CIRCLE);
_circle_radius_backup_m = _home_distance_m + AC_FENCE_CIRCLE_RADIUS_BACKUP_DISTANCE;
return true;
}
return false;
} else if (_home_distance_m >= _circle_radius_m - get_margin_ne_m()) {
record_margin_breach(AC_FENCE_TYPE_CIRCLE);
} else {
clear_margin_breach(AC_FENCE_TYPE_CIRCLE);
}
if (_breached_fences & AC_FENCE_TYPE_CIRCLE) {
clear_breach(AC_FENCE_TYPE_CIRCLE);
_circle_radius_backup_m = 0.0f;
}
return false;
}
uint8_t AC_Fence::check(bool disable_auto_fences)
{
uint8_t ret = 0;
uint8_t disabled_fences = disable_auto_fences ? get_auto_disable_fences() : 0;
uint8_t fences_to_disable = disabled_fences & _enabled_fences;
clear_breach(~_configured_fences);
clear_breach(fences_to_disable);
clear_margin_breach(~_configured_fences);
clear_margin_breach(fences_to_disable);
if (_min_alt_state == MinAltState::MANUALLY_ENABLED) {
fences_to_disable &= ~AC_FENCE_TYPE_ALT_MIN;
}
if (fences_to_disable) {
print_fence_message("auto-disabled", fences_to_disable);
}
#if 0
{
float _curr_alt_d_m;
AP::ahrs().get_relative_position_D_home(_curr_alt_d_m);
AP::logger().WriteStreaming("FENC", "TimeUS,EN,AE,CF,EF,DF,Alt", "QIIIIIf",
AP_HAL::micros64(),
enabled(),
_auto_enabled,
_configured_fences,
get_enabled_fences(),
disabled_fences,
_curr_alt_d_m*-1);
}
#endif
if ((!enabled() && !_auto_enabled && !(_configured_fences & AC_FENCE_TYPE_ALT_MIN)) || !_configured_fences) {
return 0;
}
if (!_poly_loader.get_loaded_fence_semaphore().take_nonblocking()) {
return 0;
}
enable(false, disabled_fences, false);
_last_fence_check_loc_valid = AP::ahrs().get_location(_last_fence_check_loc);
if (!(disabled_fences & AC_FENCE_TYPE_ALT_MAX) && check_fence_alt_max()) {
ret |= AC_FENCE_TYPE_ALT_MAX;
}
if (!(disabled_fences & AC_FENCE_TYPE_ALT_MIN) && check_fence_alt_min()) {
ret |= AC_FENCE_TYPE_ALT_MIN;
}
if (!(disabled_fences & AC_FENCE_TYPE_ALT_MIN)) {
auto_enable_fence_floor();
}
if (!(disabled_fences & AC_FENCE_TYPE_CIRCLE) && check_fence_circle()) {
ret |= AC_FENCE_TYPE_CIRCLE;
}
if (!(disabled_fences & AC_FENCE_TYPE_POLYGON) && check_fence_polygon()) {
ret |= AC_FENCE_TYPE_POLYGON;
}
if (_manual_recovery_start_ms != 0) {
if ((AP_HAL::millis() - _manual_recovery_start_ms) < AC_FENCE_MANUAL_RECOVERY_TIME_MIN) {
_poly_loader.get_loaded_fence_semaphore().give();
return 0;
}
_manual_recovery_start_ms = 0;
}
_poly_loader.get_loaded_fence_semaphore().give();
return ret;
}
bool AC_Fence::check_destination_within_fence(const Location& loc)
{
if ((get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX)) {
int32_t alt_above_home_cm;
if (loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, alt_above_home_cm)) {
if ((alt_above_home_cm * 0.01f) > _alt_max_m) {
return false;
}
}
}
if ((get_enabled_fences() & AC_FENCE_TYPE_ALT_MIN)) {
int32_t alt_above_home_cm;
if (loc.get_alt_cm(Location::AltFrame::ABOVE_HOME, alt_above_home_cm)) {
if ((alt_above_home_cm * 0.01f) < _alt_min_m) {
return false;
}
}
}
if ((get_enabled_fences() & AC_FENCE_TYPE_CIRCLE)) {
if (AP::ahrs().get_home().get_distance(loc) > _circle_radius_m) {
return false;
}
}
if ((get_enabled_fences() & AC_FENCE_TYPE_POLYGON)) {
if (_poly_loader.breached(loc)) {
return false;
}
}
return true;
}
void AC_Fence::record_breach(uint8_t fence_type)
{
if (!_breached_fences) {
const uint32_t now = AP_HAL::millis();
_breach_time = now;
if (now - _last_breach_notify_sent_ms > 1000) {
_last_breach_notify_sent_ms = now;
GCS_SEND_MESSAGE(MSG_FENCE_STATUS);
}
}
if (_breach_count < 65500) {
_breach_count++;
}
_breached_fences |= fence_type;
}
void AC_Fence::record_margin_breach(uint8_t fence_type)
{
const uint32_t now = AP_HAL::millis();
bool notify_margin_breach = false;
if (option_enabled(OPTIONS::NOTIFY_MARGIN_BREACH)) {
if ((!is_zero(_notify_freq)
&& AP_HAL::timeout_expired(_last_margin_breach_notify_sent_ms, now,
uint32_t(roundf(1000.0f / _notify_freq))))
|| !(_breached_fence_margins & fence_type)) {
notify_margin_breach = true;
}
}
if (!(_breached_fence_margins & fence_type)) {
_margin_breach_time = now;
}
_breached_fence_margins |= fence_type;
if (notify_margin_breach) {
_last_margin_breach_notify_sent_ms = now;
char msg[MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1];
ExpandingString e(msg, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
AC_Fence::get_fence_names(_breached_fence_margins, e);
GCS_SEND_TEXT(MAV_SEVERITY_NOTICE, "%s in %.1fm", e.get_writeable_string(), fabsf(get_breach_distance(_breached_fence_margins)));
}
}
void AC_Fence::clear_breach(uint8_t fence_type)
{
_breached_fences &= ~fence_type;
}
void AC_Fence::clear_margin_breach(uint8_t fence_type)
{
if (_breached_fence_margins & fence_type) {
if (option_enabled(OPTIONS::NOTIFY_MARGIN_BREACH)) {
print_fence_message("cleared margin breach", fence_type);
}
}
_breached_fence_margins &= ~fence_type;
}
float AC_Fence::get_breach_distance(uint8_t fence_type) const
{
fence_type = fence_type & present();
float max_m = -FLT_MAX;
if (fence_type & AC_FENCE_TYPE_ALT_MAX) {
max_m = MAX(_alt_max_breach_distance_m, max_m);
}
if (fence_type & AC_FENCE_TYPE_ALT_MIN) {
max_m = MAX(_alt_min_breach_distance_m, max_m);
}
if (fence_type & AC_FENCE_TYPE_CIRCLE) {
max_m = MAX(_circle_breach_distance_m, max_m);
}
if (fence_type & AC_FENCE_TYPE_POLYGON) {
max_m = MAX(_polygon_breach_distance_m, max_m);
}
return max_m;
}
bool AC_Fence::get_breach_direction_NED(uint8_t fence_type, Vector3f& direction_to_closest, Location& fence_check_pos) const
{
fence_type = fence_type & present();
if (_last_fence_check_loc_valid) {
fence_check_pos = _last_fence_check_loc;
}
float closest_m = FLT_MAX;
if (fence_type & AC_FENCE_TYPE_ALT_MAX && fabsf(_alt_max_breach_distance_m) < closest_m) {
direction_to_closest = Vector3f{0, 0, _alt_max_breach_distance_m};
closest_m = fabsf(_alt_max_breach_distance_m);
}
if (fence_type & AC_FENCE_TYPE_ALT_MIN && fabsf(_alt_min_breach_distance_m) < closest_m) {
direction_to_closest = Vector3f{0, 0, -_alt_min_breach_distance_m};
closest_m = fabsf(_alt_min_breach_distance_m);
}
if (fence_type & AC_FENCE_TYPE_CIRCLE && fabsf(_circle_breach_distance_m) < closest_m) {
direction_to_closest = Vector3f{_circle_breach_direction.x, _circle_breach_direction.y, 0};
closest_m = fabsf(_circle_breach_distance_m);
}
if (fence_type & AC_FENCE_TYPE_POLYGON && fabsf(_polygon_breach_distance_m) < closest_m) {
direction_to_closest = Vector3f{_polygon_nearest_point.x, _polygon_nearest_point.y, 0};
closest_m = fabsf(_polygon_breach_distance_m);
}
return _last_fence_check_loc_valid;
}
void AC_Fence::manual_recovery_start()
{
if (!_breached_fences) {
return;
}
_manual_recovery_start_ms = AP_HAL::millis();
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Manual recovery started");
}
bool AC_Fence::sys_status_present() const
{
return present();
}
bool AC_Fence::sys_status_enabled() const
{
if (!sys_status_present()) {
return false;
}
if (_action == Action::REPORT_ONLY) {
return false;
}
return enabled();
}
bool AC_Fence::sys_status_failed() const
{
if (!sys_status_present()) {
return false;
}
if (get_breaches() != 0) {
return true;
}
return false;
}
AC_PolyFence_loader &AC_Fence::polyfence()
{
return _poly_loader;
}
const AC_PolyFence_loader &AC_Fence::polyfence() const
{
return _poly_loader;
}
#else
const AP_Param::GroupInfo AC_Fence::var_info[] = { AP_GROUPEND };
AC_Fence::AC_Fence() {};
uint8_t AC_Fence::enable(bool value, uint8_t fence_types, bool update_auto_enable) { return 0; }
void AC_Fence::enable_floor() {}
void AC_Fence::disable_floor() {}
void AC_Fence::update() {}
void AC_Fence::auto_enable_fence_after_takeoff() {}
void AC_Fence::auto_enable_fence_on_arming() {}
void AC_Fence::auto_disable_fence_on_disarming() {}
uint8_t AC_Fence::present() const { return 0; }
uint8_t AC_Fence::get_enabled_fences() const { return 0; }
bool AC_Fence::pre_arm_check(char *failure_msg, const uint8_t failure_msg_len) const { return true; }
uint8_t AC_Fence::check(bool disable_auto_fences) { return 0; }
bool AC_Fence::check_destination_within_fence(const Location& loc) { return true; }
float AC_Fence::get_breach_distance(uint8_t fence_type) const { return 0.0; }
bool AC_Fence::get_breach_direction_NED(uint8_t fence_type, Vector3f& direction, Location& fence_check_pos) const { return false; }
void AC_Fence::get_fence_names(uint8_t fences, ExpandingString& msg) { }
void AC_Fence::print_fence_message(const char* msg, uint8_t fences) const {}
void AC_Fence::manual_recovery_start() {}
bool AC_Fence::sys_status_present() const { return false; }
bool AC_Fence::sys_status_enabled() const { return false; }
bool AC_Fence::sys_status_failed() const { return false; }
AC_PolyFence_loader &AC_Fence::polyfence()
{
return _poly_loader;
}
const AC_PolyFence_loader &AC_Fence::polyfence() const
{
return _poly_loader;
}
#endif
AC_Fence *AC_Fence::_singleton;
namespace AP
{
AC_Fence *fence()
{
return AC_Fence::get_singleton();
}
}
#endif