Mount_SToRM: remove message throttling

recent versions of gimbal firmware can handle 50hz update rate
This commit is contained in:
Randy Mackay 2015-03-21 05:54:23 +09:00
parent b3362d5829
commit 2189b16165

View File

@ -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;