From 3dd8aa53047769f9d434cbea3cd5caf479ed2d6b Mon Sep 17 00:00:00 2001 From: Thomas Watson Date: Sun, 13 Oct 2024 22:04:20 -0500 Subject: [PATCH] AP_CANManager: use 32 bit timeout for write_aux_frame Saves a handful of bytes. 71 minutes ought to be enough for anybody! --- libraries/AP_CANManager/AP_CANDriver.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_CANManager/AP_CANDriver.h b/libraries/AP_CANManager/AP_CANDriver.h index f93e96cec0..5f1c4f74a2 100644 --- a/libraries/AP_CANManager/AP_CANDriver.h +++ b/libraries/AP_CANManager/AP_CANDriver.h @@ -40,5 +40,5 @@ public: 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; } };