From f637facea299ff8f7de305fcc0192367929844ba Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Sat, 25 Dec 2021 09:05:23 +1100 Subject: [PATCH] Sub: create and use AP_OPTICALFLOW_ENABLED --- ArduSub/ArduSub.cpp | 2 +- ArduSub/GCS_Sub.cpp | 2 +- ArduSub/Parameters.cpp | 2 +- ArduSub/Sub.h | 6 ++---- ArduSub/config.h | 6 ------ ArduSub/system.cpp | 4 ++-- 6 files changed, 7 insertions(+), 15 deletions(-) diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index 6c36dd7eb5..4b8e8e930d 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -48,7 +48,7 @@ SCHED_TASK_CLASS arguments: const AP_Scheduler::Task Sub::scheduler_tasks[] = { SCHED_TASK(fifty_hz_loop, 50, 75, 3), SCHED_TASK_CLASS(AP_GPS, &sub.gps, update, 50, 200, 6), -#if OPTFLOW == ENABLED +#if AP_OPTICALFLOW_ENABLED SCHED_TASK_CLASS(OpticalFlow, &sub.optflow, update, 200, 160, 9), #endif SCHED_TASK(update_batt_compass, 10, 120, 12), diff --git a/ArduSub/GCS_Sub.cpp b/ArduSub/GCS_Sub.cpp index e856c04cad..0946c397ad 100644 --- a/ArduSub/GCS_Sub.cpp +++ b/ArduSub/GCS_Sub.cpp @@ -56,7 +56,7 @@ void GCS_Sub::update_vehicle_sensor_status_flags() control_sensors_health |= MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE; } -#if OPTFLOW == ENABLED +#if AP_OPTICALFLOW_ENABLED const OpticalFlow *optflow = AP::opticalflow(); if (optflow && optflow->enabled()) { control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW; diff --git a/ArduSub/Parameters.cpp b/ArduSub/Parameters.cpp index dbaa311a93..9ad30ae14a 100644 --- a/ArduSub/Parameters.cpp +++ b/ArduSub/Parameters.cpp @@ -599,7 +599,7 @@ const AP_Param::Info Sub::var_info[] = { GOBJECT(terrain, "TERRAIN_", AP_Terrain), #endif -#if OPTFLOW == ENABLED +#if AP_OPTICALFLOW_ENABLED // @Group: FLOW // @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp GOBJECT(optflow, "FLOW", OpticalFlow), diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index 64d6017d1f..f713f9b6ae 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -77,11 +77,9 @@ #include "AP_Arming_Sub.h" #include "GCS_Sub.h" -// libraries which are dependent on #defines in defines.h and/or config.h -#if OPTFLOW == ENABLED #include // Optical Flow library -#endif +// libraries which are dependent on #defines in defines.h and/or config.h #if RCMAP_ENABLED == ENABLED #include // RC input mapping library #endif @@ -167,7 +165,7 @@ private: FUNCTOR_BIND_MEMBER(&Sub::exit_mission, void)}; // Optical flow sensor -#if OPTFLOW == ENABLED +#if AP_OPTICALFLOW_ENABLED OpticalFlow optflow; #endif diff --git a/ArduSub/config.h b/ArduSub/config.h index 02e92978f1..1b8828eafd 100644 --- a/ArduSub/config.h +++ b/ArduSub/config.h @@ -99,12 +99,6 @@ # define EKF_ORIGIN_MAX_DIST_M 50000 // EKF origin and waypoints (including home) must be within 50km #endif -////////////////////////////////////////////////////////////////////////////// -// OPTICAL_FLOW -#ifndef OPTFLOW -# define OPTFLOW DISABLED -#endif - ////////////////////////////////////////////////////////////////////////////// // gripper #ifndef GRIPPER_ENABLED diff --git a/ArduSub/system.cpp b/ArduSub/system.cpp index 93d6bea262..e76ea79ce6 100644 --- a/ArduSub/system.cpp +++ b/ArduSub/system.cpp @@ -85,7 +85,7 @@ void Sub::init_ardupilot() AP::compass().set_log_bit(MASK_LOG_COMPASS); AP::compass().init(); -#if OPTFLOW == ENABLED +#if AP_OPTICALFLOW_ENABLED // initialise optical flow sensor optflow.init(MASK_LOG_OPTFLOW); #endif @@ -231,7 +231,7 @@ bool Sub::optflow_position_ok() // return immediately if neither optflow nor visual odometry is enabled bool enabled = false; -#if OPTFLOW == ENABLED +#if AP_OPTICALFLOW_ENABLED if (optflow.enabled()) { enabled = true; }