AP_Periph: always limit rangefinder update rate to given max rate

This commit is contained in:
Iampete1 2024-05-06 18:53:09 +01:00 committed by Andrew Tridgell
parent 13cbffebcc
commit bcf0733ea9
1 changed files with 1 additions and 1 deletions

View File

@ -39,6 +39,7 @@ void AP_Periph_FW::can_rangefinder_update(void)
// limit to max rate
return;
}
last_rangefinder_update_ms = now;
// update all rangefinder instances
rangefinder.update();
@ -114,7 +115,6 @@ void AP_Periph_FW::can_rangefinder_update(void)
&buffer[0],
total_size);
last_rangefinder_update_ms = now;
}
}