AP_CANManager: use 32 bit timeout for write_frame

Saves a few bytes. 71 minutes ought to be enough for anybody!
This commit is contained in:
Thomas Watson 2024-10-13 21:56:01 -05:00 committed by Andrew Tridgell
parent 4d75b44775
commit a4f6853a7b
2 changed files with 4 additions and 4 deletions

View File

@ -135,7 +135,7 @@ bool CANSensor::add_interface(AP_HAL::CANIface* can_iface)
return true;
}
bool CANSensor::write_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us)
bool CANSensor::write_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us)
{
if (!_initialized) {
debug_can(AP_CANManager::LOG_ERROR, "Driver not initialized for write_frame");
@ -171,12 +171,12 @@ void CANSensor::loop()
#endif
while (true) {
uint64_t timeout = AP_HAL::micros64() + LOOP_INTERVAL_US;
uint64_t deadline_us = AP_HAL::micros64() + LOOP_INTERVAL_US;
// wait to receive frame
bool read_select = true;
bool write_select = false;
bool ret = _can_iface->select(read_select, write_select, nullptr, timeout);
bool ret = _can_iface->select(read_select, write_select, nullptr, deadline_us);
if (ret && read_select) {
uint64_t time;
AP_HAL::CANIface::CanIOFlags flags {};

View File

@ -43,7 +43,7 @@ public:
virtual void handle_frame(AP_HAL::CANFrame &frame) = 0;
// handler for outgoing frames
bool write_frame(AP_HAL::CANFrame &out_frame, const uint64_t timeout_us);
bool write_frame(AP_HAL::CANFrame &out_frame, const uint32_t timeout_us);
#ifdef HAL_BUILD_AP_PERIPH
static void set_periph(const uint8_t i, const AP_CAN::Protocol protocol, AP_HAL::CANIface* iface) {