mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 10:28:29 -04:00
ACM Mavlink - fixed comparison of unsigned to signed int by casting to uint8_t
This commit is contained in:
parent
2fcc7d3b22
commit
63aec7510e
@ -468,7 +468,7 @@ static void NOINLINE send_statustext(mavlink_channel_t chan)
|
||||
static bool telemetry_delayed(mavlink_channel_t chan)
|
||||
{
|
||||
uint32_t tnow = millis() >> 10;
|
||||
if (tnow > g.telem_delay) {
|
||||
if (tnow > (uint8_t)g.telem_delay) {
|
||||
return false;
|
||||
}
|
||||
#if USB_MUX_PIN > 0
|
||||
|
Loading…
Reference in New Issue
Block a user