mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_OSD: move OSD_LINK_Q_* to a new param table
this gives us room for up to 63 more entries
This commit is contained in:
parent
ca92d73f25
commit
2bd04c14fd
@ -35,6 +35,9 @@
|
|||||||
#include <AP_Notify/AP_Notify.h>
|
#include <AP_Notify/AP_Notify.h>
|
||||||
#include <AP_Terrain/AP_Terrain.h>
|
#include <AP_Terrain/AP_Terrain.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 }
|
||||||
|
|
||||||
const AP_Param::GroupInfo AP_OSD::var_info[] = {
|
const AP_Param::GroupInfo AP_OSD::var_info[] = {
|
||||||
|
|
||||||
// @Param: _TYPE
|
// @Param: _TYPE
|
||||||
@ -211,6 +214,13 @@ const AP_Param::GroupInfo AP_OSD::var_info[] = {
|
|||||||
// @Path: AP_OSD_ParamScreen.cpp
|
// @Path: AP_OSD_ParamScreen.cpp
|
||||||
AP_SUBGROUPINFO(param_screen[1], "6_", 22, AP_OSD, AP_OSD_ParamScreen),
|
AP_SUBGROUPINFO(param_screen[1], "6_", 22, AP_OSD, AP_OSD_ParamScreen),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// additional tables to go beyond 63 limit
|
||||||
|
AP_SUBGROUPINFO2(screen[0], "1_", 27, AP_OSD, AP_OSD_Screen),
|
||||||
|
AP_SUBGROUPINFO2(screen[1], "2_", 28, AP_OSD, AP_OSD_Screen),
|
||||||
|
AP_SUBGROUPINFO2(screen[2], "3_", 29, AP_OSD, AP_OSD_Screen),
|
||||||
|
AP_SUBGROUPINFO2(screen[3], "4_", 30, AP_OSD, AP_OSD_Screen),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -121,6 +121,7 @@ public:
|
|||||||
|
|
||||||
// User settable parameters
|
// User settable parameters
|
||||||
static const struct AP_Param::GroupInfo var_info[];
|
static const struct AP_Param::GroupInfo var_info[];
|
||||||
|
static const struct AP_Param::GroupInfo var_info2[];
|
||||||
|
|
||||||
private:
|
private:
|
||||||
friend class AP_MSP;
|
friend class AP_MSP;
|
||||||
|
@ -995,6 +995,10 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
|
|||||||
// @Range: 0 15
|
// @Range: 0 15
|
||||||
AP_SUBGROUPINFO(rngf, "RNGF", 60, AP_OSD_Screen, AP_OSD_Setting),
|
AP_SUBGROUPINFO(rngf, "RNGF", 60, AP_OSD_Screen, AP_OSD_Setting),
|
||||||
|
|
||||||
|
AP_GROUPEND
|
||||||
|
};
|
||||||
|
|
||||||
|
const AP_Param::GroupInfo AP_OSD_Screen::var_info2[] = {
|
||||||
// @Param: LINK_Q_EN
|
// @Param: LINK_Q_EN
|
||||||
// @DisplayName: LINK_Q_EN
|
// @DisplayName: LINK_Q_EN
|
||||||
// @Description: Displays Receiver link quality
|
// @Description: Displays Receiver link quality
|
||||||
@ -1009,7 +1013,8 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
|
|||||||
// @DisplayName: LINK_Q_Y
|
// @DisplayName: LINK_Q_Y
|
||||||
// @Description: Vertical position on screen
|
// @Description: Vertical position on screen
|
||||||
// @Range: 0 15
|
// @Range: 0 15
|
||||||
AP_SUBGROUPINFO(link_quality, "LINK_Q", 61, AP_OSD_Screen, AP_OSD_Setting),
|
AP_SUBGROUPINFO(link_quality, "LINK_Q", 1, AP_OSD_Screen, AP_OSD_Setting),
|
||||||
|
|
||||||
AP_GROUPEND
|
AP_GROUPEND
|
||||||
};
|
};
|
||||||
|
|
||||||
@ -1017,6 +1022,7 @@ const AP_Param::GroupInfo AP_OSD_Screen::var_info[] = {
|
|||||||
AP_OSD_Screen::AP_OSD_Screen()
|
AP_OSD_Screen::AP_OSD_Screen()
|
||||||
{
|
{
|
||||||
AP_Param::setup_object_defaults(this, var_info);
|
AP_Param::setup_object_defaults(this, var_info);
|
||||||
|
AP_Param::setup_object_defaults(this, var_info2);
|
||||||
}
|
}
|
||||||
|
|
||||||
//Symbols
|
//Symbols
|
||||||
|
Loading…
Reference in New Issue
Block a user