AC_Fence: Add missing const in member functions

Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
Patrick José Pereira 2021-02-01 13:26:26 -03:00 committed by Andrew Tridgell
parent e4fb439a96
commit 345fe1a9e4
2 changed files with 2 additions and 2 deletions

View File

@ -165,7 +165,7 @@ bool AC_PolyFence_loader::read_latlon_from_storage(uint16_t &read_offset, Vector
// load boundary point from eeprom, returns true on successful load
// only used for converting from old storage to new storage
bool AC_PolyFence_loader::load_point_from_eeprom(uint16_t i, Vector2l& point)
bool AC_PolyFence_loader::load_point_from_eeprom(uint16_t i, Vector2l& point) const
{
// sanity check index
if (i >= max_items()) {

View File

@ -324,7 +324,7 @@ private:
// their fences when upgrading)
bool convert_to_new_storage() WARN_IF_UNUSED;
// load boundary point from eeprom, returns true on successful load
bool load_point_from_eeprom(uint16_t i, Vector2l& point) WARN_IF_UNUSED;
bool load_point_from_eeprom(uint16_t i, Vector2l& point) const WARN_IF_UNUSED;
#if AC_POLYFENCE_FENCE_POINT_PROTOCOL_SUPPORT