mirror of https://github.com/ArduPilot/ardupilot
AP_Airspeed: save some bytes by making conversion structure static
This commit is contained in:
parent
e2046c11b8
commit
e20f8f5dcc
|
@ -246,7 +246,7 @@ void AP_Airspeed::convert_per_instance()
|
|||
return;
|
||||
}
|
||||
|
||||
const struct convert_table {
|
||||
static const struct convert_table {
|
||||
uint32_t element[2];
|
||||
ap_var_type type;
|
||||
const char* name;
|
||||
|
|
Loading…
Reference in New Issue