AP_DroneCAN: cope with 16 bit limit on event timeout

use a smaller process() time while waiting for node startup
This commit is contained in:
Andrew Tridgell 2023-04-17 14:35:18 +10:00
parent 761297a068
commit 42192b2800
1 changed files with 9 additions and 3 deletions

View File

@ -312,9 +312,15 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters)
node_status_msg.sub_mode = 0;
// Spin node for device discovery
for (uint8_t i = 0; i < 5; i++) {
send_node_status();
canard_iface.process(1000);
uint32_t start_loop_ms = AP_HAL::millis();
uint32_t last_send_ms = 0;
while (AP_HAL::millis() - start_loop_ms < 5000) {
uint32_t now = AP_HAL::millis();
if (now - last_send_ms >= 1000) {
send_node_status();
last_send_ms = now;
}
canard_iface.process(50);
}
hal.util->snprintf(_thread_name, sizeof(_thread_name), "dronecan_%u", driver_index);