From 1db0feea59bfc7b531fff957d7eed4ff00b1dfb7 Mon Sep 17 00:00:00 2001 From: Mirko Denecke Date: Mon, 22 Jun 2020 22:34:34 +0200 Subject: [PATCH] ArduSub: update_trigger() is now called in AP_Camera update() --- ArduSub/ArduSub.cpp | 28 ++-------------------------- ArduSub/Sub.h | 1 - 2 files changed, 2 insertions(+), 27 deletions(-) diff --git a/ArduSub/ArduSub.cpp b/ArduSub/ArduSub.cpp index e3f73a21ac..ba455bdff3 100644 --- a/ArduSub/ArduSub.cpp +++ b/ArduSub/ArduSub.cpp @@ -26,7 +26,7 @@ */ const AP_Scheduler::Task Sub::scheduler_tasks[] = { SCHED_TASK(fifty_hz_loop, 50, 75), - SCHED_TASK(update_GPS, 50, 200), + SCHED_TASK_CLASS(AP_GPS, &sub.gps, update, 50, 200), #if OPTFLOW == ENABLED SCHED_TASK_CLASS(OpticalFlow, &sub.optflow, update, 200, 160), #endif @@ -47,7 +47,7 @@ const AP_Scheduler::Task Sub::scheduler_tasks[] = { SCHED_TASK_CLASS(AP_Mount, &sub.camera_mount, update, 50, 75), #endif #if CAMERA == ENABLED - SCHED_TASK_CLASS(AP_Camera, &sub.camera, update_trigger, 50, 75), + SCHED_TASK_CLASS(AP_Camera, &sub.camera, update, 50, 75), #endif SCHED_TASK(ten_hz_logging_loop, 10, 350), SCHED_TASK(twentyfive_hz_logging, 25, 110), @@ -286,30 +286,6 @@ void Sub::one_hz_loop() set_likely_flying(hal.util->get_soft_armed()); } -// called at 50hz -void Sub::update_GPS() -{ - static uint32_t last_gps_reading[GPS_MAX_INSTANCES]; // time of last gps message - bool gps_updated = false; - - gps.update(); - - // log after every gps message - for (uint8_t i=0; i