ArduCopter: 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:14 +10:00 committed by Peter Barker
parent 35ab667e74
commit 78c742978e
4 changed files with 4 additions and 4 deletions

View File

@ -144,7 +144,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
SCHED_TASK(throttle_loop, 50, 75, 6), SCHED_TASK(throttle_loop, 50, 75, 6),
SCHED_TASK_CLASS(AP_GPS, &copter.gps, update, 50, 200, 9), SCHED_TASK_CLASS(AP_GPS, &copter.gps, update, 50, 200, 9),
#if AP_OPTICALFLOW_ENABLED #if AP_OPTICALFLOW_ENABLED
SCHED_TASK_CLASS(OpticalFlow, &copter.optflow, update, 200, 160, 12), SCHED_TASK_CLASS(AP_OpticalFlow, &copter.optflow, update, 200, 160, 12),
#endif #endif
SCHED_TASK(update_batt_compass, 10, 120, 15), SCHED_TASK(update_batt_compass, 10, 120, 15),
SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&copter.g2.rc_channels, read_aux_all, 10, 50, 18), SCHED_TASK_CLASS(RC_Channels, (RC_Channels*)&copter.g2.rc_channels, read_aux_all, 10, 50, 18),

View File

@ -310,7 +310,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

View File

@ -115,7 +115,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
#endif #endif
#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

@ -674,7 +674,7 @@ const AP_Param::Info Copter::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 PRECISION_LANDING == ENABLED #if PRECISION_LANDING == ENABLED