diff --git a/libraries/AP_CANManager/AP_CANDriver.h b/libraries/AP_CANManager/AP_CANDriver.h index f93e96cec0e7a..5f1c4f74a2a76 100644 --- a/libraries/AP_CANManager/AP_CANDriver.h +++ b/libraries/AP_CANManager/AP_CANDriver.h @@ -40,5 +40,5 @@ class AP_CANDriver virtual bool add_11bit_driver(CANSensor *sensor) { return false; } // handler for outgoing frames for auxillary drivers - virtual bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us) { return false; } + virtual bool write_aux_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us) { return false; } }; diff --git a/libraries/AP_CANManager/AP_CANSensor.cpp b/libraries/AP_CANManager/AP_CANSensor.cpp index e86ef31992475..ffa9bf3cc6d9f 100644 --- a/libraries/AP_CANManager/AP_CANSensor.cpp +++ b/libraries/AP_CANManager/AP_CANSensor.cpp @@ -135,7 +135,7 @@ bool CANSensor::add_interface(AP_HAL::CANIface* can_iface) return true; } -bool CANSensor::write_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us) +bool CANSensor::write_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us) { if (!_initialized) { debug_can(AP_CANManager::LOG_ERROR, "Driver not initialized for write_frame"); @@ -171,12 +171,12 @@ void CANSensor::loop() #endif while (true) { - uint64_t timeout = AP_HAL::micros64() + LOOP_INTERVAL_US; + uint64_t deadline_us = AP_HAL::micros64() + LOOP_INTERVAL_US; // wait to receive frame bool read_select = true; bool write_select = false; - bool ret = _can_iface->select(read_select, write_select, nullptr, timeout); + bool ret = _can_iface->select(read_select, write_select, nullptr, deadline_us); if (ret && read_select) { uint64_t time; AP_HAL::CANIface::CanIOFlags flags {}; diff --git a/libraries/AP_CANManager/AP_CANSensor.h b/libraries/AP_CANManager/AP_CANSensor.h index 7afd1bbea0fa5..b5ac4ee3b0b0f 100644 --- a/libraries/AP_CANManager/AP_CANSensor.h +++ b/libraries/AP_CANManager/AP_CANSensor.h @@ -43,7 +43,7 @@ class CANSensor : public AP_CANDriver { virtual void handle_frame(AP_HAL::CANFrame &frame) = 0; // handler for outgoing frames - bool write_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us); + bool write_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us); #ifdef HAL_BUILD_AP_PERIPH static void set_periph(const uint8_t i, const AP_CAN::Protocol protocol, AP_HAL::CANIface* iface) { diff --git a/libraries/AP_DroneCAN/AP_Canard_iface.cpp b/libraries/AP_DroneCAN/AP_Canard_iface.cpp index 7382f57033c9d..fd38e303c4253 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 43d786639fdf0..671722028dffc 100644 --- a/libraries/AP_DroneCAN/AP_Canard_iface.h +++ b/libraries/AP_DroneCAN/AP_Canard_iface.h @@ -54,7 +54,7 @@ class CanardInterface : public Canard::Interface { 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 21243e5d08c40..639e017e82cb6 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 2d6e5ae2b7f78..9a7ae54c6639c 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.h +++ b/libraries/AP_DroneCAN/AP_DroneCAN.h @@ -95,7 +95,7 @@ class AP_DroneCAN : public AP_CANDriver, public AP_ESC_Telem_Backend { 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; }