AP_CANManager: use 32 bit timeout for write_aux_frame

Saves a handful of bytes. 71 minutes ought to be enough for anybody!
This commit is contained in:
Thomas Watson 2024-10-13 22:04:20 -05:00 committed by Andrew Tridgell
parent a4f6853a7b
commit 3dd8aa5304
1 changed files with 1 additions and 1 deletions

View File

@ -40,5 +40,5 @@ public:
virtual bool add_11bit_driver(CANSensor *sensor) { return false; } virtual bool add_11bit_driver(CANSensor *sensor) { return false; }
// handler for outgoing frames for auxillary drivers // 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; }
}; };