From 2189b16165d6042f3d4eb8d9807862d32c8892ef Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 21 Mar 2015 05:54:23 +0900 Subject: [PATCH] Mount_SToRM: remove message throttling recent versions of gimbal firmware can handle 50hz update rate --- libraries/AP_Mount/AP_Mount_SToRM32.cpp | 8 -------- 1 file changed, 8 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount_SToRM32.cpp b/libraries/AP_Mount/AP_Mount_SToRM32.cpp index 2b1c8b36ce..38d4decc58 100644 --- a/libraries/AP_Mount/AP_Mount_SToRM32.cpp +++ b/libraries/AP_Mount/AP_Mount_SToRM32.cpp @@ -31,14 +31,6 @@ void AP_Mount_SToRM32::update() return; } - // throttle updates to 10hz (this assumes update is called at 50hz) - static uint8_t counter = 0; - counter++; - if (counter < 5) { - return; - } - counter = 0; - // flag to trigger sending target angles to gimbal bool resend_now = false;