mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Plane: moved OSD to top level params
this is to give lots of depth for OSD params (which will be very complex)
This commit is contained in:
parent
20dea6df45
commit
bc503cc600
@ -1096,6 +1096,12 @@ const AP_Param::Info Plane::var_info[] = {
|
||||
// @Path: ../libraries/AP_Landing/AP_Landing.cpp
|
||||
GOBJECT(landing, "LAND_", AP_Landing),
|
||||
|
||||
#if OSD_ENABLED
|
||||
// @Group: OSD
|
||||
// @Path: ../libraries/AP_OSD/AP_OSD.cpp
|
||||
GOBJECT(osd, "OSD", AP_OSD),
|
||||
#endif
|
||||
|
||||
AP_VAREND
|
||||
};
|
||||
|
||||
@ -1169,12 +1175,6 @@ 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),
|
||||
#endif
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
|
@ -47,6 +47,7 @@ public:
|
||||
k_param_landing,
|
||||
k_param_NavEKF3,
|
||||
k_param_BoardConfig_CAN,
|
||||
k_param_osd,
|
||||
|
||||
// Misc
|
||||
//
|
||||
@ -541,11 +542,6 @@ public:
|
||||
// Payload Gripper
|
||||
AP_Gripper gripper;
|
||||
#endif
|
||||
|
||||
#if OSD_ENABLED == ENABLED
|
||||
AP_OSD osd;
|
||||
#endif
|
||||
|
||||
};
|
||||
|
||||
extern const AP_Param::Info var_info[];
|
||||
|
@ -290,6 +290,10 @@ private:
|
||||
// RSSI
|
||||
AP_RSSI rssi;
|
||||
|
||||
#if OSD_ENABLED == ENABLED
|
||||
AP_OSD osd;
|
||||
#endif
|
||||
|
||||
// This is the state of the flight control system
|
||||
// There are multiple states defined such as MANUAL, FBW-A, AUTO
|
||||
enum FlightMode control_mode = INITIALISING;
|
||||
|
@ -123,7 +123,7 @@ void Plane::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