mirror of https://github.com/ArduPilot/ardupilot
AC_Fence: void index when overwriting fence count on fencepoint-close
This commit is contained in:
parent
09bc81e846
commit
c20b20ec17
|
@ -1547,6 +1547,7 @@ void AC_PolyFence_loader::handle_msg_fence_point(GCS_MAVLINK &link, const mavlin
|
|||
fence_storage.write_uint8(inclusion_fence->storage_offset+1, packet.idx-1);
|
||||
// and write end of storage marker
|
||||
fence_storage.write_uint8(inclusion_fence->storage_offset+2+(packet.idx-1)*8, uint8_t(AC_PolyFenceType::END_OF_STORAGE));
|
||||
void_index();
|
||||
} else {
|
||||
const FenceIndex *inclusion_fence = get_or_create_include_fence();
|
||||
if (inclusion_fence == nullptr) {
|
||||
|
|
Loading…
Reference in New Issue