diff --git a/libraries/AP_DroneCAN/AP_Canard_iface.cpp b/libraries/AP_DroneCAN/AP_Canard_iface.cpp index 7382f57033..fd38e303c4 100644 --- a/libraries/AP_DroneCAN/AP_Canard_iface.cpp +++ b/libraries/AP_DroneCAN/AP_Canard_iface.cpp @@ -456,7 +456,7 @@ bool CanardInterface::add_11bit_driver(CANSensor *sensor) } // handler for outgoing frames for auxillary drivers -bool CanardInterface::write_aux_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us) +bool CanardInterface::write_aux_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us) { const uint64_t tx_deadline_us = AP_HAL::micros64() + timeout_us; bool ret = false; diff --git a/libraries/AP_DroneCAN/AP_Canard_iface.h b/libraries/AP_DroneCAN/AP_Canard_iface.h index 43d786639f..671722028d 100644 --- a/libraries/AP_DroneCAN/AP_Canard_iface.h +++ b/libraries/AP_DroneCAN/AP_Canard_iface.h @@ -54,7 +54,7 @@ public: bool add_11bit_driver(CANSensor *sensor); // handler for outgoing frames for auxillary drivers - bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us); + bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us); #if AP_TEST_DRONECAN_DRIVERS static CanardInterface& get_test_iface() { return test_iface; } diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.cpp b/libraries/AP_DroneCAN/AP_DroneCAN.cpp index 21243e5d08..639e017e82 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -1956,7 +1956,7 @@ bool AP_DroneCAN::add_11bit_driver(CANSensor *sensor) } // handler for outgoing frames for auxillary drivers -bool AP_DroneCAN::write_aux_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us) +bool AP_DroneCAN::write_aux_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us) { if (out_frame.isExtended()) { // don't allow extended frames to be sent by auxillary driver diff --git a/libraries/AP_DroneCAN/AP_DroneCAN.h b/libraries/AP_DroneCAN/AP_DroneCAN.h index 2d6e5ae2b7..9a7ae54c66 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.h +++ b/libraries/AP_DroneCAN/AP_DroneCAN.h @@ -95,7 +95,7 @@ public: bool add_11bit_driver(CANSensor *sensor) override; // handler for outgoing frames for auxillary drivers - bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us) override; + bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us) override; uint8_t get_driver_index() const { return _driver_index; }