ArduSub: rename OpticalFlow class to AP_OpticalFlow

Brings us in-line with other classes in ArduPilot.

Removes ambiguity with AP_HAL::OpticalFlow which can cause compilation errors as we start to make code more portable across targets
This commit is contained in:
Peter Barker 2022-08-15 11:31:15 +10:00 committed by Peter Barker
parent 0d19d7646f
commit 2cb5a0cc26
4 changed files with 4 additions and 4 deletions

View File

@ -72,7 +72,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = {
SCHED_TASK(fifty_hz_loop, 50, 75, 3), SCHED_TASK(fifty_hz_loop, 50, 75, 3),
SCHED_TASK_CLASS(AP_GPS, &sub.gps, update, 50, 200, 6), SCHED_TASK_CLASS(AP_GPS, &sub.gps, update, 50, 200, 6),
#if AP_OPTICALFLOW_ENABLED #if AP_OPTICALFLOW_ENABLED
SCHED_TASK_CLASS(OpticalFlow, &sub.optflow, update, 200, 160, 9), SCHED_TASK_CLASS(AP_OpticalFlow, &sub.optflow, update, 200, 160, 9),
#endif #endif
SCHED_TASK(update_batt_compass, 10, 120, 12), SCHED_TASK(update_batt_compass, 10, 120, 12),
SCHED_TASK(read_rangefinder, 20, 100, 15), SCHED_TASK(read_rangefinder, 20, 100, 15),

View File

@ -57,7 +57,7 @@ void GCS_Sub::update_vehicle_sensor_status_flags()
} }
#if AP_OPTICALFLOW_ENABLED #if AP_OPTICALFLOW_ENABLED
const OpticalFlow *optflow = AP::opticalflow(); const AP_OpticalFlow *optflow = AP::opticalflow();
if (optflow && optflow->enabled()) { if (optflow && optflow->enabled()) {
control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW; control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW; control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;

View File

@ -596,7 +596,7 @@ const AP_Param::Info Sub::var_info[] = {
#if AP_OPTICALFLOW_ENABLED #if AP_OPTICALFLOW_ENABLED
// @Group: FLOW // @Group: FLOW
// @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp // @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp
GOBJECT(optflow, "FLOW", OpticalFlow), GOBJECT(optflow, "FLOW", AP_OpticalFlow),
#endif #endif
#if RPM_ENABLED == ENABLED #if RPM_ENABLED == ENABLED

View File

@ -163,7 +163,7 @@ private:
// Optical flow sensor // Optical flow sensor
#if AP_OPTICALFLOW_ENABLED #if AP_OPTICALFLOW_ENABLED
OpticalFlow optflow; AP_OpticalFlow optflow;
#endif #endif
// system time in milliseconds of last recorded yaw reset from ekf // system time in milliseconds of last recorded yaw reset from ekf