AP_DroneCAN: fix DroneCAN run for SITL

This commit is contained in:
bugobliterator 2023-04-17 21:33:56 +10:00 committed by Andrew Tridgell
parent 42192b2800
commit b1c4cf9923
2 changed files with 6 additions and 10 deletions

View File

@ -4,6 +4,8 @@
#if HAL_ENABLE_DRONECAN_DRIVERS
#include <canard/handler_list.h>
#include <canard/transfer_object.h>
#include <AP_Math/AP_Math.h>
extern const AP_HAL::HAL& hal;
#define LOG_TAG "DroneCANIface"
@ -274,7 +276,7 @@ void CanardInterface::process(uint32_t duration_ms) {
processTx();
uint64_t now = AP_HAL::native_micros64();
if (now < deadline) {
_event_handle.wait(deadline - now);
_event_handle.wait(MIN(UINT16_MAX - 2U, deadline - now));
} else {
break;
}

View File

@ -312,15 +312,9 @@ void AP_DroneCAN::init(uint8_t driver_index, bool enable_filters)
node_status_msg.sub_mode = 0;
// Spin node for device discovery
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);
for (uint8_t i = 0; i < 5; i++) {
send_node_status();
canard_iface.process(1000);
}
hal.util->snprintf(_thread_name, sizeof(_thread_name), "dronecan_%u", driver_index);