mirror of https://github.com/ArduPilot/ardupilot
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:
parent
35ab667e74
commit
78c742978e
|
@ -144,7 +144,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = {
|
|||
SCHED_TASK(throttle_loop, 50, 75, 6),
|
||||
SCHED_TASK_CLASS(AP_GPS, &copter.gps, update, 50, 200, 9),
|
||||
#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
|
||||
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),
|
||||
|
|
|
@ -310,7 +310,7 @@ private:
|
|||
|
||||
// Optical flow sensor
|
||||
#if AP_OPTICALFLOW_ENABLED
|
||||
OpticalFlow optflow;
|
||||
AP_OpticalFlow optflow;
|
||||
#endif
|
||||
|
||||
// system time in milliseconds of last recorded yaw reset from ekf
|
||||
|
|
|
@ -115,7 +115,7 @@ void GCS_Copter::update_vehicle_sensor_status_flags(void)
|
|||
#endif
|
||||
|
||||
#if AP_OPTICALFLOW_ENABLED
|
||||
const OpticalFlow *optflow = AP::opticalflow();
|
||||
const AP_OpticalFlow *optflow = AP::opticalflow();
|
||||
if (optflow && optflow->enabled()) {
|
||||
control_sensors_present |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW;
|
||||
|
|
|
@ -674,7 +674,7 @@ const AP_Param::Info Copter::var_info[] = {
|
|||
#if AP_OPTICALFLOW_ENABLED
|
||||
// @Group: FLOW
|
||||
// @Path: ../libraries/AP_OpticalFlow/AP_OpticalFlow.cpp
|
||||
GOBJECT(optflow, "FLOW", OpticalFlow),
|
||||
GOBJECT(optflow, "FLOW", AP_OpticalFlow),
|
||||
#endif
|
||||
|
||||
#if PRECISION_LANDING == ENABLED
|
||||
|
|
Loading…
Reference in New Issue