diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index e1c7b20af6..fcffc61e7b 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -87,7 +87,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { #if HAL_MOUNT_ENABLED SCHED_TASK_CLASS(AP_Mount, &sub.camera_mount, update, 50, 75, 45), #endif -#if CAMERA == ENABLED +#if AP_CAMERA_ENABLED SCHED_TASK_CLASS(AP_Camera, &sub.camera, update, 50, 75, 48), #endif SCHED_TASK(ten_hz_logging_loop, 10, 350, 51), diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index a9025addf5..8e2fa53221 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -409,7 +409,7 @@ const AP_Param::Info Sub::var_info[] = { // variables not in the g class which contain EEPROM saved variables -#if CAMERA == ENABLED +#if AP_CAMERA_ENABLED // @Group: CAM_ // @Path: ../libraries/AP_Camera/AP_Camera.cpp GOBJECT(camera, "CAM_", AP_Camera), diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 2bb1c402c5..be74602a40 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -99,9 +99,7 @@ #include // Rally point library #endif -#if CAMERA == ENABLED #include // Photo or video camera -#endif #if AP_SCRIPTING_ENABLED #include @@ -336,7 +334,7 @@ private: AC_Circle circle_nav; // Camera -#if CAMERA == ENABLED +#if AP_CAMERA_ENABLED AP_Camera camera{MASK_LOG_CAMERA}; #endif diff --git a/ArduSub/config.h b/ArduSub/config.h index 322bd5b9aa..af0e6fc52c 100644 --- a/ArduSub/config.h +++ b/ArduSub/config.h @@ -103,13 +103,6 @@ # define NAV_GUIDED ENABLED #endif -////////////////////////////////////////////////////////////////////////////// -// CAMERA TRIGGER AND CONTROL -// -#ifndef CAMERA -# define CAMERA DISABLED -#endif - ////////////////////////////////////////////////////////////////////////////// // Flight mode definitions // diff --git a/ArduSub/flight_mode.cpp b/ArduSub/flight_mode.cpp index cfd9c5943b..521586923f 100644 --- a/ArduSub/flight_mode.cpp +++ b/ArduSub/flight_mode.cpp @@ -78,7 +78,7 @@ bool Sub::set_mode(control_mode_t mode, ModeReason reason) // update notify object notify_flight_mode(control_mode); -#if CAMERA == ENABLED +#if AP_CAMERA_ENABLED camera.set_is_auto_mode(control_mode == AUTO); #endif