Plane: Reduce size of GeoFenceState

Cuts it from 32 bytes to 28
This commit is contained in:
Michael du Breuil 2019-09-16 13:07:56 -07:00 committed by WickedShell
parent af0dfb6d8b
commit 7d8b114b24
1 changed files with 8 additions and 10 deletions

View File

@ -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);
/*