mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Mount_SToRM: remove message throttling
recent versions of gimbal firmware can handle 50hz update rate
This commit is contained in:
parent
b3362d5829
commit
2189b16165
@ -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;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user