From 8b5f5a5fa04e64e2bb699f172c14c860d3b7a6d4 Mon Sep 17 00:00:00 2001 From: kozinalexey Date: Sat, 17 Mar 2018 08:31:03 +0300 Subject: [PATCH] Copter: fix camera relay trigger camera.update() for automatic shots always called from void Copter::update_GPS(void), after gps read copter specific bug --- ArduCopter/ArduCopter.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index 696595d213..29261e67d2 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -141,7 +141,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_Mount, &copter.camera_mount, update, 50, 75), #endif #if CAMERA == ENABLED - SCHED_TASK_CLASS(AP_Camera, &copter.camera, update, 50, 75), + SCHED_TASK_CLASS(AP_Camera, &copter.camera, update_trigger, 50, 75), #endif #if LOGGING_ENABLED == ENABLED SCHED_TASK(ten_hz_logging_loop, 10, 350),