mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_OSD: align param info structures to save flash
This commit is contained in:
parent
57e35f39b1
commit
5c013552ed
@ -39,7 +39,7 @@
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
// macro for easy use of var_info2
|
||||
#define AP_SUBGROUPINFO2(element, name, idx, thisclazz, elclazz) { AP_PARAM_GROUP, idx, name, AP_VAROFFSET(thisclazz, element), { group_info : elclazz::var_info2 }, AP_PARAM_FLAG_NESTED_OFFSET }
|
||||
#define AP_SUBGROUPINFO2(element, name, idx, thisclazz, elclazz) { name, AP_VAROFFSET(thisclazz, element), { group_info : elclazz::var_info2 }, AP_PARAM_FLAG_NESTED_OFFSET, idx, AP_PARAM_GROUP }
|
||||
|
||||
const AP_Param::GroupInfo AP_OSD::var_info[] = {
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user