ArduPlane: update_trigger() is now called in AP_Camera update()

This commit is contained in:
Mirko Denecke 2020-06-22 22:33:55 +02:00 committed by Randy Mackay
parent 6f0782abbf
commit 10a85892cf
1 changed files with 1 additions and 5 deletions

View File

@ -73,7 +73,7 @@ const AP_Scheduler::Task Plane::scheduler_tasks[] = {
SCHED_TASK_CLASS(AP_Mount, &plane.camera_mount, update, 50, 100),
#endif // MOUNT == ENABLED
#if CAMERA == ENABLED
SCHED_TASK_CLASS(AP_Camera, &plane.camera, update_trigger, 50, 100),
SCHED_TASK_CLASS(AP_Camera, &plane.camera, update, 50, 100),
#endif // CAMERA == ENABLED
SCHED_TASK_CLASS(AP_Scheduler, &plane.scheduler, update_logging, 0.2, 100),
SCHED_TASK(compass_save, 0.1, 200),
@ -394,10 +394,6 @@ void Plane::update_GPS_10Hz(void)
// see if we've breached the geo-fence
geofence_check(false);
#if CAMERA == ENABLED
camera.update();
#endif
// update wind estimate
ahrs.estimate_wind();
} else if (gps.status() < AP_GPS::GPS_OK_FIX_3D && ground_start_count != 0) {