mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AP_Frsky_Telem: removed time constraint to allow SITL regression testing
This commit is contained in:
parent
6303c700d4
commit
13592cef91
@ -480,6 +480,7 @@ void AP_Frsky_Telem::send_sport_frame(uint8_t frame, uint16_t appid, uint32_t d
|
|||||||
buf2[len++] = c;
|
buf2[len++] = c;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#ifndef HAL_BOARD_SITL
|
||||||
/*
|
/*
|
||||||
check that we haven't been too slow in responding to the new
|
check that we haven't been too slow in responding to the new
|
||||||
UART data. If we respond too late then we will overwrite the next
|
UART data. If we respond too late then we will overwrite the next
|
||||||
@ -495,6 +496,7 @@ void AP_Frsky_Telem::send_sport_frame(uint8_t frame, uint16_t appid, uint32_t d
|
|||||||
// we've been too slow in responding
|
// we've been too slow in responding
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
_port->write(buf2, len);
|
_port->write(buf2, len);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user