@ -1169,6 +1169,12 @@ const AP_Param::GroupInfo ParametersG2::var_info[] = {
AP_SUBGROUPINFO(gripper, "GRIP_", 12, ParametersG2, AP_Gripper),
#endif
#if OSD_ENABLED
// @Group: OSD
// @Path: ../libraries/AP_OSD/AP_OSD.cpp
AP_SUBGROUPINFO(osd, "OSD_", 13, ParametersG2, AP_OSD),
AP_GROUPEND
};
@ -542,6 +542,10 @@ public:
AP_Gripper gripper;
#if OSD_ENABLED == ENABLED
AP_OSD osd;
extern const AP_Param::Info var_info[];
@ -85,6 +85,7 @@
#include <AP_BoardConfig/AP_BoardConfig_CAN.h>
#include <AP_Frsky_Telem/AP_Frsky_Telem.h>
#include <AP_Devo_Telem/AP_Devo_Telem.h>
#include <AP_OSD/AP_OSD.h>
#include <AP_ServoRelayEvents/AP_ServoRelayEvents.h>
#include <AP_Rally/AP_Rally.h>
@ -373,3 +373,8 @@
#define DEVO_TELEM_ENABLED ENABLED
#ifndef OSD_ENABLED
#define OSD_ENABLED DISABLED
@ -58,3 +58,4 @@ LIBRARIES += AP_Beacon
LIBRARIES += PID
LIBRARIES += AP_Soaring
LIBRARIES += AP_Devo_Telem
LIBRARIES += AP_OSD
@ -122,6 +122,10 @@ void Plane::init_ardupilot()
devo_telemetry.init(serial_manager);
g2.osd.init();
#if LOGGING_ENABLED == ENABLED
log_init();
@ -32,6 +32,7 @@ def build(bld):
'PID',
'AP_Soaring',
'AP_Devo_Telem',
'AP_OSD',
],
)