mirror of https://github.com/ArduPilot/ardupilot
ArduPlane: add and use AP_CAMERA_ENABLED
This commit is contained in:
parent
fd28991ab2
commit
dabf78c61f
|
@ -97,7 +97,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
|
|||
#if HAL_MOUNT_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Mount, &plane.camera_mount, update, 50, 100, 105),
|
||||
#endif // HAL_MOUNT_ENABLED
|
||||
#if CAMERA == ENABLED
|
||||
#if AP_CAMERA_ENABLED
|
||||
SCHED_TASK_CLASS(AP_Camera, &plane.camera, update, 50, 100, 108),
|
||||
#endif // CAMERA == ENABLED
|
||||
SCHED_TASK_CLASS(AP_Scheduler, &plane.scheduler, update_logging, 0.2, 100, 111),
|
||||
|
|
|
@ -746,7 +746,7 @@ const AP_Param::Info Plane::var_info[] = {
|
|||
// @Path: ../libraries/AP_GPS/AP_GPS.cpp
|
||||
GOBJECT(gps, "GPS", AP_GPS),
|
||||
|
||||
#if CAMERA == ENABLED
|
||||
#if AP_CAMERA_ENABLED
|
||||
// @Group: CAM_
|
||||
// @Path: ../libraries/AP_Camera/AP_Camera.cpp
|
||||
GOBJECT(camera, "CAM_", AP_Camera),
|
||||
|
|
|
@ -236,7 +236,7 @@ private:
|
|||
AP_Navigation *nav_controller = &L1_controller;
|
||||
|
||||
// Camera
|
||||
#if CAMERA == ENABLED
|
||||
#if AP_CAMERA_ENABLED
|
||||
AP_Camera camera{MASK_LOG_CAMERA};
|
||||
#endif
|
||||
|
||||
|
|
|
@ -111,13 +111,6 @@
|
|||
#define DSPOILR_RUD_RATE_DEFAULT 100
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// CAMERA TRIGGER AND CONTROL
|
||||
//
|
||||
#ifndef CAMERA
|
||||
# define CAMERA ENABLED
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
// FLIGHT AND NAVIGATION CONTROL
|
||||
|
|
|
@ -53,7 +53,7 @@ bool Mode::enter()
|
|||
plane.guided_state.last_target_alt = 0;
|
||||
#endif
|
||||
|
||||
#if CAMERA == ENABLED
|
||||
#if AP_CAMERA_ENABLED
|
||||
plane.camera.set_is_auto_mode(this == &plane.mode_auto);
|
||||
#endif
|
||||
|
||||
|
|
Loading…
Reference in New Issue