From 0f4367744f7a02eee4949f81bf7a56b4e2beccbd Mon Sep 17 00:00:00 2001 From: Jonathan Challinger Date: Tue, 5 Jul 2016 14:48:59 -0700 Subject: [PATCH] Copter: update precland at 400hz, log at 25hz --- ArduCopter/ArduCopter.cpp | 7 ++++++- ArduCopter/precision_landing.cpp | 3 --- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/ArduCopter/ArduCopter.cpp b/ArduCopter/ArduCopter.cpp index 02dc356612..f25f79adfb 100644 --- a/ArduCopter/ArduCopter.cpp +++ b/ArduCopter/ArduCopter.cpp @@ -102,7 +102,7 @@ const AP_Scheduler::Task Copter::scheduler_tasks[] = { SCHED_TASK(compass_accumulate, 100, 100), SCHED_TASK(barometer_accumulate, 50, 90), #if PRECISION_LANDING == ENABLED - SCHED_TASK(update_precland, 50, 50), + SCHED_TASK(update_precland, 400, 50), #endif #if FRAME_CONFIG == HELI_FRAME SCHED_TASK(check_dynamic_flight, 50, 75), @@ -428,6 +428,11 @@ void Copter::twentyfive_hz_logging() DataFlash.Log_Write_IMU(ins); } #endif + +#if PRECISION_LANDING == ENABLED + // log output + Log_Write_Precland(); +#endif } void Copter::dataflash_periodic(void) diff --git a/ArduCopter/precision_landing.cpp b/ArduCopter/precision_landing.cpp index 4b4592ad05..10fb230635 100644 --- a/ArduCopter/precision_landing.cpp +++ b/ArduCopter/precision_landing.cpp @@ -23,8 +23,5 @@ void Copter::update_precland() } copter.precland.update(final_alt); - - // log output - Log_Write_Precland(); } #endif