From 7d8b114b245e0eee046d26143ef41551912df107 Mon Sep 17 00:00:00 2001 From: Michael du Breuil Date: Mon, 16 Sep 2019 13:07:56 -0700 Subject: [PATCH] Plane: Reduce size of GeoFenceState Cuts it from 32 bytes to 28 --- ArduPlane/geofence.cpp | 18 ++++++++---------- 1 file changed, 8 insertions(+), 10 deletions(-) diff --git a/ArduPlane/geofence.cpp b/ArduPlane/geofence.cpp index 1e5a2c06ae..da7fd64a00 100644 --- a/ArduPlane/geofence.cpp +++ b/ArduPlane/geofence.cpp @@ -21,24 +21,22 @@ * very quickly at runtime */ static struct GeofenceState { + Vector2l *boundary; // point 0 is the return point + uint32_t breach_time; + int32_t guided_lat; + int32_t guided_lng; + uint16_t breach_count; + uint8_t breach_type; + GeofenceEnableReason enable_reason; + uint8_t old_switch_position; uint8_t num_points; bool boundary_uptodate; bool fence_triggered; bool is_pwm_enabled; //true if above FENCE_ENABLE_PWM threshold bool is_enabled; - GeofenceEnableReason enable_reason; bool floor_enabled; //typically used for landing - uint16_t breach_count; - uint8_t breach_type; - uint32_t breach_time; - uint8_t old_switch_position; - int32_t guided_lat; - int32_t guided_lng; - /* point 0 is the return point */ - Vector2l *boundary; } *geofence_state; - static const StorageAccess fence_storage(StorageManager::StorageFence); /*