From 09276e744db7964f341f4a9986fa8a83b92fd27f Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Sun, 13 Oct 2024 22:04:20 -0500 Subject: [PATCH] AP_DroneCAN: use 32 bit timeout for write_aux_frame Saves a handful of bytes. 71 minutes ought to be enough for anybody! --- libraries/AP_DroneCAN/AP_Canard_iface.cpp | 2 +- libraries/AP_DroneCAN/AP_Canard_iface.h | 2 +- libraries/AP_DroneCAN/AP_DroneCAN.cpp | 2 +- libraries/AP_DroneCAN/AP_DroneCAN.h | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/libraries/AP_DroneCAN/AP_Canard_iface.cpp b/libraries/AP_DroneCAN/AP_Canard_iface.cpp index 7382f57033c9de..fd38e303c42535 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 43d786639fdf05..671722028dffc7 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 59174a778b7feb..a1aed61285611f 100644 --- a/libraries/AP_DroneCAN/AP_DroneCAN.cpp +++ b/libraries/AP_DroneCAN/AP_DroneCAN.cpp @@ -1900,7 +1900,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 7264fad9472fcd..c465bcf3918778 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; }