From e55eea961fb2e85bea5ecc6ff92ba3b5f3c3054f Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 24 Dec 2021 19:17:51 +1100 Subject: [PATCH] ArduPlane: create and use AP_OPTICALFLOW_ENABLED --- ArduPlane/ArduPlane.cpp | 2 +- ArduPlane/GCS_Plane.cpp | 2 +- ArduPlane/Parameters.cpp | 2 +- ArduPlane/Plane.h | 2 +- ArduPlane/config.h | 9 --------- ArduPlane/system.cpp | 2 +- 6 files changed, 5 insertions(+), 14 deletions(-) diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index b188186ee3..d8a7dfb9c5 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -84,7 +84,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = { SCHED_TASK(read_rangefinder, 50, 100, 78), SCHED_TASK_CLASS(AP_ICEngine, &plane.g2.ice_control, update, 10, 100, 81), SCHED_TASK_CLASS(Compass, &plane.compass, cal_update, 50, 50, 84), -#if OPTFLOW == ENABLED +#if AP_OPTICALFLOW_ENABLED SCHED_TASK_CLASS(OpticalFlow, &plane.optflow, update, 50, 50, 87), #endif SCHED_TASK(one_second_loop, 1, 400, 90), diff --git a/ArduPlane/GCS_Plane.cpp b/ArduPlane/GCS_Plane.cpp index 7b66fcdf54..0a8012a314 100644 --- a/ArduPlane/GCS_Plane.cpp +++ b/ArduPlane/GCS_Plane.cpp @@ -110,7 +110,7 @@ void GCS_Plane::update_vehicle_sensor_status_flags(void) control_sensors_health |= MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION; } -#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/ArduPlane/Parameters.cpp b/ArduPlane/Parameters.cpp index 461ed33e62..f5903998e4 100644 --- a/ArduPlane/Parameters.cpp +++ b/ArduPlane/Parameters.cpp @@ -938,7 +938,7 @@ const AP_Param::Info Plane::var_info[] = { GOBJECT(afs, "AFS_", AP_AdvancedFailsafe), #endif -#if OPTFLOW == ENABLED +#if AP_OPTICALFLOW_ENABLED // @Group: FLOW // @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp GOBJECT(optflow, "FLOW", OpticalFlow), diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 2f11117a2a..914677d6e3 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -241,7 +241,7 @@ private: AP_Camera camera{MASK_LOG_CAMERA}; #endif -#if OPTFLOW == ENABLED +#if AP_OPTICALFLOW_ENABLED // Optical flow sensor OpticalFlow optflow; #endif diff --git a/ArduPlane/config.h b/ArduPlane/config.h index 209c9113d4..f27263f074 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -33,15 +33,6 @@ #endif -////////////////////////////////////////////////////////////////////////////// -// Optical flow sensor support -// - -#ifndef OPTFLOW - # define OPTFLOW ENABLED -#endif - - ////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////// // RADIO CONFIGURATION diff --git a/ArduPlane/system.cpp b/ArduPlane/system.cpp index 64d83bf99b..fc76eea9bb 100644 --- a/ArduPlane/system.cpp +++ b/ArduPlane/system.cpp @@ -136,7 +136,7 @@ void Plane::init_ardupilot() reset_control_switch(); // initialise sensor -#if OPTFLOW == ENABLED +#if AP_OPTICALFLOW_ENABLED if (optflow.enabled()) { optflow.init(-1); }