mirror of https://github.com/ArduPilot/ardupilot
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:
parent
a4f6853a7b
commit
3dd8aa5304
|
@ -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; }
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue