From 89d423556c2663e2d9da10f0a7d4ff5dff613e40 Mon Sep 17 00:00:00 2001 From: Mirko Denecke Date: Mon, 22 Jun 2020 22:34:15 +0200 Subject: [PATCH] ArduCopter: update_trigger() is now called in AP_Camera update() --- ArduCopter/Copter.cpp | 28 ++-------------------------- ArduCopter/Copter.h | 1 - 2 files changed, 2 insertions(+), 27 deletions(-) diff --git a/ArduCopter/Copter.cpp b/ArduCopter/Copter.cpp index e6395c76c3..9fde684cf3 100644 --- a/ArduCopter/Copter.cpp +++ b/ArduCopter/Copter.cpp @@ -91,7 +91,7 @@ const AP_HAL::HAL& hal = AP_HAL::get_HAL(); const AP_Scheduler::Task Copter::scheduler_tasks[] = { SCHED_TASK(rc_loop, 100, 130), SCHED_TASK(throttle_loop, 50, 75), - SCHED_TASK(update_GPS, 50, 200), + SCHED_TASK_CLASS(AP_GPS, &copter.gps, update, 50, 200), #if OPTFLOW == ENABLED SCHED_TASK_CLASS(OpticalFlow, &copter.optflow, update, 200, 160), #endif @@ -150,7 +150,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_trigger, 50, 75), + SCHED_TASK_CLASS(AP_Camera, &copter.camera, update, 50, 75), #endif #if LOGGING_ENABLED == ENABLED SCHED_TASK(ten_hz_logging_loop, 10, 350), @@ -515,30 +515,6 @@ void Copter::one_hz_loop() AP_Notify::flags.flying = !ap.land_complete; } -// called at 50hz -void Copter::update_GPS(void) -{ - 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