diff --git a/libraries/AC_Fence/AC_Fence.cpp b/libraries/AC_Fence/AC_Fence.cpp index e973c38932..e748137330 100644 --- a/libraries/AC_Fence/AC_Fence.cpp +++ b/libraries/AC_Fence/AC_Fence.cpp @@ -573,6 +573,7 @@ bool AC_Fence::load_polygon_from_eeprom() _boundary[index] = ekf_origin.get_distance_NE(temp_loc) * 100.0f; } _boundary_num_points = _total; + _boundary_update_ms = AP_HAL::millis(); // update validity of polygon _boundary_valid = _poly_loader.boundary_valid(_boundary_num_points, _boundary); diff --git a/libraries/AC_Fence/AC_Fence.h b/libraries/AC_Fence/AC_Fence.h index 931fbeb914..f9de841480 100644 --- a/libraries/AC_Fence/AC_Fence.h +++ b/libraries/AC_Fence/AC_Fence.h @@ -112,6 +112,9 @@ public: /// handler for polygon fence messages with GCS void handle_msg(GCS_MAVLINK &link, mavlink_message_t* msg); + /// return system time of last update to the boundary (allows external detection of boundary changes) + uint32_t get_boundary_update_ms() const { return _boundary_update_ms; } + static const struct AP_Param::GroupInfo var_info[]; // methods for mavlink SYS_STATUS message (send_sys_status) @@ -187,6 +190,7 @@ private: uint8_t _boundary_num_points = 0; // number of points in the boundary array (should equal _total parameter after load has completed) bool _boundary_create_attempted = false; // true if we have attempted to create the boundary array bool _boundary_valid = false; // true if boundary forms a closed polygon + uint32_t _boundary_update_ms; // system time of last update to the boundary }; namespace AP {