diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index 0099248950..fa62b12288 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -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; diff --git a/ArduCopter/Parameters.cpp b/ArduCopter/Parameters.cpp index 82143d0f09..2630aa33c1 100644 --- a/ArduCopter/Parameters.cpp +++ b/ArduCopter/Parameters.cpp @@ -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 }; diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index c3efee426a..89475534ee 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -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[]; diff --git a/ArduCopter/system.cpp b/ArduCopter/system.cpp index 25d77df0ae..e3e766e2eb 100644 --- a/ArduCopter/system.cpp +++ b/ArduCopter/system.cpp @@ -106,7 +106,7 @@ void Copter::init_ardupilot() #endif #if OSD_ENABLED == ENABLED - g2.osd.init(); + osd.init(); #endif #if LOGGING_ENABLED == ENABLED