mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 08:13:56 -04:00
Copter: integrate camera frontend/backend split
This commit is contained in:
parent
50bcf1f278
commit
e30a492137
@ -444,9 +444,9 @@ const AP_Param::Info Copter::var_info[] = {
|
|||||||
// variables not in the g class which contain EEPROM saved variables
|
// variables not in the g class which contain EEPROM saved variables
|
||||||
|
|
||||||
#if AP_CAMERA_ENABLED
|
#if AP_CAMERA_ENABLED
|
||||||
// @Group: CAM_
|
// @Group: CAM
|
||||||
// @Path: ../libraries/AP_Camera/AP_Camera.cpp
|
// @Path: ../libraries/AP_Camera/AP_Camera.cpp
|
||||||
GOBJECT(camera, "CAM_", AP_Camera),
|
GOBJECT(camera, "CAM", AP_Camera),
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// @Group: RELAY_
|
// @Group: RELAY_
|
||||||
|
@ -127,6 +127,11 @@ void Copter::init_ardupilot()
|
|||||||
camera_mount.init();
|
camera_mount.init();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if AP_CAMERA_ENABLED
|
||||||
|
// initialise camera
|
||||||
|
camera.init();
|
||||||
|
#endif
|
||||||
|
|
||||||
#if PRECISION_LANDING == ENABLED
|
#if PRECISION_LANDING == ENABLED
|
||||||
// initialise precision landing
|
// initialise precision landing
|
||||||
init_precland();
|
init_precland();
|
||||||
|
Loading…
Reference in New Issue
Block a user