AP_PiccoloCAN: use 32 bit microsecond timeouts for connection funcs

For consistency with other parts of the code.
This commit is contained in:
Thomas Watson 2024-10-08 23:15:44 -05:00 committed by Andrew Tridgell
parent baf41ae92e
commit 55c5cb10d0
3 changed files with 8 additions and 8 deletions

View File

@ -687,26 +687,26 @@ bool AP_PiccoloCAN::is_esc_channel_active(uint8_t chan)
/**
* Determine if a servo is present on the CAN bus (has telemetry data been received)
*/
bool AP_PiccoloCAN::is_servo_present(uint8_t chan, uint64_t timeout_ms)
bool AP_PiccoloCAN::is_servo_present(uint8_t chan, uint32_t timeout_us)
{
if (chan >= PICCOLO_CAN_MAX_NUM_SERVO) {
return false;
}
return _servos[chan].is_connected(timeout_ms);
return _servos[chan].is_connected(timeout_us);
}
/**
* Determine if an ESC is present on the CAN bus (has telemetry data been received)
*/
bool AP_PiccoloCAN::is_esc_present(uint8_t chan, uint64_t timeout_ms)
bool AP_PiccoloCAN::is_esc_present(uint8_t chan, uint32_t timeout_us)
{
if (chan >= PICCOLO_CAN_MAX_NUM_ESC) {
return false;
}
return _escs[chan].is_connected(timeout_ms);
return _escs[chan].is_connected(timeout_us);
}

View File

@ -63,10 +63,10 @@ public:
bool is_esc_channel_active(uint8_t chan);
// return true if a particular servo has been detected on the CAN interface
bool is_servo_present(uint8_t chan, uint64_t timeout_ms = 2000);
bool is_servo_present(uint8_t chan, uint32_t timeout_us = 2000000);
// return true if a particular ESC has been detected on the CAN interface
bool is_esc_present(uint8_t chan, uint64_t timeout_ms = 2000);
bool is_esc_present(uint8_t chan, uint32_t timeout_us = 2000000);
// return true if a particular servo is enabled
bool is_servo_enabled(uint8_t chan);

View File

@ -58,10 +58,10 @@ public:
virtual bool is_enabled(void) const { return false; }
// Determine if this device has been seen within a specified timeframe
virtual bool is_connected(int64_t timeout_ms) const {
virtual bool is_connected(uint32_t timeout_us) const {
uint64_t now = AP_HAL::micros64();
return now < (last_msg_timestamp + (1000ULL * timeout_ms));
return now < (last_msg_timestamp + timeout_us);
}
// Reset the received message timestamp