mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-10 09:53:58 -04:00
Copter: moved OSD to top level params
this gives us plenty of param depth for a complex param tree
This commit is contained in:
parent
75bf6984f5
commit
20dea6df45
@ -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;
|
||||
|
@ -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
|
||||
};
|
||||
|
||||
|
@ -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[];
|
||||
|
@ -106,7 +106,7 @@ void Copter::init_ardupilot()
|
||||
#endif
|
||||
|
||||
#if OSD_ENABLED == ENABLED
|
||||
g2.osd.init();
|
||||
osd.init();
|
||||
#endif
|
||||
|
||||
#if LOGGING_ENABLED == ENABLED
|
||||
|
Loading…
Reference in New Issue
Block a user