mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
ArduSub: add and use AP_CAMERA_ENABLED
This commit is contained in:
parent
dabf78c61f
commit
9b5d70f7b5
@ -87,7 +87,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
|
|||||||
#if HAL_MOUNT_ENABLED
|
#if HAL_MOUNT_ENABLED
|
||||||
SCHED_TASK_CLASS(AP_Mount, &sub.camera_mount, update, 50, 75, 45),
|
SCHED_TASK_CLASS(AP_Mount, &sub.camera_mount, update, 50, 75, 45),
|
||||||
#endif
|
#endif
|
||||||
#if CAMERA == ENABLED
|
#if AP_CAMERA_ENABLED
|
||||||
SCHED_TASK_CLASS(AP_Camera, &sub.camera, update, 50, 75, 48),
|
SCHED_TASK_CLASS(AP_Camera, &sub.camera, update, 50, 75, 48),
|
||||||
#endif
|
#endif
|
||||||
SCHED_TASK(ten_hz_logging_loop, 10, 350, 51),
|
SCHED_TASK(ten_hz_logging_loop, 10, 350, 51),
|
||||||
|
@ -409,7 +409,7 @@ const AP_Param::Info Sub::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 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),
|
||||||
|
@ -99,9 +99,7 @@
|
|||||||
#include <AP_Rally/AP_Rally.h> // Rally point library
|
#include <AP_Rally/AP_Rally.h> // Rally point library
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if CAMERA == ENABLED
|
|
||||||
#include <AP_Camera/AP_Camera.h> // Photo or video camera
|
#include <AP_Camera/AP_Camera.h> // Photo or video camera
|
||||||
#endif
|
|
||||||
|
|
||||||
#if AP_SCRIPTING_ENABLED
|
#if AP_SCRIPTING_ENABLED
|
||||||
#include <AP_Scripting/AP_Scripting.h>
|
#include <AP_Scripting/AP_Scripting.h>
|
||||||
@ -336,7 +334,7 @@ private:
|
|||||||
AC_Circle circle_nav;
|
AC_Circle circle_nav;
|
||||||
|
|
||||||
// Camera
|
// Camera
|
||||||
#if CAMERA == ENABLED
|
#if AP_CAMERA_ENABLED
|
||||||
AP_Camera camera{MASK_LOG_CAMERA};
|
AP_Camera camera{MASK_LOG_CAMERA};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -103,13 +103,6 @@
|
|||||||
# define NAV_GUIDED ENABLED
|
# define NAV_GUIDED ENABLED
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
|
||||||
// CAMERA TRIGGER AND CONTROL
|
|
||||||
//
|
|
||||||
#ifndef CAMERA
|
|
||||||
# define CAMERA DISABLED
|
|
||||||
#endif
|
|
||||||
|
|
||||||
//////////////////////////////////////////////////////////////////////////////
|
//////////////////////////////////////////////////////////////////////////////
|
||||||
// Flight mode definitions
|
// Flight mode definitions
|
||||||
//
|
//
|
||||||
|
@ -78,7 +78,7 @@ bool Sub::set_mode(control_mode_t mode, ModeReason reason)
|
|||||||
// update notify object
|
// update notify object
|
||||||
notify_flight_mode(control_mode);
|
notify_flight_mode(control_mode);
|
||||||
|
|
||||||
#if CAMERA == ENABLED
|
#if AP_CAMERA_ENABLED
|
||||||
camera.set_is_auto_mode(control_mode == AUTO);
|
camera.set_is_auto_mode(control_mode == AUTO);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user