voxl_esc: Limit frequency of UART passthru writes to 20Hz

This commit is contained in:
Eric Katzfey 2025-03-04 13:50:45 -08:00 committed by Eric Katzfey
parent ecb222c7e7
commit 5e54d727fc
2 changed files with 15 additions and 8 deletions

View File

@ -1336,16 +1336,22 @@ bool VoxlEsc::updateOutputs(uint16_t outputs[MAX_ACTUATORS],
uint8_t num_writes = 0;
while (_esc_serial_passthru_sub.updated() && (num_writes < 4)) {
mavlink_tunnel_s uart_passthru{};
_esc_serial_passthru_sub.copy(&uart_passthru);
// Don't do these faster than 20Hz
if (hrt_elapsed_time(&_last_uart_passthru) > 50_ms) {
_last_uart_passthru = hrt_absolute_time();
if (_uart_port.write(uart_passthru.payload, uart_passthru.payload_length) != uart_passthru.payload_length) {
PX4_ERR("Failed to send mavlink tunnel data to esc");
return false;
// Don't do more than a few writes each check
while (_esc_serial_passthru_sub.updated() && (num_writes < 4)) {
mavlink_tunnel_s uart_passthru{};
_esc_serial_passthru_sub.copy(&uart_passthru);
if (_uart_port.write(uart_passthru.payload, uart_passthru.payload_length) != uart_passthru.payload_length) {
PX4_ERR("Failed to send mavlink tunnel data to esc");
return false;
}
num_writes++;
}
num_writes++;
}
perf_count(_output_update_perf);

View File

@ -257,6 +257,7 @@ private:
Battery _battery;
static constexpr unsigned _battery_report_interval{100_ms};
hrt_abstime _last_battery_report_time;
hrt_abstime _last_uart_passthru{0};
bool _device_initialized{false};