diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index e1503da36a..66316d0c64 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -166,7 +166,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { #if RPM_ENABLED == ENABLED SCHED_TASK(rpm_update, 40, 200), #endif - SCHED_TASK(compass_cal_update, 100, 100), + SCHED_TASK_CLASS(Compass, &copter.compass, cal_update, 100, 100), SCHED_TASK(accel_cal_update, 10, 100), SCHED_TASK_CLASS(AP_TempCalibration, &copter.g2.temp_calibration, update, 10, 100), #if HAL_ADSB_ENABLED diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index e9764a0e92..24617a8925 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -864,7 +864,6 @@ private: bool rangefinder_up_ok() const; void rpm_update(); void update_optical_flow(void); - void compass_cal_update(void); void accel_cal_update(void); void init_proximity(); void update_proximity(); diff --git a/ArduCopter/sensors.cpp b/ArduCopter/sensors.cpp index 769838d275..243d0cb981 100644 --- a/ArduCopter/sensors.cpp +++ b/ArduCopter/sensors.cpp @@ -162,35 +162,6 @@ void Copter::rpm_update(void) #endif } -void Copter::compass_cal_update() -{ - compass.cal_update(); - - if (hal.util->get_soft_armed()) { - return; - } - - static uint32_t compass_cal_stick_gesture_begin = 0; - - if (compass.is_calibrating()) { - if (channel_yaw->get_control_in() < -4000 && channel_throttle->get_control_in() > 900) { - compass.cancel_calibration_all(); - } - } else { - bool stick_gesture_detected = compass_cal_stick_gesture_begin != 0 && !motors->armed() && channel_yaw->get_control_in() > 4000 && channel_throttle->get_control_in() > 900; - uint32_t tnow = millis(); - - if (!stick_gesture_detected) { - compass_cal_stick_gesture_begin = tnow; - } else if (tnow-compass_cal_stick_gesture_begin > 1000*COMPASS_CAL_STICK_GESTURE_TIME) { -#ifdef CAL_ALWAYS_REBOOT - compass.start_calibration_all(true,true,COMPASS_CAL_STICK_DELAY,true); -#else - compass.start_calibration_all(true,true,COMPASS_CAL_STICK_DELAY,false); -#endif - } - } -} void Copter::accel_cal_update() {