Browse Source

AC_Fence: add get_boundary_update_ms

this allows callers to detect changes in the underlying polygon fence
master
Randy Mackay 6 years ago
parent
commit
beb9ecbdcb
  1. 1
      libraries/AC_Fence/AC_Fence.cpp
  2. 4
      libraries/AC_Fence/AC_Fence.h

1
libraries/AC_Fence/AC_Fence.cpp

@ -573,6 +573,7 @@ bool AC_Fence::load_polygon_from_eeprom() @@ -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);

4
libraries/AC_Fence/AC_Fence.h

@ -112,6 +112,9 @@ public: @@ -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: @@ -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 {

Loading…
Cancel
Save