Copter: moved OSD to top level params

this gives us plenty of param depth for a complex param tree
This commit is contained in:
Andrew Tridgell 2018-06-23 17:34:25 +10:00
parent 75bf6984f5
commit 20dea6df45
4 changed files with 12 additions and 11 deletions

View File

@ -451,6 +451,10 @@ private:
AP_DEVO_Telem devo_telemetry{ahrs};
#endif
#if OSD_ENABLED == ENABLED
AP_OSD osd;
#endif
// Variables for extended status MAVLink messages
uint32_t control_sensors_present;
uint32_t control_sensors_enabled;

View File

@ -795,6 +795,12 @@ const AP_Param::Info Copter::var_info[] = {
GSCALAR(terrain_follow, "TERRAIN_FOLLOW", 0),
#endif
#if OSD_ENABLED == ENABLED
// @Group: OSD
// @Path: ../libraries/AP_OSD/AP_OSD.cpp
GOBJECT(osd, "OSD", AP_OSD),
#endif
// @Group:
// @Path: Parameters.cpp
GOBJECT(g2, "", ParametersG2),
@ -980,12 +986,6 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
AP_SUBGROUPINFO(follow, "FOLL", 27, ParametersG2, AP_Follow),
#endif
#if OSD_ENABLED
// @Group: OSD
// @Path: ../libraries/AP_OSD/AP_OSD.cpp
AP_SUBGROUPINFO(osd, "OSD_", 28, ParametersG2, AP_OSD),
#endif
AP_GROUPEND
};

View File

@ -47,6 +47,7 @@ public:
k_param_g2, // 2nd block of parameters
k_param_NavEKF3,
k_param_BoardConfig_CAN,
k_param_osd,
// simulation
k_param_sitl = 10,
@ -586,10 +587,6 @@ public:
AP_Follow follow;
#endif
#if OSD_ENABLED == ENABLED
AP_OSD osd;
#endif
};
extern const AP_Param::Info var_info[];

View File

@ -106,7 +106,7 @@ void Copter::init_ardupilot()
#endif
#if OSD_ENABLED == ENABLED
g2.osd.init();
osd.init();
#endif
#if LOGGING_ENABLED == ENABLED