ACM Mavlink - fixed comparison of unsigned to signed int by casting to uint8_t

This commit is contained in:
Jason Short 2012-09-10 20:22:57 -07:00
parent 2fcc7d3b22
commit 63aec7510e
1 changed files with 1 additions and 1 deletions

View File

@ -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