AC_Fence: emit a FENCE_STATUS message if we newly-breach the fences

This should resolve a problem in autotest where we don't detect the
fence as being breached as ArduPilot never announces the fact it has
breached - it just changes mode to RTL but the interval on the
FENCE_STATUS message never aligns with the time the vehicle is breached.
This commit is contained in:
Peter Barker 2021-02-13 14:01:25 +11:00 committed by Randy Mackay
parent edc2b0c94e
commit a0172fd2ca
2 changed files with 10 additions and 1 deletions

View File

@ -401,7 +401,14 @@ void AC_Fence::record_breach(uint8_t fence_type)
{
// if we haven't already breached a limit, update the breach time
if (!_breached_fences) {
_breach_time = AP_HAL::millis();
const uint32_t now = AP_HAL::millis();
_breach_time = now;
// emit a message indicated we're newly-breached, but not too often
if (now - _last_breach_notify_sent_ms > 1000) {
_last_breach_notify_sent_ms = now;
gcs().send_message(MSG_FENCE_STATUS);
}
}
// update breach count

View File

@ -168,9 +168,11 @@ private:
uint8_t _breached_fences; // bitmask holding the fence type that was breached (i.e. AC_FENCE_TYPE_ALT_MIN, AC_FENCE_TYPE_CIRCLE)
uint32_t _breach_time; // time of last breach in milliseconds
uint16_t _breach_count; // number of times we have breached the fence
uint32_t _last_breach_notify_sent_ms; // last time we sent a message about newly-breaching the fences
uint32_t _manual_recovery_start_ms; // system time in milliseconds that pilot re-took manual control
AC_PolyFence_loader _poly_loader{_total}; // polygon fence
};