AP_DroneCAN: 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 3dd8aa5304
commit 7ca558f625
4 changed files with 4 additions and 4 deletions

View File

@ -456,7 +456,7 @@ bool CanardInterface::add_11bit_driver(CANSensor *sensor)
} }
// handler for outgoing frames for auxillary drivers // 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; const uint64_t tx_deadline_us = AP_HAL::micros64() + timeout_us;
bool ret = false; bool ret = false;

View File

@ -54,7 +54,7 @@ public:
bool add_11bit_driver(CANSensor *sensor); bool add_11bit_driver(CANSensor *sensor);
// handler for outgoing frames for auxillary drivers // 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 #if AP_TEST_DRONECAN_DRIVERS
static CanardInterface& get_test_iface() { return test_iface; } static CanardInterface& get_test_iface() { return test_iface; }

View File

@ -1956,7 +1956,7 @@ bool AP_DroneCAN::add_11bit_driver(CANSensor *sensor)
} }
// handler for outgoing frames for auxillary drivers // 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()) { if (out_frame.isExtended()) {
// don't allow extended frames to be sent by auxillary driver // don't allow extended frames to be sent by auxillary driver

View File

@ -95,7 +95,7 @@ public:
bool add_11bit_driver(CANSensor *sensor) override; bool add_11bit_driver(CANSensor *sensor) override;
// handler for outgoing frames for auxillary drivers // 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; } uint8_t get_driver_index() const { return _driver_index; }