mirror of https://github.com/ArduPilot/ardupilot
AP_RangeFinder: Rearrange parameters to reduce memory usage
Saves 4 bytes per instance, and with 10 instances this gives us an extra 40 bytes of RAM
This commit is contained in:
parent
2b6c9b931c
commit
ebab492700
|
@ -13,18 +13,18 @@ public:
|
|||
AP_RangeFinder_Params(const AP_RangeFinder_Params &other) = delete;
|
||||
AP_RangeFinder_Params &operator=(const AP_RangeFinder_Params&) = delete;
|
||||
|
||||
AP_Vector3f pos_offset; // position offset in body frame
|
||||
AP_Float scaling;
|
||||
AP_Float offset;
|
||||
AP_Int16 powersave_range;
|
||||
AP_Int16 min_distance_cm;
|
||||
AP_Int16 max_distance_cm;
|
||||
AP_Int8 type;
|
||||
AP_Int8 pin;
|
||||
AP_Int8 ratiometric;
|
||||
AP_Int16 powersave_range;
|
||||
AP_Int8 stop_pin;
|
||||
AP_Float scaling;
|
||||
AP_Float offset;
|
||||
AP_Int8 function;
|
||||
AP_Int16 min_distance_cm;
|
||||
AP_Int16 max_distance_cm;
|
||||
AP_Int8 ground_clearance_cm;
|
||||
AP_Int8 address;
|
||||
AP_Vector3f pos_offset; // position offset in body frame
|
||||
AP_Int8 orientation;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue