ArduPlane: create and use AP_OPTICALFLOW_ENABLED

This commit is contained in:
Peter Barker 2021-12-24 19:17:51 +11:00 committed by Andrew Tridgell
parent f361d9b0d0
commit e55eea961f
6 changed files with 5 additions and 14 deletions

View File

@ -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),

View File

@ -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;

View File

@ -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),

View File

@ -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

View File

@ -33,15 +33,6 @@
#endif
//////////////////////////////////////////////////////////////////////////////
// Optical flow sensor support
//
#ifndef OPTFLOW
# define OPTFLOW ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// RADIO CONFIGURATION

View File

@ -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);
}