mirror of https://github.com/ArduPilot/ardupilot
Rover: integrate camera frontend/backend split
This commit is contained in:
parent
e9d9326410
commit
f7fe4f8856
|
@ -292,9 +292,9 @@ const AP_Param::Info Rover::var_info[] = {
|
|||
GOBJECT(ahrs, "AHRS_", AP_AHRS),
|
||||
|
||||
#if AP_CAMERA_ENABLED
|
||||
// @Group: CAM_
|
||||
// @Group: CAM
|
||||
// @Path: ../libraries/AP_Camera/AP_Camera.cpp
|
||||
GOBJECT(camera, "CAM_", AP_Camera),
|
||||
GOBJECT(camera, "CAM", AP_Camera),
|
||||
#endif
|
||||
|
||||
#if PRECISION_LANDING == ENABLED
|
||||
|
|
|
@ -112,6 +112,11 @@ void Rover::init_ardupilot()
|
|||
camera_mount.init();
|
||||
#endif
|
||||
|
||||
#if AP_CAMERA_ENABLED
|
||||
// initialise camera
|
||||
camera.init();
|
||||
#endif
|
||||
|
||||
#if PRECISION_LANDING == ENABLED
|
||||
// initialise precision landing
|
||||
init_precland();
|
||||
|
|
Loading…
Reference in New Issue